Package swervelib.parser
Class SwerveModulePhysicalCharacteristics
java.lang.Object
swervelib.parser.SwerveModulePhysicalCharacteristics
Configuration class which stores physical characteristics shared between every swerve module.
-
Field Summary
FieldsModifier and TypeFieldDescriptionfinal intAngle motor encoder pulse per rotation.final doubleAngle gear ratio.final intCurrent limits for the Swerve Module.final doubleFree speed rotations per minute of the motor, as described by the vendor.final doubleThe time it takes for the motor to go from 0 to full throttle in seconds.final intDrive motor encoder pulse per rotation.final doubleDrive gear ratio.final intCurrent limits for the Swerve Module.final doubleThe time it takes for the motor to go from 0 to full throttle in seconds.final doubleOptimal voltage of the robot.final doubleWheel diameter in meters.final doubleWheel grip tape coefficient of friction on carpet, as described by the vendor. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModulePhysicalCharacteristics(double driveGearRatio, double angleGearRatio, double angleMotorFreeSpeedRPM, double wheelDiameter, double driveMotorRampRate, double angleMotorRampRate, int driveEncoderPulsePerRotation, int angleEncoderPulsePerRotation) Construct the swerve module physical characteristics.SwerveModulePhysicalCharacteristics(double driveGearRatio, double angleGearRatio, double angleMotorFreeSpeedRPM, double wheelDiameter, double wheelGripCoefficientOfFriction, double optimalVoltage, int driveMotorCurrentLimit, int angleMotorCurrentLimit, double driveMotorRampRate, double angleMotorRampRate, int driveEncoderPulsePerRotation, int angleEncoderPulsePerRotation) Construct the swerve module physical characteristics. -
Method Summary
-
Field Details
-
wheelDiameter
public final double wheelDiameterWheel diameter in meters. -
driveGearRatio
public final double driveGearRatioDrive gear ratio. How many times the motor has to spin before the wheel makes a complete rotation. -
angleGearRatio
public final double angleGearRatioAngle gear ratio. How many times the motor has to spin before the wheel makes a full rotation. -
driveEncoderPulsePerRotation
public final int driveEncoderPulsePerRotationDrive motor encoder pulse per rotation. 1 if integrated encoder. -
angleEncoderPulsePerRotation
public final int angleEncoderPulsePerRotationAngle motor encoder pulse per rotation. 1 if integrated encoder. -
optimalVoltage
public final double optimalVoltageOptimal voltage of the robot. -
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. -
wheelGripCoefficientOfFriction
public final double wheelGripCoefficientOfFrictionWheel grip tape coefficient of friction on carpet, as described by the vendor. -
angleMotorFreeSpeedRPM
public final double angleMotorFreeSpeedRPMFree speed rotations per minute of the motor, as described by the vendor.
-
-
Constructor Details
-
SwerveModulePhysicalCharacteristics
public SwerveModulePhysicalCharacteristics(double driveGearRatio, double angleGearRatio, double angleMotorFreeSpeedRPM, double wheelDiameter, double wheelGripCoefficientOfFriction, double optimalVoltage, int driveMotorCurrentLimit, int angleMotorCurrentLimit, double driveMotorRampRate, double angleMotorRampRate, int driveEncoderPulsePerRotation, int angleEncoderPulsePerRotation) Construct the swerve module physical characteristics.- Parameters:
driveGearRatio- Gear ratio of the drive motor. Number of motor rotations to rotate the wheel.angleGearRatio- Gear ratio of the angle motor. Number of motor rotations to spin the wheel.angleMotorFreeSpeedRPM- Motor free speed rotation per minute.wheelDiameter- Wheel diameter in meters.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).driveEncoderPulsePerRotation- The number of encoder pulses per motor rotation, 1 for integrated encoders.angleEncoderPulsePerRotation- The number of encoder pulses per motor rotation, 1 for integrated encoders.
-
SwerveModulePhysicalCharacteristics
public SwerveModulePhysicalCharacteristics(double driveGearRatio, double angleGearRatio, double angleMotorFreeSpeedRPM, double wheelDiameter, double driveMotorRampRate, double angleMotorRampRate, int driveEncoderPulsePerRotation, int angleEncoderPulsePerRotation) 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:
driveGearRatio- Gear ratio of the drive motor. Number of motor rotations to rotate the wheel.angleGearRatio- Gear ratio of the angle motor. Number of motor rotations to spin the wheel.angleMotorFreeSpeedRPM- Motor free speed rotation per minute.wheelDiameter- Wheel diameter in meters.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).driveEncoderPulsePerRotation- The number of encoder pulses per motor rotation, 1 for integrated encoders.angleEncoderPulsePerRotation- The number of encoder pulses per motor rotation, 1 for integrated encoders.
-