Class SwerveModulePhysicalCharacteristics

java.lang.Object
swervelib.parser.SwerveModulePhysicalCharacteristics

public class SwerveModulePhysicalCharacteristics extends Object
Configuration class which stores physical characteristics shared between every swerve module.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final int
    Angle motor encoder pulse per rotation.
    final double
    Angle gear ratio.
    final int
    Current limits for the Swerve Module.
    final double
    Free speed rotations per minute of the motor, as described by the vendor.
    final double
    Angle motor kV used for second order kinematics to tune the feedforward, this variable should be adjusted so that your drive train does not drift towards the direction you are rotating while you translate.
    final double
    The time it takes for the motor to go from 0 to full throttle in seconds.
    final int
    Drive motor encoder pulse per rotation.
    final double
    Drive gear ratio.
    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.
    final double
    Optimal voltage of the robot.
    final double
    Wheel diameter in meters.
    final double
    Wheel grip tape coefficient of friction on carpet, as described by the vendor.
  • Constructor Summary

    Constructors
    Constructor
    Description
    SwerveModulePhysicalCharacteristics(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, double angleMotorKV)
    Construct the swerve module physical characteristics.
  • Method Summary

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • wheelDiameter

      public final double wheelDiameter
      Wheel diameter in meters.
    • driveGearRatio

      public final double driveGearRatio
      Drive gear ratio. How many times the motor has to spin before the wheel makes a complete rotation.
    • angleGearRatio

      public final double angleGearRatio
      Angle gear ratio. How many times the motor has to spin before the wheel makes a full rotation.
    • driveEncoderPulsePerRotation

      public final int driveEncoderPulsePerRotation
      Drive motor encoder pulse per rotation. 1 if integrated encoder.
    • angleEncoderPulsePerRotation

      public final int angleEncoderPulsePerRotation
      Angle motor encoder pulse per rotation. 1 for Neo encoder. 2048 for Falcons.
    • optimalVoltage

      public final double optimalVoltage
      Optimal voltage of the robot.
    • driveMotorCurrentLimit

      public final int driveMotorCurrentLimit
      Current limits for the Swerve Module.
    • angleMotorCurrentLimit

      public final int angleMotorCurrentLimit
      Current limits for the Swerve Module.
    • driveMotorRampRate

      public final double driveMotorRampRate
      The time it takes for the motor to go from 0 to full throttle in seconds.
    • angleMotorRampRate

      public final double angleMotorRampRate
      The time it takes for the motor to go from 0 to full throttle in seconds.
    • wheelGripCoefficientOfFriction

      public final double wheelGripCoefficientOfFriction
      Wheel grip tape coefficient of friction on carpet, as described by the vendor.
    • angleMotorFreeSpeedRPM

      public final double angleMotorFreeSpeedRPM
      Free speed rotations per minute of the motor, as described by the vendor.
    • angleMotorKV

      public final double angleMotorKV
      Angle motor kV used for second order kinematics to tune the feedforward, this variable should be adjusted so that your drive train does not drift towards the direction you are rotating while you translate. When set to 0 the calculated kV will be used.
  • 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, double angleMotorKV)
      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.