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>
90 std::vector<std::unique_ptr<SwerveModule>> _modules;
106 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
124 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
127 wpi::units::hertz_t odometryUpdateFrequency,
128 ModuleConstants
const &... modules
130 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules...}
152 template <std::same_as<SwerveModuleConstants>... ModuleConstants>
155 wpi::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,
165 _modules{CreateModuleArray(
CANBus{drivetrainConstants.CANBusName}, modules...)},
166 _pigeon2{drivetrainConstants.Pigeon2Id, CANBus{drivetrainConstants.CANBusName}},
167 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
169 if (drivetrainConstants.Pigeon2Configs) {
170 ctre::phoenix::StatusCode retval{};
171 for (
int i = 0; i < kNumConfigAttempts; ++i) {
172 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
173 if (retval.
IsOK())
break;
175 if (!retval.
IsOK()) {
176 printf(
"Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.
GetName());
180 GetOdometryThread().Start();
186 template <
typename... ModuleConstants>
187 std::vector<std::unique_ptr<SwerveModule>> CreateModuleArray(
189 ModuleConstants
const &... constants
191 std::vector<std::unique_ptr<SwerveModule>> modules;
192 modules.reserve(
sizeof...(ModuleConstants));
194 [&]<
size_t... Idxs>(std::index_sequence<Idxs...>) {
195 (modules.emplace_back(std::make_unique<SwerveModule>(constants, canbus,
_drivetrain.GetModule(Idxs))), ...);
196 }(std::index_sequence_for<ModuleConstants...>{});
209 virtual void UpdateSimState(wpi::units::second_t dt, wpi::units::volt_t supplyVoltage)
211 _simDrive.Update(dt, supplyVoltage, _modules);
228 std::vector<hardware::traits::CommonDevice *> devices;
229 devices.reserve(_modules.size() * 3 + 1);
231 for (
auto &module : _modules) {
232 devices.push_back(&module->GetDriveMotor());
233 devices.push_back(&module->GetSteerMotor());
234 devices.push_back(&module->GetEncoder());
256 std::vector<hardware::traits::CommonDevice *> devices;
257 devices.reserve(_modules.size() * 3 + 1);
259 for (
auto &module : _modules) {
260 devices.push_back(&module->GetDriveMotor());
261 devices.push_back(&module->GetSteerMotor());
262 devices.push_back(&module->GetEncoder());
326 template <std::derived_from<requests::SwerveRequest> Request>
327 requires (!std::is_const_v<Request>)
331 [&request](
auto const ¶ms,
auto modules)
mutable {
332 return request.Apply(params, modules);
342 template <std::derived_from<requests::SwerveRequest> Request>
343 requires (!std::is_const_v<Request>)
347 [request=std::move(request)](
auto const ¶ms,
auto modules)
mutable {
348 return request.Apply(params, modules);
380 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
405 return _drivetrain.ConfigNeutralMode(neutralMode, timeoutSeconds);
431 _drivetrain.SeedFieldCentric(rotation);
486 _drivetrain.SetOperatorPerspectiveForward(fieldDirection);
526 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp);
558 Pose2d visionRobotPose,
559 wpi::units::second_t timestamp,
560 std::array<double, 3> visionMeasurementStdDevs)
562 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp, visionMeasurementStdDevs);
578 _drivetrain.SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
605 virtual std::optional<Pose2d>
SamplePoseAt(wpi::units::second_t timestamp)
const
619 return *_modules.at(index);
630 return *_modules.at(index);
638 std::span<std::unique_ptr<SwerveModule>
const>
GetModules()
const
658 return _pigeon2.GetRotation3d();
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
static ctre::phoenix::StatusCode OptimizeBusUtilizationForAll(Devices &... devices)
Optimizes the bus utilization of the provided devices by reducing the update frequencies of their sta...
Definition ParentDevice.hpp:287
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:27
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:42
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:484
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, wpi::units::second_t timeoutSeconds)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:403
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:292
virtual void UpdateSimState(wpi::units::second_t dt, wpi::units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:209
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:452
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:413
ctre::phoenix::StatusCode OptimizeBusUtilization()
Optimizes the bus utilization of all devices in the swerve drivetrain by reducing the update frequenc...
Definition SwerveDrivetrain.hpp:226
impl::SwerveDrivetrainImpl::OdometryThread OdometryThread
Performs swerve module updates in a separate thread to minimize latency.
Definition SwerveDrivetrain.hpp:55
swerve::SwerveModule< DriveMotorT, SteerMotorT, EncoderT > SwerveModule
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveDrivetrain.hpp:75
virtual std::optional< Pose2d > SamplePoseAt(wpi::units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrain.hpp:605
virtual void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrain.hpp:589
SwerveModule const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:628
ctre::phoenix::StatusCode OptimizeBusUtilization(wpi::units::hertz_t optimizedFreqHz)
Optimizes the bus utilization of all devices in the swerve drivetrain by reducing the update frequenc...
Definition SwerveDrivetrain.hpp:254
SwerveModule & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:617
std::span< std::unique_ptr< SwerveModule > const > GetModules() const
Get a reference to the full array of modules.
Definition SwerveDrivetrain.hpp:638
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:328
virtual void AddVisionMeasurement(Pose2d visionRobotPose, wpi::units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:557
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:344
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:302
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, wpi::units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:125
virtual void AddVisionMeasurement(Pose2d visionRobotPose, wpi::units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:524
virtual wpi::math::Rotation3d GetRotation3d() const
Gets the current orientation of the robot as a wpi::math::Rotation3d from the Pigeon 2 quaternion val...
Definition SwerveDrivetrain.hpp:656
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:312
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:391
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:360
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:429
virtual void SetVisionMeasurementStdDevs(std::array< double, 3 > visionMeasurementStdDevs)
Sets the pose estimator's trust of global measurements.
Definition SwerveDrivetrain.hpp:576
virtual void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:440
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:272
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:107
impl::SwerveDrivetrainImpl::SwerveDriveState SwerveDriveState
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:62
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, wpi::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
SwerveModule::Constants SwerveModuleConstants
All constants for a swerve module.
Definition SwerveDrivetrain.hpp:80
virtual ~SwerveDrivetrain()=default
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:464
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:669
hardware::Pigeon2 const & GetPigeon2() const
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:681
wpi::units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:282
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:84
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:378
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:87
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:648
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:500
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:52
SwerveModuleConstants< typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration > Constants
All constants for a swerve module.
Definition SwerveModule.hpp:62
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:33
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
constexpr const char * GetName() const
Gets the name of this StatusCode.
Definition StatusCodes.h:867
constexpr bool IsOK() const
Definition StatusCodes.h:860
Definition SwerveModule.hpp:28
Definition ExternalFeedbackConfigs.hpp:16
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
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:116