CTRE Phoenix 6 C++ 25.1.0
Loading...
Searching...
No Matches
SwerveDrivetrain.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
14
15namespace ctre {
16namespace phoenix6 {
17namespace swerve {
18
19/**
20 * \brief Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
21 *
22 * This class handles the kinematics, configuration, and odometry of a
23 * swerve drive utilizing CTR Electronics devices. We recommend using
24 * the Swerve Project Generator in Tuner X to create a template project
25 * that demonstrates how to use this class.
26 *
27 * This class performs pose estimation internally using a separate odometry
28 * thread. Vision measurements can be added using AddVisionMeasurement.
29 * Other odometry APIs such as ResetPose are also available. The resulting
30 * pose estimate can be retrieved along with module states and other
31 * information using GetState. Additionally, the odometry thread synchronously
32 * provides all new state updates to a telemetry function registered with
33 * RegisterTelemetry.
34 *
35 * This class will construct the hardware devices internally, so the user
36 * only specifies the constants (IDs, PID gains, gear ratios, etc).
37 * Getters for these hardware devices are available.
38 *
39 * If using the generator, the order in which modules are constructed is
40 * Front Left, Front Right, Back Left, Back Right. This means if you need
41 * the Back Left module, call \c GetModule(2); to get the third (0-indexed)
42 * module.
43 */
44template <
45 typename DriveMotorT,
46 typename SteerMotorT,
47 typename EncoderT,
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>>
51>
53public:
54 /** \brief Performs swerve module updates in a separate thread to minimize latency. */
56
57 /**
58 * \brief Plain-Old-Data class holding the state of the swerve drivetrain.
59 * This encapsulates most data that is relevant for telemetry or
60 * decision-making from the Swerve Drive.
61 */
63
64protected:
65 /** \brief Number of times to attempt config applies. */
66 static constexpr int kNumConfigAttempts = 2;
67
68 /** \brief The underlying drivetrain instance. */
70
71private:
72 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> _modules;
73
74 hardware::Pigeon2 _pigeon2;
75 SimSwerveDrivetrain _simDrive;
76
77public:
78 /**
79 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
80 *
81 * This constructs the underlying hardware devices, so users should not construct
82 * the devices themselves. If they need the devices, they can access them
83 * through getters in the classes.
84 *
85 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
86 * \param modules Constants for each specific module
87 */
88 template <
89 typename... ModuleConstants,
90 typename = std::enable_if_t<std::conjunction_v<
91 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
92 >>
93 >
94 SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules) :
95 SwerveDrivetrain{drivetrainConstants, 0_Hz, modules...}
96 {}
97
98 /**
99 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
100 *
101 * This constructs the underlying hardware devices, so users should not construct
102 * the devices themselves. If they need the devices, they can access them
103 * through getters in the classes.
104 *
105 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
106 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
107 * unspecified or set to 0 Hz, this is 250 Hz on
108 * CAN FD, and 100 Hz on CAN 2.0.
109 * \param modules Constants for each specific module
110 */
111 template <
112 typename... ModuleConstants,
113 typename = std::enable_if_t<std::conjunction_v<
114 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
115 >>
116 >
118 SwerveDrivetrainConstants const &drivetrainConstants,
119 units::hertz_t odometryUpdateFrequency,
120 ModuleConstants const &... modules
121 ) :
122 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules...}
123 {}
124
125 /**
126 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
127 *
128 * This constructs the underlying hardware devices, so users should not construct
129 * the devices themselves. If they need the devices, they can access them
130 * through getters in the classes.
131 *
132 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
133 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
134 * unspecified or set to 0 Hz, this is 250 Hz on
135 * CAN FD, and 100 Hz on CAN 2.0.
136 * \param odometryStandardDeviation The standard deviation for odometry calculation
137 * in the form [x, y, theta]ᵀ, with units in meters
138 * and radians
139 * \param visionStandardDeviation The standard deviation for vision calculation
140 * in the form [x, y, theta]ᵀ, with units in meters
141 * and radians
142 * \param modules Constants for each specific module
143 */
144 template <
145 typename... ModuleConstants,
146 typename = std::enable_if_t<std::conjunction_v<
147 std::is_same< ModuleConstants, SwerveModuleConstants<configs::TalonFXConfiguration, configs::TalonFXConfiguration, configs::CANcoderConfiguration> >...
148 >>
149 >
151 SwerveDrivetrainConstants const &drivetrainConstants,
152 units::hertz_t odometryUpdateFrequency,
153 std::array<double, 3> const &odometryStandardDeviation,
154 std::array<double, 3> const &visionStandardDeviation,
155 ModuleConstants const &... modules
156 ) :
158 drivetrainConstants, odometryUpdateFrequency,
159 odometryStandardDeviation, visionStandardDeviation,
160 modules...
161 },
162 _modules{CreateModuleArray(drivetrainConstants.CANBusName, modules...)},
163 _pigeon2{drivetrainConstants.Pigeon2Id, std::string{drivetrainConstants.CANBusName}},
164 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
165 {
166 if (drivetrainConstants.Pigeon2Configs) {
167 ctre::phoenix::StatusCode retval{};
168 for (int i = 0; i < kNumConfigAttempts; ++i) {
169 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
170 if (retval.IsOK()) break;
171 }
172 if (!retval.IsOK()) {
173 printf("Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
174 }
175 }
176 /* do not start thread until after applying Pigeon 2 configs */
178 }
179
180 virtual ~SwerveDrivetrain() = default;
181
182private:
183 template <typename... ModuleConstants>
184 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> CreateModuleArray(
185 std::string_view canbusName,
186 ModuleConstants const &... constants
187 ) {
188 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> modules;
189 modules.reserve(sizeof...(ModuleConstants));
190
191 [&]<size_t... Idxs>(std::index_sequence<Idxs...>) {
192 (modules.emplace_back(std::make_unique<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>(constants, canbusName, _drivetrain.GetModule(Idxs))), ...);
193 }(std::index_sequence_for<ModuleConstants...>{});
194
195 return modules;
196 }
197
198public:
199 /**
200 * \brief Updates all the simulation state variables for this
201 * drivetrain class. User provides the update variables for the simulation.
202 *
203 * \param dt time since last update call
204 * \param supplyVoltage voltage as seen at the motor controllers
205 */
206 virtual void UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
207 {
208 _simDrive.Update(dt, supplyVoltage, _modules);
209 }
210
211 /**
212 * \brief Gets whether the drivetrain is on a CAN FD bus.
213 *
214 * \returns true if on CAN FD
215 */
216 bool IsOnCANFD() const
217 {
218 return _drivetrain.IsOnCANFD();
219 }
220
221 /**
222 * \brief Gets the target odometry update frequency.
223 *
224 * \returns Target odometry update frequency
225 */
226 units::hertz_t GetOdometryFrequency() const
227 {
228 return _drivetrain.GetOdometryFrequency();
229 }
230
231 /**
232 * \brief Gets a reference to the odometry thread.
233 *
234 * \returns Odometry thread
235 */
237 {
238 return _drivetrain.GetOdometryThread();
239 }
240
241 /**
242 * \brief Check if the odometry is currently valid.
243 *
244 * \returns True if odometry is valid
245 */
246 virtual bool IsOdometryValid() const
247 {
248 return _drivetrain.IsOdometryValid();
249 }
250
251 /**
252 * \brief Gets a reference to the kinematics used for the drivetrain.
253 *
254 * \returns Swerve kinematics
255 */
257 {
258 return _drivetrain.GetKinematics();
259 }
260
261 /**
262 * \brief Applies the specified control request to this swerve drivetrain.
263 *
264 * This captures the swerve request by reference, so it must live for
265 * at least as long as the drivetrain. This can be done by storing the
266 * request as a member variable of your drivetrain subsystem or robot.
267 *
268 * \param request Request to apply
269 */
270 template <
271 typename Request,
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>>
274 >
275 void SetControl(Request &request)
276 {
277 _drivetrain.SetControl(
278 [&request](auto const &params, auto const &modules) mutable {
279 return request.Apply(params, modules);
280 }
281 );
282 }
283
284 /**
285 * \brief Applies the specified control request to this swerve drivetrain.
286 *
287 * \param request Request to apply
288 */
289 template <
290 typename Request,
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>>
293 >
294 void SetControl(Request &&request)
295 {
296 _drivetrain.SetControl(
297 [request=std::move(request)](auto const &params, auto const &modules) mutable {
298 return request.Apply(params, modules);
299 }
300 );
301 }
302
303 /**
304 * \brief Gets the current state of the swerve drivetrain.
305 * This includes information such as the pose estimate,
306 * module states, and chassis speeds.
307 *
308 * \returns Current state of the drivetrain
309 */
311 {
312 return _drivetrain.GetState();
313 }
314
315 /**
316 * \brief Register the specified lambda to be executed whenever the SwerveDriveState
317 * is updated in the odometry thread.
318 *
319 * It is imperative that this function is cheap, as it will be executed synchronously
320 * with the odometry call; if this takes a long time, it may negatively impact the
321 * odometry of this stack.
322 *
323 * This can also be used for logging data if the function performs logging instead of telemetry.
324 * Additionally, the SwerveDriveState object can be cloned and stored for later processing.
325 *
326 * \param telemetryFunction Function to call for telemetry or logging
327 */
328 virtual void RegisterTelemetry(std::function<void(SwerveDriveState const &)> telemetryFunction)
329 {
330 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
331 }
332
333 /**
334 * \brief Configures the neutral mode to use for all modules' drive motors.
335 *
336 * \param neutralMode The drive motor neutral mode
337 * \returns Status code of the first failed config call, or OK if all succeeded
338 */
340 {
341 return _drivetrain.ConfigNeutralMode(neutralMode);
342 }
343
344 /**
345 * \brief Zero's this swerve drive's odometry entirely.
346 *
347 * This will zero the entire odometry, and place the robot at 0,0
348 */
349 virtual void TareEverything()
350 {
351 _drivetrain.TareEverything();
352 }
353
354 /**
355 * \brief Resets the rotation of the robot pose to 0 from the
356 * requests#ForwardPerspectiveValue#OperatorPerspective perspective.
357 * This makes the current orientation of the robot X forward for
358 * field-centric maneuvers.
359 *
360 * This is equivalent to calling ResetRotation with the operator
361 * perspective rotation.
362 */
363 virtual void SeedFieldCentric()
364 {
365 _drivetrain.SeedFieldCentric();
366 }
367
368 /**
369 * \brief Resets the pose of the robot. The pose should be from the
370 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
371 *
372 * \param pose Pose to make the current pose
373 */
374 virtual void ResetPose(Pose2d const &pose)
375 {
376 _drivetrain.ResetPose(pose);
377 }
378
379 /**
380 * \brief Resets the translation of the robot pose without affecting rotation.
381 * The translation should be from the requests#ForwardPerspectiveValue#BlueAlliance
382 * perspective.
383 *
384 * \param translation Translation to make the current translation
385 */
386 virtual void ResetTranslation(Translation2d const &translation)
387 {
388 _drivetrain.ResetTranslation(translation);
389 }
390
391 /**
392 * \brief Resets the rotation of the robot pose without affecting translation.
393 * The rotation should be from the requests#ForwardPerspectiveValue#BlueAlliance
394 * perspective.
395 *
396 * \param rotation Rotation to make the current rotation
397 */
398 virtual void ResetRotation(Rotation2d const &rotation)
399 {
400 _drivetrain.ResetRotation(rotation);
401 }
402
403 /**
404 * \brief Takes the requests#ForwardPerspectiveValue#BlueAlliance perpective
405 * direction and treats it as the forward direction for
406 * requests#ForwardPerspectiveValue#OperatorPerspective.
407 *
408 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
409 * If the operator is in the Red Alliance Station, this should be 180 degrees.
410 *
411 * This does not change the robot pose, which is in the
412 * requests#ForwardPerspectiveValue#BlueAlliance perspective.
413 * As a result, the robot pose may need to be reset using ResetPose.
414 *
415 * \param fieldDirection Heading indicating which direction is forward from
416 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
417 */
418 virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
419 {
420 _drivetrain.SetOperatorPerspectiveForward(fieldDirection);
421 }
422
423 /**
424 * \brief Returns the requests#ForwardPerspectiveValue#BlueAlliance perpective
425 * direction that is treated as the forward direction for
426 * requests#ForwardPerspectiveValue#OperatorPerspective.
427 *
428 * If the operator is in the Blue Alliance Station, this should be 0 degrees.
429 * If the operator is in the Red Alliance Station, this should be 180 degrees.
430 *
431 * \returns Heading indicating which direction is forward from
432 * the requests#ForwardPerspectiveValue#BlueAlliance perspective
433 */
435 {
436 return _drivetrain.GetOperatorForwardDirection();
437 }
438
439 /**
440 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
441 * odometry pose estimate while still accounting for measurement noise.
442 *
443 * This method can be called as infrequently as you want, as long as you are
444 * calling impl#SwerveDrivePoseEstimator#Update every loop.
445 *
446 * To promote stability of the pose estimate and make it robust to bad vision
447 * data, we recommend only adding vision measurements that are already within
448 * one meter or so of the current pose estimate.
449 *
450 * \param visionRobotPose The pose of the robot as measured by the
451 * vision camera.
452 * \param timestamp The timestamp of the vision measurement in
453 * seconds. Note that you must use a timestamp with an
454 * epoch since system startup (i.e., the epoch of this
455 * timestamp is the same epoch as utils#GetCurrentTime).
456 * This means that you should use utils#GetCurrentTime
457 * as your time source in this case.
458 * An FPGA timestamp can be converted to the correct
459 * timebase using utils#FPGAToCurrentTime.
460 */
461 virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
462 {
463 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp);
464 }
465
466 /**
467 * \brief Adds a vision measurement to the Kalman Filter. This will correct the
468 * odometry pose estimate while still accounting for measurement noise.
469 *
470 * This method can be called as infrequently as you want, as long as you are
471 * calling impl#SwerveDrivePoseEstimator#Update every loop.
472 *
473 * To promote stability of the pose estimate and make it robust to bad vision
474 * data, we recommend only adding vision measurements that are already within
475 * one meter or so of the current pose estimate.
476 *
477 * Note that the vision measurement standard deviations passed into this method
478 * will continue to apply to future measurements until a subsequent call to
479 * #SetVisionMeasurementStdDevs or this method.
480 *
481 * \param visionRobotPose The pose of the robot as measured by the
482 * vision camera.
483 * \param timestamp The timestamp of the vision measurement in
484 * seconds. Note that you must use a timestamp with an
485 * epoch since system startup (i.e., the epoch of this
486 * timestamp is the same epoch as utils#GetCurrentTime).
487 * This means that you should use utils#GetCurrentTime
488 * as your time source in this case.
489 * An FPGA timestamp can be converted to the correct
490 * timebase using utils#FPGAToCurrentTime.
491 * \param visionMeasurementStdDevs Standard deviations of the vision pose
492 * measurement (x position in meters, y position
493 * in meters, and heading in radians). Increase
494 * these numbers to trust the vision pose
495 * measurement less.
496 */
498 Pose2d visionRobotPose,
499 units::second_t timestamp,
500 std::array<double, 3> visionMeasurementStdDevs)
501 {
502 _drivetrain.AddVisionMeasurement(std::move(visionRobotPose), timestamp, visionMeasurementStdDevs);
503 }
504
505 /**
506 * \brief Sets the pose estimator's trust of global measurements. This might be used to
507 * change trust in vision measurements after the autonomous period, or to change
508 * trust as distance to a vision target increases.
509 *
510 * \param visionMeasurementStdDevs Standard deviations of the vision
511 * measurements. Increase these
512 * numbers to trust global measurements from
513 * vision less. This matrix is in the form [x,
514 * y, theta]ᵀ, with units in meters and radians.
515 */
516 virtual void SetVisionMeasurementStdDevs(std::array<double, 3> visionMeasurementStdDevs)
517 {
518 _drivetrain.SetVisionMeasurementStdDevs(visionMeasurementStdDevs);
519 }
520
521 /**
522 * \brief Return the pose at a given timestamp, if the buffer is not empty.
523 *
524 * \param timestamp The pose's timestamp. Note that you must use a timestamp
525 * with an epoch since system startup (i.e., the epoch of
526 * this timestamp is the same epoch as utils#GetCurrentTime).
527 * This means that you should use utils#GetCurrentTime
528 * as your time source in this case.
529 * An FPGA timestamp can be converted to the correct
530 * timebase using utils#FPGAToCurrentTime.
531 * \returns The pose at the given timestamp (or std::nullopt if the buffer is
532 * empty).
533 */
534 virtual std::optional<Pose2d> SamplePoseAt(units::second_t timestamp)
535 {
536 return _drivetrain.SamplePoseAt(timestamp);
537 }
538
539 /**
540 * \brief Get a reference to the module at the specified index.
541 * The index corresponds to the module described in the constructor.
542 *
543 * \param index Which module to get
544 * \returns Reference to SwerveModule
545 */
547 {
548 return *_modules.at(index);
549 }
550 /**
551 * \brief Get a reference to the module at the specified index.
552 * The index corresponds to the module described in the constructor.
553 *
554 * \param index Which module to get
555 * \returns Reference to SwerveModule
556 */
558 {
559 return *_modules.at(index);
560 }
561 /**
562 * \brief Get a reference to the full array of modules.
563 * The indexes correspond to the module described in the constructor.
564 *
565 * \returns Reference to the SwerveModule array
566 */
567 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> const &GetModules() const
568 {
569 return _modules;
570 }
571
572 /**
573 * \brief Gets the locations of the swerve modules.
574 *
575 * \returns Reference to the array of swerve module locations
576 */
577 std::vector<Translation2d> const &GetModuleLocations() const { return _drivetrain.GetModuleLocations(); }
578
579 /**
580 * \brief Gets the current orientation of the robot as a frc#Rotation3d from
581 * the Pigeon 2 quaternion values.
582 *
583 * \returns The robot orientation as a frc#Rotation3d
584 */
585 frc::Rotation3d GetRotation3d() const
586 {
587 return _pigeon2.GetRotation3d();
588 }
589
590 /**
591 * \brief Gets this drivetrain's Pigeon 2 reference.
592 *
593 * This should be used only to access signals and change configurations that the
594 * swerve drivetrain does not configure itself.
595 *
596 * \returns This drivetrain's Pigeon 2 reference
597 */
599 {
600 return _pigeon2;
601 }
602};
603
604}
605}
606}
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
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
Definition span.hpp:401
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