Package swervelib.parser
Class SwerveModulePhysicalCharacteristics
java.lang.Object
swervelib.parser.SwerveModulePhysicalCharacteristics
Configuration class which stores physical characteristics shared between every swerve module.
-
Field Summary
Modifier and TypeFieldDescriptionfinal double
The minimum voltage to spin the module or wheel.final int
Current limits for the Swerve Module.final double
The time it takes for the motor to go from 0 to full throttle in seconds.The conversion factors for the drive and angle motors, created bySwerveMath.calculateMetersPerRotation(double, double, double)
andSwerveMath.calculateDegreesPerSteeringRotation(double, double)
.final double
The minimum voltage to spin the module or wheel.final int
Current limits for the Swerve Module.final double
The time it takes for the motor to go from 0 to full throttle in seconds.double
The voltage to use for the smart motor voltage compensation.final double
Robot mass in Kilograms.final double
Steer rotational inertia in (KilogramSquareMeters) kg/m_sq.final double
Wheel grip tape coefficient of friction on carpet, as described by the vendor. -
Constructor Summary
ConstructorDescriptionSwerveModulePhysicalCharacteristics
(ConversionFactorsJson conversionFactors, double driveMotorRampRate, double angleMotorRampRate) Construct the swerve module physical characteristics.SwerveModulePhysicalCharacteristics
(ConversionFactorsJson conversionFactors, double wheelGripCoefficientOfFriction, double optimalVoltage, int driveMotorCurrentLimit, int angleMotorCurrentLimit, double driveMotorRampRate, double angleMotorRampRate, double driveFrictionVoltage, double angleFrictionVoltage, double steerRotationalInertia, double robotMassKg) Construct the swerve module physical characteristics. -
Method Summary
-
Field Details
-
driveMotorCurrentLimit
public final int driveMotorCurrentLimitCurrent limits for the Swerve Module. -
angleMotorCurrentLimit
public final int angleMotorCurrentLimitCurrent limits for the Swerve Module. -
driveMotorRampRate
public final double driveMotorRampRateThe time it takes for the motor to go from 0 to full throttle in seconds. -
angleMotorRampRate
public final double angleMotorRampRateThe time it takes for the motor to go from 0 to full throttle in seconds. -
driveFrictionVoltage
public final double driveFrictionVoltageThe minimum voltage to spin the module or wheel. -
angleFrictionVoltage
public final double angleFrictionVoltageThe minimum voltage to spin the module or wheel. -
wheelGripCoefficientOfFriction
public final double wheelGripCoefficientOfFrictionWheel grip tape coefficient of friction on carpet, as described by the vendor. -
steerRotationalInertia
public final double steerRotationalInertiaSteer rotational inertia in (KilogramSquareMeters) kg/m_sq. -
robotMassKg
public final double robotMassKgRobot mass in Kilograms. -
optimalVoltage
public double optimalVoltageThe voltage to use for the smart motor voltage compensation. -
conversionFactor
The conversion factors for the drive and angle motors, created bySwerveMath.calculateMetersPerRotation(double, double, double)
andSwerveMath.calculateDegreesPerSteeringRotation(double, double)
.
-
-
Constructor Details
-
SwerveModulePhysicalCharacteristics
public SwerveModulePhysicalCharacteristics(ConversionFactorsJson conversionFactors, double wheelGripCoefficientOfFriction, double optimalVoltage, int driveMotorCurrentLimit, int angleMotorCurrentLimit, double driveMotorRampRate, double angleMotorRampRate, double driveFrictionVoltage, double angleFrictionVoltage, double steerRotationalInertia, double robotMassKg) Construct the swerve module physical characteristics.- Parameters:
conversionFactors
- The conversion factors for the drive and angle motors, created bySwerveMath.calculateMetersPerRotation(double, double, double)
andSwerveMath.calculateDegreesPerSteeringRotation(double, double)
.wheelGripCoefficientOfFriction
- Wheel grip coefficient of friction on carpet given by manufacturer.optimalVoltage
- Optimal robot voltage.driveMotorCurrentLimit
- Current limit for the drive motor.angleMotorCurrentLimit
- Current limit for the angle motor.driveMotorRampRate
- The time in seconds to go from 0 to full throttle on the motor. (Prevents over drawing power from battery)angleMotorRampRate
- The time in seconds to go from 0 to full throttle on the motor. (Prevents overdrawing power and power loss).angleFrictionVoltage
- Angle motor minimum voltage.driveFrictionVoltage
- Drive motor minimum voltage.steerRotationalInertia
- Steering rotational inertia in KilogramSquareMeters.robotMassKg
- Robot mass in kG.
-
SwerveModulePhysicalCharacteristics
public SwerveModulePhysicalCharacteristics(ConversionFactorsJson conversionFactors, double driveMotorRampRate, double angleMotorRampRate) Construct the swerve module physical characteristics. Assume coefficient of friction is 1.19 (taken from blue nitrile on carpet from Studica) and optimal voltage is 12v. Assumes the drive motor current limit is 40A, and the angle motor current limit is 20A.- Parameters:
conversionFactors
- The conversion factors for the drive and angle motors, created bySwerveMath.calculateMetersPerRotation(double, double, double)
andSwerveMath.calculateDegreesPerSteeringRotation(double, double)
.driveMotorRampRate
- The time in seconds to go from 0 to full throttle on the motor. (Prevents over drawing power from battery)angleMotorRampRate
- The time in seconds to go from 0 to full throttle on the motor. (Prevents overdrawing power and power loss).
-