48 typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, DriveMotorT>>,
49 typename = std::enable_if_t<std::is_base_of_v<hardware::traits::CommonTalon, SteerMotorT>>,
50 typename = std::enable_if_t<std::disjunction_v<
51 std::is_same<hardware::CANcoder, EncoderT>,
52 std::is_same<hardware::CANdi, EncoderT>,
53 std::is_same<hardware::TalonFXS, EncoderT>
76 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> _modules;
93 typename... ModuleConstants,
94 typename = std::enable_if_t<std::conjunction_v<
119 typename... ModuleConstants,
120 typename = std::enable_if_t<std::conjunction_v<
129 units::hertz_t odometryUpdateFrequency,
130 ModuleConstants
const &... modules
132 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency,
std::array{0.1, 0.1, 0.1},
std::array{0.9, 0.9, 0.9}, modules...}
155 typename... ModuleConstants,
156 typename = std::enable_if_t<std::conjunction_v<
165 units::hertz_t odometryUpdateFrequency,
166 std::array<double, 3>
const &odometryStandardDeviation,
167 std::array<double, 3>
const &visionStandardDeviation,
168 ModuleConstants
const &... modules
171 drivetrainConstants, odometryUpdateFrequency,
172 odometryStandardDeviation, visionStandardDeviation,
173 span<
SwerveModuleConstants<typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration> const>{
174 std::array{modules...}
177 _modules{CreateModuleArray(drivetrainConstants.CANBusName, modules...)},
178 _pigeon2{drivetrainConstants.Pigeon2Id, std::string{drivetrainConstants.CANBusName}},
179 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
181 if (drivetrainConstants.Pigeon2Configs) {
183 for (
int i = 0; i < kNumConfigAttempts; ++i) {
184 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
185 if (retval.IsOK())
break;
187 if (!retval.IsOK()) {
188 printf(
"Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
192 GetOdometryThread().Start();
198 template <
typename... ModuleConstants>
199 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> CreateModuleArray(
200 std::string_view canbusName,
201 ModuleConstants
const &... constants
203 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> modules;
204 modules.reserve(
sizeof...(ModuleConstants));
206 [&]<
size_t... Idxs>(std::index_sequence<Idxs...>) {
208 }(std::index_sequence_for<ModuleConstants...>{});
223 _simDrive.Update(dt, supplyVoltage, _modules);
233 return _drivetrain.IsOnCANFD();
243 return _drivetrain.GetOdometryFrequency();
253 return _drivetrain.GetOdometryThread();
263 return _drivetrain.IsOdometryValid();
273 return _drivetrain.GetKinematics();
287 typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>,
288 typename = std::enable_if_t<!std::is_const_v<Request>>
292 _drivetrain.SetControl(
293 [&request](
auto const ¶ms,
auto const &modules)
mutable {
294 return request.Apply(params, modules);
306 typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>,
307 typename = std::enable_if_t<!std::is_const_v<Request>>
311 _drivetrain.SetControl(
312 [request=std::move(request)](
auto const ¶ms,
auto const &modules)
mutable {
313 return request.Apply(params, modules);
327 return _drivetrain.GetState();
345 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
356 return _drivetrain.ConfigNeutralMode(neutralMode);
366 _drivetrain.TareEverything();
380 _drivetrain.SeedFieldCentric();
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);
562 return _drivetrain.SamplePoseAt(timestamp);
574 return *_modules.at(index);
585 return *_modules.at(index);
593 std::vector<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 description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:29
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2303
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:46
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrain.hpp:56
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:251
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
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:101
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:70
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:241
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:163
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:73
virtual void UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:221
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:583
virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:475
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:231
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:343
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:354
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:624
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:127
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:261
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:449
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:290
std::vector< 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 ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:389
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:433
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:603
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:309
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:271
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:413
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:325
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:572
virtual void SeedFieldCentric()
Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspe...
Definition SwerveDrivetrain.hpp:378
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:364
virtual ~SwerveDrivetrain()=default
virtual void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrain.hpp:542
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 std::optional< Pose2d > SamplePoseAt(units::second_t timestamp)
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrain.hpp:560
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:401
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:45
Class that converts a chassis velocity (dx, dy, and dtheta components) into individual module states ...
Definition SwerveDriveKinematics.hpp:42
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrainImpl.hpp:33
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
friend class OdometryThread
Definition SwerveDrivetrainImpl.hpp:170
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18
Common constants for a swerve drivetrain.
Definition SwerveDrivetrainConstants.hpp:19
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:154
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:121