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::is_base_of_v<hardware::ParentDevice, EncoderT>>
72 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> _modules;
89 typename... ModuleConstants,
90 typename = std::enable_if_t<std::conjunction_v<
91 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
112 typename... ModuleConstants,
113 typename = std::enable_if_t<std::conjunction_v<
114 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
119 units::hertz_t odometryUpdateFrequency,
120 ModuleConstants
const &... modules
122 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency,
std::array{0.1, 0.1, 0.1},
std::array{0.9, 0.9, 0.9}, modules...}
145 typename... ModuleConstants,
146 typename = std::enable_if_t<std::conjunction_v<
147 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
152 units::hertz_t odometryUpdateFrequency,
153 std::array<double, 3>
const &odometryStandardDeviation,
154 std::array<double, 3>
const &visionStandardDeviation,
155 ModuleConstants
const &... modules
158 drivetrainConstants, odometryUpdateFrequency,
159 odometryStandardDeviation, visionStandardDeviation,
162 _modules{CreateModuleArray(drivetrainConstants.CANBusName, modules...)},
163 _pigeon2{drivetrainConstants.Pigeon2Id,
std::string{drivetrainConstants.CANBusName}},
167 ctre::phoenix::StatusCode retval{};
170 if (retval.IsOK())
break;
172 if (!retval.IsOK()) {
173 printf(
"Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
183 template <
typename... ModuleConstants>
184 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> CreateModuleArray(
185 std::string_view canbusName,
186 ModuleConstants
const &... constants
188 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> modules;
189 modules.reserve(
sizeof...(ModuleConstants));
191 [&]<
size_t... Idxs>(std::index_sequence<Idxs...>) {
193 }(std::index_sequence_for<ModuleConstants...>{});
208 _simDrive.
Update(dt, supplyVoltage, _modules);
272 typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>,
273 typename = std::enable_if_t<!std::is_const_v<Request>>
278 [&request](
auto const ¶ms,
auto const &modules)
mutable {
279 return request.Apply(params, modules);
291 typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>,
292 typename = std::enable_if_t<!std::is_const_v<Request>>
297 [request=std::move(request)](
auto const ¶ms,
auto const &modules)
mutable {
298 return request.Apply(params, modules);
498 Pose2d visionRobotPose,
499 units::second_t timestamp,
500 std::array<double, 3> visionMeasurementStdDevs)
502 _drivetrain.
AddVisionMeasurement(std::move(visionRobotPose), timestamp, visionMeasurementStdDevs);
548 return *_modules.at(index);
559 return *_modules.at(index);
567 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>>
const &
GetModules()
const
ctre::phoenix::StatusCode Apply(const Pigeon2Configuration &configs)
Applies the contents of the specified config to the device.
Definition CorePigeon2.hpp:270
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:29
frc::Rotation3d GetRotation3d() const
Returns the orientation of the robot as a frc#Rotation3d created from the quaternion signals.
configs::Pigeon2Configurator & GetConfigurator()
Gets the configurator for this Pigeon2.
Definition CorePigeon2.hpp:1154
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2202
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:34
void Update(units::second_t dt, units::volt_t supplyVoltage, std::vector< std::unique_ptr< SwerveModule< DriveMotorT, SteerMotorT, EncoderT > > > const &modulesToApply)
Definition SimSwerveDrivetrain.hpp:119
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrain.hpp:52
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:236
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:497
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:94
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:66
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:226
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:150
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:69
virtual void UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:206
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:557
virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:461
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:216
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:328
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:339
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:598
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:117
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:246
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:434
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:275
std::vector< std::unique_ptr< SwerveModule< DriveMotorT, SteerMotorT, EncoderT > > > const & GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrain.hpp:567
virtual void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:374
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:418
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:577
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:294
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:256
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:398
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:310
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:546
virtual void SeedFieldCentric()
Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspe...
Definition SwerveDrivetrain.hpp:363
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:349
virtual ~SwerveDrivetrain()=default
frc::Rotation3d GetRotation3d() const
Gets the current orientation of the robot as a frc#Rotation3d from the Pigeon 2 quaternion values.
Definition SwerveDrivetrain.hpp:585
virtual void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrain.hpp:516
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:534
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:386
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:39
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
void Start()
Starts the odometry thread.
Definition SwerveDrivetrainImpl.hpp:70
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrainImpl.hpp:464
void SetControl(SwerveRequestFunc &&request)
Applies the specified control function to this swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:384
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:712
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrainImpl.hpp:353
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:416
void SeedFieldCentric()
Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspe...
Definition SwerveDrivetrainImpl.hpp:486
bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrainImpl.hpp:367
void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrainImpl.hpp:529
friend class OdometryThread
Definition SwerveDrivetrainImpl.hpp:170
void RegisterTelemetry(std::function< void(SwerveDriveState const &)> telemetryFunction)
Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry...
Definition SwerveDrivetrainImpl.hpp:435
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrainImpl.hpp:447
SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrainImpl.hpp:377
SwerveModuleImpl & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrainImpl.hpp:690
void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrainImpl.hpp:553
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrainImpl.hpp:570
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrainImpl.hpp:360
std::optional< Pose2d > SamplePoseAt(units::second_t timestamp)
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrainImpl.hpp:677
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrainImpl.hpp:346
void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrainImpl.hpp:657
void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrainImpl.hpp:497
void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrainImpl.hpp:513
void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrainImpl.hpp:599
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
std::optional< configs::Pigeon2Configuration > Pigeon2Configs
The configuration object to apply to the Pigeon2.
Definition SwerveDrivetrainConstants.hpp:43
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:121