45 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
46 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
49 requires std::same_as<EncoderT, hardware::CANcoder> ||
50 std::same_as<EncoderT, hardware::CANdi> ||
51 std::same_as<EncoderT, hardware::TalonFXS>
72 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> _modules;
90 typename DriveMotorT::Configuration,
91 typename SteerMotorT::Configuration,
92 typename EncoderT::Configuration
114 typename DriveMotorT::Configuration,
115 typename SteerMotorT::Configuration,
116 typename EncoderT::Configuration
117 >>... ModuleConstants
121 units::hertz_t odometryUpdateFrequency,
122 ModuleConstants
const &... modules
124 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules...}
148 typename DriveMotorT::Configuration,
149 typename SteerMotorT::Configuration,
150 typename EncoderT::Configuration
151 >>... ModuleConstants
155 units::hertz_t odometryUpdateFrequency,
156 std::array<double, 3>
const &odometryStandardDeviation,
157 std::array<double, 3>
const &visionStandardDeviation,
158 ModuleConstants
const &... modules
161 drivetrainConstants, odometryUpdateFrequency,
162 odometryStandardDeviation, visionStandardDeviation,
163 std::span<
SwerveModuleConstants<typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration> const>{
164 std::array{modules...}
167 _modules{CreateModuleArray(
CANBus{drivetrainConstants.CANBusName}, modules...)},
168 _pigeon2{drivetrainConstants.Pigeon2Id, CANBus{drivetrainConstants.CANBusName}},
169 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
171 if (drivetrainConstants.Pigeon2Configs) {
173 for (
int i = 0; i < kNumConfigAttempts; ++i) {
174 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
175 if (retval.IsOK())
break;
177 if (!retval.IsOK()) {
178 printf(
"Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
182 GetOdometryThread().Start();
188 template <
typename... ModuleConstants>
189 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> CreateModuleArray(
191 ModuleConstants
const &... constants
193 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> modules;
194 modules.reserve(
sizeof...(ModuleConstants));
196 [&]<
size_t... Idxs>(std::index_sequence<Idxs...>) {
198 }(std::index_sequence_for<ModuleConstants...>{});
213 _simDrive.Update(dt, supplyVoltage, _modules);
223 return _drivetrain.IsOnCANFD();
233 return _drivetrain.GetOdometryFrequency();
243 return _drivetrain.GetOdometryThread();
253 return _drivetrain.IsOdometryValid();
263 return _drivetrain.GetKinematics();
275 template <std::derived_from<requests::SwerveRequest> Request>
276 requires (!std::is_const_v<Request>)
279 _drivetrain.SetControl(
280 [&request](
auto const ¶ms,
auto modules)
mutable {
281 return request.Apply(params, modules);
291 template <std::derived_from<requests::SwerveRequest> Request>
292 requires (!std::is_const_v<Request>)
295 _drivetrain.SetControl(
296 [request=std::move(request)](
auto const ¶ms,
auto modules)
mutable {
297 return request.Apply(params, modules);
311 return _drivetrain.GetState();
329 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
342 return _drivetrain.ConfigNeutralMode(neutralMode);
354 return _drivetrain.ConfigNeutralMode(neutralMode, timeoutSeconds);
364 _drivetrain.TareEverything();
380 _drivetrain.SeedFieldCentric(rotation);
391 _drivetrain.ResetPose(pose);
403 _drivetrain.ResetTranslation(translation);
415 _drivetrain.ResetRotation(rotation);
435 _drivetrain.SetOperatorPerspectiveForward(fieldDirection);
451 return _drivetrain.GetOperatorForwardDirection();
477 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp);
511 Pose2d visionRobotPose,
512 units::second_t timestamp,
513 std::array<double, 3> visionMeasurementStdDevs)
515 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp, visionMeasurementStdDevs);
531 _drivetrain.SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
544 _drivetrain.SetStateStdDevs(stateStdDevs);
560 virtual std::optional<Pose2d>
SamplePoseAt(units::second_t timestamp)
const
562 return _drivetrain.SamplePoseAt(timestamp);
574 return *_modules.at(index);
585 return *_modules.at(index);
593 std::span<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>
const>
GetModules()
const
603 std::vector<Translation2d>
const &
GetModuleLocations()
const {
return _drivetrain.GetModuleLocations(); }
613 return _pigeon2.GetRotation3d();
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:34
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:42
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrain.hpp:52
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:433
virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:475
std::span< std::unique_ptr< SwerveModule< DriveMotorT, SteerMotorT, EncoderT > > const > GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrain.hpp:593
virtual void UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:211
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:572
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:241
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:401
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:362
virtual void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrain.hpp:542
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:277
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:293
virtual std::optional< Pose2d > SamplePoseAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrain.hpp:560
virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:510
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:251
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:261
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:340
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:119
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:352
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:309
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:231
virtual void SeedFieldCentric(Rotation2d const &rotation=Rotation2d{})
Resets the rotation of the robot pose to the given value from the requests::ForwardPerspectiveValue::...
Definition SwerveDrivetrain.hpp:378
virtual frc::Rotation3d GetRotation3d() const
Gets the current orientation of the robot as a frc#Rotation3d from the Pigeon 2 quaternion values.
Definition SwerveDrivetrain.hpp:611
virtual void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrain.hpp:529
virtual void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:389
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:221
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:95
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:153
virtual ~SwerveDrivetrain()=default
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:413
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:624
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:583
hardware::Pigeon2 const & GetPigeon2() const
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:636
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:66
virtual void RegisterTelemetry(std::function< void(SwerveDriveState const &)> telemetryFunction)
Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry...
Definition SwerveDrivetrain.hpp:327
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:69
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:603
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:449
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
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:32
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:29
friend class OdometryThread
Definition SwerveDrivetrainImpl.hpp:164
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
Definition motor_constants.h:14
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:1603
Common constants for a swerve drivetrain.
Definition SwerveDrivetrainConstants.hpp:19
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:115