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