Package com.ctre.phoenix6.swerve
Class SimSwerveDrivetrain
java.lang.Object
com.ctre.phoenix6.swerve.SimSwerveDrivetrain
Simplified swerve drive simulation class.
This class assumes that the swerve drive is perfect, meaning that there is no scrub and the wheels do not slip.
In addition, it assumes the inertia of the robot is governed only by the inertia of the steer module and the individual drive wheels. Robot-wide inertia is not accounted for, and neither is translational vs rotational inertia of the robot.
These assumptions provide a simplified example that can demonstrate the behavior of a swerve drive in simulation. Users are encouraged to expand this model for their own use.
-
Nested Class Summary
-
Field Summary
Modifier and TypeFieldDescriptionprotected final SwerveDriveKinematics
protected Rotation2d
protected final SimSwerveDrivetrain.SimSwerveModule[]
protected final Pigeon2SimState
-
Constructor Summary
ConstructorDescriptionSimSwerveDrivetrain
(Translation2d[] wheelLocations, Pigeon2SimState pigeonSim, SwerveModuleConstants... moduleConstants) -
Method Summary
Modifier and TypeMethodDescriptionprotected double
addFriction
(double motorVoltage, double frictionVoltage) Applies the effects of friction to dampen the motor voltage.void
update
(double dtSeconds, double supplyVoltage, SwerveModule... modulesToApply) Update this simulation for the time duration.
-
Field Details
-
m_pigeonSim
-
m_modules
-
m_kinem
-
m_lastAngle
-
-
Constructor Details
-
SimSwerveDrivetrain
public SimSwerveDrivetrain(Translation2d[] wheelLocations, Pigeon2SimState pigeonSim, SwerveModuleConstants... moduleConstants)
-
-
Method Details
-
update
Update this simulation for the time duration.This performs a simulation update on all the simulated devices
- Parameters:
dtSeconds
- The time delta between this update and the previous updatesupplyVoltage
- The voltage as seen at the motor controllersmodulesToApply
- What modules to apply the update to
-
addFriction
Applies the effects of friction to dampen the motor voltage.- Parameters:
motorVoltage
- Voltage output by the motorfrictionVoltage
- Voltage required to overcome friction- Returns:
- Friction-dampened motor voltage
-