Class SwerveModuleSimulation

java.lang.Object
org.ironmaple.simulation.drivesims.SwerveModuleSimulation

public class SwerveModuleSimulation extends Object

Simulation for a Single Swerve Module.

Check Online Documentation

This class provides a simulation for a single swerve module in the SwerveDriveSimulation.

1. Purpose

This class serves as the bridge between your code and the physics engine.

You will apply voltage outputs to the drive/steer motor of the module and obtain their encoder readings in your code, just as how you deal with your physical motors.

2. Perspectives

  • Simulates the steering mechanism using a custom brushless motor simulator.
  • Simulates the propelling force generated by the driving motor, with a current limit.
  • Simulates encoder readings, which can be used to simulate a SwerveDriveOdometry.

3. Simulating Odometry

An example of how to simulate odometry using this class is the ModuleIOSim.java from the Advanced Swerve Drive with maple-sim example.

  • Field Details

    • driveMotorConfigs

      public final SimMotorConfigs driveMotorConfigs
    • DRIVE_GEAR_RATIO

      public final double DRIVE_GEAR_RATIO
    • STEER_GEAR_RATIO

      public final double STEER_GEAR_RATIO
    • WHEELS_COEFFICIENT_OF_FRICTION

      public final double WHEELS_COEFFICIENT_OF_FRICTION
    • DRIVE_FRICTION_VOLTAGE

      public final edu.wpi.first.units.measure.Voltage DRIVE_FRICTION_VOLTAGE
    • WHEEL_RADIUS

      public final edu.wpi.first.units.measure.Distance WHEEL_RADIUS
  • Constructor Details

    • SwerveModuleSimulation

      public SwerveModuleSimulation(DCMotor driveMotorModel, DCMotor steerMotorModel, double driveGearRatio, double steerGearRatio, edu.wpi.first.units.measure.Voltage driveFrictionVoltage, edu.wpi.first.units.measure.Voltage steerFrictionVoltage, edu.wpi.first.units.measure.Distance wheelRadius, edu.wpi.first.units.measure.MomentOfInertia steerRotationalInertia, double tireCoefficientOfFriction)

      Constructs a Swerve Module Simulation.

      If you are using SimulatedArena.overrideSimulationTimings(Time, int) to use custom timings, you must call the method before constructing any swerve module simulations using this constructor.

      Parameters:
      driveMotorModel - the model of the driving motor
      steerMotorModel - ; the model of the steering motor
      driveGearRatio - the gear ratio for the driving motor, >1 is reduction
      steerGearRatio - the gear ratio for the steering motor, >1 is reduction
      driveFrictionVoltage - the measured minimum amount of voltage that can turn the driving rotter
      steerFrictionVoltage - the measured minimum amount of voltage that can turn the steering rotter
      wheelRadius - the radius of the wheels.
      steerRotationalInertia - the rotational inertia of the entire steering mechanism
      tireCoefficientOfFriction - the coefficient of friction of the tires, normally around 1.2 Units.inchesToMeters(double).
  • Method Details

    • getDriveMotorConfigs

      public SimMotorConfigs getDriveMotorConfigs()
    • getSteerMotorConfigs

      public SimMotorConfigs getSteerMotorConfigs()
    • useDriveMotorController

      public <T extends SimulatedMotorController> T useDriveMotorController(T driveMotorController)

      Sets the motor controller for the drive motor.

      The configured controller runs control loop on the motor.

      Parameters:
      driveMotorController - the motor controller to control the drive motor
    • useGenericMotorControllerForDrive

      public SimulatedMotorController.GenericMotorController useGenericMotorControllerForDrive()
    • useSteerMotorController

      public <T extends SimulatedMotorController> T useSteerMotorController(T steerMotorController)

      Requests the Steering Motor to Run at a Specified Output.

      Think of it as the requestOutput() of your physical steering motor.

      Parameters:
      steerMotorController - the motor controller to control the steer motor
    • useGenericControllerForSteer

      public SimulatedMotorController.GenericMotorController useGenericControllerForSteer()
    • getDriveMotorAppliedVoltage

      public edu.wpi.first.units.measure.Voltage getDriveMotorAppliedVoltage()

      Obtains the Actual Output Voltage of the Drive Motor.

      Returns:
      the actual output voltage of the drive motor
    • getSteerMotorAppliedVoltage

      public edu.wpi.first.units.measure.Voltage getSteerMotorAppliedVoltage()

      Obtains the Actual Output Voltage of the Steering Motor.

      Returns:
      the actual output voltage of the steering motor
      See Also:
    • getDriveMotorSupplyCurrent

      public edu.wpi.first.units.measure.Current getDriveMotorSupplyCurrent()

      Obtains the Amount of Current Supplied to the Drive Motor.

      Returns:
      the current supplied to the drive motor
    • getDriveMotorStatorCurrent

      public edu.wpi.first.units.measure.Current getDriveMotorStatorCurrent()

      Obtains the Stator current the Drive Motor.

      Returns:
      the stator current of the drive motor
    • getSteerMotorSupplyCurrent

      public edu.wpi.first.units.measure.Current getSteerMotorSupplyCurrent()

      Obtains the Amount of Current Supplied to the Steer Motor.

      Returns:
      the current supplied to the steer motor
      See Also:
    • getSteerMotorStatorCurrent

      public edu.wpi.first.units.measure.Current getSteerMotorStatorCurrent()

      Obtains the Stator current the Steer Motor.

      Returns:
      the stator current of the drive motor
      See Also:
    • getDriveEncoderUnGearedPosition

      public edu.wpi.first.units.measure.Angle getDriveEncoderUnGearedPosition()

      Obtains the Position of the Drive Encoder.

      This value represents the un-geared position of the encoder, i.e., the amount of radians the drive motor's encoder has rotated.

      Returns:
      the position of the drive motor's encoder (un-geared)
    • getDriveWheelFinalPosition

      public edu.wpi.first.units.measure.Angle getDriveWheelFinalPosition()

      Obtains the Final Position of the Wheel.

      This method provides the final position of the drive encoder in terms of wheel angle.

      Returns:
      the final position of the drive encoder (wheel rotations)
    • getDriveEncoderUnGearedSpeed

      public edu.wpi.first.units.measure.AngularVelocity getDriveEncoderUnGearedSpeed()

      Obtains the Speed of the Drive Encoder.

      Returns:
      the un-geared speed of the drive encoder
    • getDriveWheelFinalSpeed

      public edu.wpi.first.units.measure.AngularVelocity getDriveWheelFinalSpeed()

      Obtains the Final Speed of the Wheel.

      Returns:
      the final speed of the drive wheel
    • getSteerRelativeEncoderPosition

      public edu.wpi.first.units.measure.Angle getSteerRelativeEncoderPosition()

      Obtains the Relative Position of the Steer Encoder.

      Returns:
      the relative encoder position of the steer motor
      See Also:
    • getSteerRelativeEncoderVelocity

      public edu.wpi.first.units.measure.AngularVelocity getSteerRelativeEncoderVelocity()

      Obtains the Speed of the Steer Relative Encoder (Geared).

      Returns:
      the speed of the steer relative encoder
      See Also:
    • getSteerAbsoluteFacing

      public Rotation2d getSteerAbsoluteFacing()

      Obtains the Absolute Facing of the Steer Mechanism.

      Returns:
      the absolute facing of the steer mechanism, as a Rotation2d
    • getSteerAbsoluteEncoderSpeed

      public edu.wpi.first.units.measure.AngularVelocity getSteerAbsoluteEncoderSpeed()

      Obtains the Absolute Rotational Velocity of the Steer Mechanism.

      Returns:
      the absolute angular velocity of the steer mechanism
    • getCachedDriveEncoderUnGearedPositions

      public edu.wpi.first.units.measure.Angle[] getCachedDriveEncoderUnGearedPositions()

      Obtains the Cached Readings of the Drive Encoder's Un-Geared Position.

      The values of getDriveEncoderUnGearedPosition() are cached at each sub-tick and can be retrieved using this method.

      Returns:
      an array of cached drive encoder un-geared positions
    • getCachedDriveWheelFinalPositions

      public edu.wpi.first.units.measure.Angle[] getCachedDriveWheelFinalPositions()

      Obtains the Cached Readings of the Drive Encoder's Final Position (Wheel Rotations).

      The values of getDriveWheelFinalPosition() are cached at each sub-tick and are divided by the gear ratio to obtain the final wheel rotations.

      Returns:
      an array of cached drive encoder final positions (wheel rotations)
    • getCachedSteerRelativeEncoderPositions

      public edu.wpi.first.units.measure.Angle[] getCachedSteerRelativeEncoderPositions()

      Obtains the Cached Readings of the Steer Relative Encoder's Position.

      The values of getSteerRelativeEncoderPosition() are cached at each sub-tick and can be retrieved using this method.

      Returns:
      an array of cached steer relative encoder positions
    • getCachedSteerAbsolutePositions

      public Rotation2d[] getCachedSteerAbsolutePositions()

      Obtains the Cached Readings of the Steer Absolute Positions.

      The values of getSteerAbsoluteFacing() are cached at each sub-tick and can be retrieved using this method.

      Returns:
      an array of cached absolute steer positions, as Rotation2d objects
    • getGrippingForceNewtons

      protected double getGrippingForceNewtons(double gravityForceOnModuleNewtons)
    • updateSimulationSubTickGetModuleForce

      public org.dyn4j.geometry.Vector2 updateSimulationSubTickGetModuleForce(org.dyn4j.geometry.Vector2 moduleCurrentGroundVelocityWorldRelative, Rotation2d robotFacing, double gravityForceOnModuleNewtons)

      Updates the Simulation for This Module.

      Note: Friction forces are not simulated in this method.

      Parameters:
      moduleCurrentGroundVelocityWorldRelative - the current ground velocity of the module, relative to the world
      robotFacing - the absolute facing of the robot, relative to the world
      gravityForceOnModuleNewtons - the gravitational force acting on this module, in newtons
      Returns:
      the propelling force generated by the module, as a Vector2 object
    • getCurrentState

      public SwerveModuleState getCurrentState()
      Returns:
      the current module state of this simulation module
    • getFreeSpinState

      protected SwerveModuleState getFreeSpinState()

      Obtains the "free spin" state of the module

      The "free spin" state of a simulated module refers to its state after spinning freely for a long time under the current input voltage

      Returns:
      the free spinning module state
    • maximumGroundSpeed

      public edu.wpi.first.units.measure.LinearVelocity maximumGroundSpeed()

      Obtains the theoretical speed that the module can achieve.

      Returns:
      the theoretical maximum ground speed that the module can achieve, in m/s
    • getTheoreticalPropellingForcePerModule

      public edu.wpi.first.units.measure.Force getTheoreticalPropellingForcePerModule(edu.wpi.first.units.measure.Mass robotMass, int modulesCount)

      Obtains the theoretical maximum propelling force of ONE module.

      Calculates the maximum propelling force with respect to the gripping force and the drive motor's torque under its current limit.

      Parameters:
      robotMass - the mass of the robot
      modulesCount - the amount of modules on the robot, assumed to be sharing the gravity force equally
      Returns:
      the maximum propelling force of EACH module
    • maxAcceleration

      public edu.wpi.first.units.measure.LinearAcceleration maxAcceleration(edu.wpi.first.units.measure.Mass robotMass, int modulesCount)

      Obtains the theatrical linear acceleration that the robot can achieve.

      Calculates the maximum linear acceleration of a robot, with respect to its mass and getTheoreticalPropellingForcePerModule(Mass, int).

      Parameters:
      robotMass - the mass of the robot
      modulesCount - the amount of modules on the robot, assumed to be sharing the gravity force equally