CTRE Phoenix 6 C++ 26.0.0-beta-1
Loading...
Searching...
No Matches
SimSwerveDrivetrain.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.Ā  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
12#include <frc/simulation/DCMotorSim.h>
13#include <frc/system/plant/LinearSystemId.h>
14
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18
19/**
20 * \brief Simplified swerve drive simulation class.
21 *
22 * This class assumes that the swerve drive is perfect, meaning
23 * that there is no scrub and the wheels do not slip.
24 *
25 * In addition, it assumes the inertia of the robot is governed only
26 * by the inertia of the steer module and the individual drive wheels.
27 * Robot-wide inertia is not accounted for, and neither is translational
28 * vs rotational inertia of the robot.
29 *
30 * These assumptions provide a simplified example that can demonstrate the
31 * behavior of a swerve drive in simulation. Users are encouraged to
32 * expand this model for their own use.
33 */
34template <
35 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
36 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
37 typename EncoderT
38>
39 requires std::same_as<EncoderT, hardware::CANcoder> ||
40 std::same_as<EncoderT, hardware::CANdi> ||
41 std::same_as<EncoderT, hardware::TalonFXS>
43protected:
45 public:
46 /** \brief Reference to motor simulation for drive motor */
47 frc::sim::DCMotorSim DriveMotor;
48 /** \brief Reference to motor simulation for the steer motor */
49 frc::sim::DCMotorSim SteerMotor;
50 /** \brief Reference to steer gearing for updating encoder */
51 units::scalar_t DriveGearing;
52 /** \brief Reference to steer gearing for updating encoder */
53 units::scalar_t SteerGearing;
54 /** \brief Voltage necessary for the drive motor to overcome friction */
55 units::volt_t DriveFrictionVoltage;
56 /** \brief Voltage necessary for the steer motor to overcome friction */
57 units::volt_t SteerFrictionVoltage;
58 /** \brief Whether the drive motor is inverted */
60 /** \brief Whether the steer motor is inverted */
62 /** \brief Whether the azimuth encoder is inverted */
64 /** \brief Offset of the azimuth encoder */
65 units::turn_t EncoderOffset;
66 /** \brief The type of encoder to use for the azimuth */
68
70 units::scalar_t driveGearing, units::kilogram_square_meter_t driveInertia,
71 units::volt_t driveFrictionVoltage, bool driveMotorInverted,
72 DriveMotorArrangement driveMotorType,
73 units::scalar_t steerGearing, units::kilogram_square_meter_t steerInertia,
74 units::volt_t steerFrictionVoltage, bool steerMotorInverted,
75 SteerMotorArrangement steerMotorType,
76 bool encoderInverted,
77 units::turn_t encoderOffset,
78 SteerFeedbackType encoderType
79 ) :
80 DriveMotor{frc::LinearSystemId::DCMotorSystem(GetDriveMotorGearbox(driveMotorType), driveInertia, driveGearing), GetDriveMotorGearbox(driveMotorType)},
81 SteerMotor{frc::LinearSystemId::DCMotorSystem(GetSteerMotorGearbox(steerMotorType), steerInertia, steerGearing), GetSteerMotorGearbox(steerMotorType)},
82 DriveGearing{driveGearing},
83 SteerGearing{steerGearing},
84 DriveFrictionVoltage{driveFrictionVoltage},
85 SteerFrictionVoltage{steerFrictionVoltage},
86 DriveMotorInverted{driveMotorInverted},
87 SteerMotorInverted{steerMotorInverted},
88 EncoderInverted{encoderInverted},
89 EncoderOffset{encoderOffset},
90 EncoderType{encoderType}
91 {}
92
93 static frc::DCMotor GetDriveMotorGearbox(DriveMotorArrangement driveMotorType)
94 {
95 switch (driveMotorType) {
97 default:
98 return frc::DCMotor::KrakenX60FOC(1);
100 return frc::DCMotor::NEO(1);
102 return frc::DCMotor::NeoVortex(1);
103 }
104 }
105
106 static frc::DCMotor GetSteerMotorGearbox(SteerMotorArrangement steerMotorType)
107 {
108 switch (steerMotorType) {
110 default:
111 return frc::DCMotor::KrakenX60FOC(1);
113 return frc::DCMotor{12_V, 3.1_Nm, 202_A, 4_A, 774_rad_per_s, 1};
115 return frc::DCMotor::NEO(1);
117 return frc::DCMotor::NeoVortex(1);
119 return frc::DCMotor::NEO550(1);
123 return frc::DCMotor::CIM(1);
124 }
125 }
126 };
127
129 std::vector<SimSwerveModule> _modules;
130
132 Rotation2d _lastAngle{};
133
134public:
135 template <
136 std::same_as<SwerveModuleConstants<
137 typename DriveMotorT::Configuration,
138 typename SteerMotorT::Configuration,
139 typename EncoderT::Configuration
140 >>... ModuleConstants
141 >
143 std::vector<Translation2d> wheelLocations,
144 sim::Pigeon2SimState &pigeonSim,
145 ModuleConstants const &... moduleConstants
146 ) :
147 _pigeonSim{pigeonSim},
148 _modules{
150 moduleConstants.DriveMotorGearRatio,
151 moduleConstants.DriveInertia,
152 moduleConstants.DriveFrictionVoltage,
153 moduleConstants.DriveMotorInverted,
154 moduleConstants.DriveMotorType,
155 moduleConstants.SteerMotorGearRatio,
156 moduleConstants.SteerInertia,
157 moduleConstants.SteerFrictionVoltage,
158 moduleConstants.SteerMotorInverted,
159 moduleConstants.SteerMotorType,
160 moduleConstants.EncoderInverted,
161 moduleConstants.EncoderOffset,
162 moduleConstants.FeedbackSource
163 }...
164 },
165 _kinem{std::move(wheelLocations)}
166 {}
167
168 void Update(
169 units::second_t dt,
170 units::volt_t supplyVoltage,
171 std::span<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>> const> modulesToApply
172 ) {
173 if (modulesToApply.size() != _modules.size()) return;
174
175 std::vector<SwerveModuleState> states(modulesToApply.size());
176 /* update our sim devices */
177 for (size_t i = 0; i < modulesToApply.size(); ++i) {
178 auto &driveMotor = modulesToApply[i]->GetDriveMotor().GetSimState();
179 auto &steerMotor = modulesToApply[i]->GetSteerMotor().GetSimState();
180 auto &encoder = modulesToApply[i]->GetEncoder().GetSimState();
181
182 if constexpr (std::same_as<hardware::TalonFXS, DriveMotorT>) {
184 } else {
186 }
187
188 if constexpr (std::same_as<hardware::TalonFXS, SteerMotorT>) {
190 steerMotor.ExtSensorOrientation = _modules[i].SteerMotorInverted != _modules[i].EncoderInverted ? sim::ChassisReference::Clockwise_Positive : sim::ChassisReference::CounterClockwise_Positive;
191 steerMotor.PulseWidthSensorOffset = _modules[i].EncoderOffset;
192 } else {
194 }
195
196 if constexpr (std::same_as<hardware::CANcoder, EncoderT>) {
198 encoder.SensorOffset = _modules[i].EncoderOffset;
199 }
200
201 driveMotor.SetSupplyVoltage(supplyVoltage);
202 steerMotor.SetSupplyVoltage(supplyVoltage);
203 encoder.SetSupplyVoltage(supplyVoltage);
204
205 _modules[i].DriveMotor.SetInputVoltage(AddFriction(driveMotor.GetMotorVoltage(), _modules[i].DriveFrictionVoltage));
206 _modules[i].SteerMotor.SetInputVoltage(AddFriction(steerMotor.GetMotorVoltage(), _modules[i].SteerFrictionVoltage));
207
208 _modules[i].DriveMotor.Update(dt);
209 _modules[i].SteerMotor.Update(dt);
210
211 driveMotor.SetRawRotorPosition(_modules[i].DriveMotor.GetAngularPosition() * _modules[i].DriveGearing);
212 driveMotor.SetRotorVelocity(_modules[i].DriveMotor.GetAngularVelocity() * _modules[i].DriveGearing);
213
214 steerMotor.SetRawRotorPosition(_modules[i].SteerMotor.GetAngularPosition() * _modules[i].SteerGearing);
215 steerMotor.SetRotorVelocity(_modules[i].SteerMotor.GetAngularVelocity() * _modules[i].SteerGearing);
216 if constexpr (std::same_as<hardware::TalonFXS, SteerMotorT>) {
217 /* azimuth encoders see the mechanism, so don't account for the steer gearing */
218 steerMotor.SetPulseWidthPosition(_modules[i].SteerMotor.GetAngularPosition());
219 steerMotor.SetPulseWidthVelocity(_modules[i].SteerMotor.GetAngularVelocity());
220 }
221
222 if constexpr (std::same_as<hardware::CANcoder, EncoderT>) {
223 /* azimuth encoders see the mechanism, so don't account for the steer gearing */
224 encoder.SetRawPosition(_modules[i].SteerMotor.GetAngularPosition());
225 encoder.SetVelocity(_modules[i].SteerMotor.GetAngularVelocity());
226 } else if constexpr (std::same_as<hardware::CANdi, EncoderT>) {
227 switch (_modules[i].EncoderType) {
232 encoder.Pwm1SensorOffset = _modules[i].EncoderOffset;
233
234 /* azimuth encoders see the mechanism, so don't account for the steer gearing */
235 encoder.SetPwm1Connected(true);
236 encoder.SetPwm1Position(_modules[i].SteerMotor.GetAngularPosition());
237 encoder.SetPwm1Velocity(_modules[i].SteerMotor.GetAngularVelocity());
238 break;
239
244 encoder.Pwm1SensorOffset = _modules[i].EncoderOffset;
245
246 /* azimuth encoders see the mechanism, so don't account for the steer gearing */
247 encoder.SetPwm2Connected(true);
248 encoder.SetPwm2Position(_modules[i].SteerMotor.GetAngularPosition());
249 encoder.SetPwm2Velocity(_modules[i].SteerMotor.GetAngularVelocity());
250 break;
251
252 default:
253 break;
254 }
255 }
256
257 states[i] = modulesToApply[i]->GetCurrentState();
258 }
259
260 auto const angularVel = _kinem.ToChassisSpeeds(states).omega;
261 _lastAngle = _lastAngle + Rotation2d{angularVel * dt};
264 }
265
266protected:
267 /**
268 * \brief Applies the effects of friction to dampen the motor voltage.
269 *
270 * \param motorVoltage Voltage output by the motor
271 * \param frictionVoltage Voltage required to overcome friction
272 * \returns Friction-dampened motor voltage
273 */
274 static units::volt_t AddFriction(units::volt_t motorVoltage, units::volt_t frictionVoltage)
275 {
276 if (units::math::abs(motorVoltage) < frictionVoltage) {
277 motorVoltage = 0_V;
278 } else if (motorVoltage > 0_V) {
279 motorVoltage -= frictionVoltage;
280 } else {
281 motorVoltage += frictionVoltage;
282 }
283 return motorVoltage;
284 }
285};
286
287}
288}
289}
Class to control the state of a simulated hardware::Pigeon2.
Definition Pigeon2SimState.hpp:31
ctre::phoenix::StatusCode SetAngularVelocityZ(units::angular_velocity::degrees_per_second_t dps)
Sets the simulated angular velocity Z component of the Pigeon2.
ctre::phoenix::StatusCode SetRawYaw(units::angle::degree_t deg)
Sets the simulated raw yaw of the Pigeon2.
units::scalar_t DriveGearing
Reference to steer gearing for updating encoder.
Definition SimSwerveDrivetrain.hpp:51
frc::sim::DCMotorSim SteerMotor
Reference to motor simulation for the steer motor.
Definition SimSwerveDrivetrain.hpp:49
SimSwerveModule(units::scalar_t driveGearing, units::kilogram_square_meter_t driveInertia, units::volt_t driveFrictionVoltage, bool driveMotorInverted, DriveMotorArrangement driveMotorType, units::scalar_t steerGearing, units::kilogram_square_meter_t steerInertia, units::volt_t steerFrictionVoltage, bool steerMotorInverted, SteerMotorArrangement steerMotorType, bool encoderInverted, units::turn_t encoderOffset, SteerFeedbackType encoderType)
Definition SimSwerveDrivetrain.hpp:69
bool SteerMotorInverted
Whether the steer motor is inverted.
Definition SimSwerveDrivetrain.hpp:61
units::turn_t EncoderOffset
Offset of the azimuth encoder.
Definition SimSwerveDrivetrain.hpp:65
bool DriveMotorInverted
Whether the drive motor is inverted.
Definition SimSwerveDrivetrain.hpp:59
units::volt_t SteerFrictionVoltage
Voltage necessary for the steer motor to overcome friction.
Definition SimSwerveDrivetrain.hpp:57
frc::sim::DCMotorSim DriveMotor
Reference to motor simulation for drive motor.
Definition SimSwerveDrivetrain.hpp:47
static frc::DCMotor GetSteerMotorGearbox(SteerMotorArrangement steerMotorType)
Definition SimSwerveDrivetrain.hpp:106
static frc::DCMotor GetDriveMotorGearbox(DriveMotorArrangement driveMotorType)
Definition SimSwerveDrivetrain.hpp:93
bool EncoderInverted
Whether the azimuth encoder is inverted.
Definition SimSwerveDrivetrain.hpp:63
units::scalar_t SteerGearing
Reference to steer gearing for updating encoder.
Definition SimSwerveDrivetrain.hpp:53
SteerFeedbackType EncoderType
The type of encoder to use for the azimuth.
Definition SimSwerveDrivetrain.hpp:67
units::volt_t DriveFrictionVoltage
Voltage necessary for the drive motor to overcome friction.
Definition SimSwerveDrivetrain.hpp:55
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:42
std::vector< SimSwerveModule > _modules
Definition SimSwerveDrivetrain.hpp:129
void Update(units::second_t dt, units::volt_t supplyVoltage, std::span< std::unique_ptr< SwerveModule< DriveMotorT, SteerMotorT, EncoderT > > const > modulesToApply)
Definition SimSwerveDrivetrain.hpp:168
SimSwerveDrivetrain(std::vector< Translation2d > wheelLocations, sim::Pigeon2SimState &pigeonSim, ModuleConstants const &... moduleConstants)
Definition SimSwerveDrivetrain.hpp:142
impl::SwerveDriveKinematics _kinem
Definition SimSwerveDrivetrain.hpp:131
Rotation2d _lastAngle
Definition SimSwerveDrivetrain.hpp:132
sim::Pigeon2SimState & _pigeonSim
Definition SimSwerveDrivetrain.hpp:128
static units::volt_t AddFriction(units::volt_t motorVoltage, units::volt_t frictionVoltage)
Applies the effects of friction to dampen the motor voltage.
Definition SimSwerveDrivetrain.hpp:274
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:52
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:41
ChassisSpeeds ToChassisSpeeds(WheelSpeeds const &moduleStates) const
Performs forward kinematics to return the resulting chassis state from the given module states.
@ Clockwise_Positive
The device should read a clockwise rotation as positive motion.
@ CounterClockwise_Positive
The device should read a counter-clockwise rotation as positive motion.
SteerMotorArrangement
Supported motor arrangements for the steer motors.
Definition SwerveModuleConstants.hpp:49
@ TalonFXS_Brushed_AC
Brushed motor connected to a Talon FXS on terminals A and C.
@ TalonFXS_Brushed_AB
Brushed motor connected to a Talon FXS on terminals A and B.
@ TalonFX_Integrated
Talon FX integrated brushless motor.
@ TalonFXS_Brushed_BC
Brushed motor connected to a Talon FXS on terminals B and C.
@ TalonFXS_NEO550_JST
Third party NEO550 brushless motor connected to a Talon FXS over JST.
@ TalonFXS_NEO_JST
Third party NEO brushless motor connected to a Talon FXS over JST.
@ TalonFXS_VORTEX_JST
Third party VORTEX brushless motor connected to a Talon FXS over JST.
@ TalonFXS_Minion_JST
CTR Electronics MinionĀ® brushless motor connected to a Talon FXS over JST.
SteerFeedbackType
Supported feedback sensors for the steer motors.
Definition SwerveModuleConstants.hpp:87
@ SyncCANdiPWM2
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANdiPWM2 for the steer motor.
@ SyncCANdiPWM1
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANdiPWM1 for the steer motor.
@ RemoteCANdiPWM2
Use signals::FeedbackSensorSourceValue::RemoteCANdiPWM2 for the steer motor.
@ FusedCANdiPWM2
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANdiPWM2 for the steer motor.
@ FusedCANdiPWM1
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANdiPWM1 for the steer motor.
@ RemoteCANdiPWM1
Use signals::FeedbackSensorSourceValue::RemoteCANdiPWM1 for the steer motor.
DriveMotorArrangement
Supported motor arrangements for the drive motors.
Definition SwerveModuleConstants.hpp:31
@ TalonFX_Integrated
Talon FX integrated brushless motor.
@ TalonFXS_NEO_JST
Third party NEO brushless motor connected to a Talon FXS over JST.
@ TalonFXS_VORTEX_JST
Third party VORTEX brushless motor connected to a Talon FXS over JST.
Definition motor_constants.h:14
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148