CTRE Phoenix 6 C++ 26.0.0-beta-1
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 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
46 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
47 typename EncoderT
48>
49 requires std::same_as<EncoderT, hardware::CANcoder> ||
50 std::same_as<EncoderT, hardware::CANdi> ||
51 std::same_as<EncoderT, hardware::TalonFXS>
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;
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 std::same_as<SwerveModuleConstants<
90 typename DriveMotorT::Configuration,
91 typename SteerMotorT::Configuration,
92 typename EncoderT::Configuration
93 >>... ModuleConstants
94 >
95 SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules) :
96 SwerveDrivetrain{drivetrainConstants, 0_Hz, modules...}
97 {}
98
99 /**
100 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
101 *
102 * This constructs the underlying hardware devices, so users should not construct
103 * the devices themselves. If they need the devices, they can access them
104 * through getters in the classes.
105 *
106 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
107 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
108 * unspecified or set to 0 Hz, this is 250 Hz on
109 * CAN FD, and 100 Hz on CAN 2.0.
110 * \param modules Constants for each specific module
111 */
112 template <
113 std::same_as<SwerveModuleConstants<
114 typename DriveMotorT::Configuration,
115 typename SteerMotorT::Configuration,
116 typename EncoderT::Configuration
117 >>... ModuleConstants
118 >
120 SwerveDrivetrainConstants const &drivetrainConstants,
121 units::hertz_t odometryUpdateFrequency,
122 ModuleConstants const &... modules
123 ) :
124 SwerveDrivetrain{drivetrainConstants, odometryUpdateFrequency, std::array{0.1, 0.1, 0.1}, std::array{0.9, 0.9, 0.9}, modules...}
125 {}
126
127 /**
128 * \brief Constructs a CTRE SwerveDrivetrain using the specified constants.
129 *
130 * This constructs the underlying hardware devices, so users should not construct
131 * the devices themselves. If they need the devices, they can access them
132 * through getters in the classes.
133 *
134 * \param drivetrainConstants Drivetrain-wide constants for the swerve drive
135 * \param odometryUpdateFrequency The frequency to run the odometry loop. If
136 * unspecified or set to 0 Hz, this is 250 Hz on
137 * CAN FD, and 100 Hz on CAN 2.0.
138 * \param odometryStandardDeviation The standard deviation for odometry calculation
139 * in the form [x, y, theta]ᵀ, with units in meters
140 * and radians
141 * \param visionStandardDeviation The standard deviation for vision calculation
142 * in the form [x, y, theta]ᵀ, with units in meters
143 * and radians
144 * \param modules Constants for each specific module
145 */
146 template <
147 std::same_as<SwerveModuleConstants<
148 typename DriveMotorT::Configuration,
149 typename SteerMotorT::Configuration,
150 typename EncoderT::Configuration
151 >>... ModuleConstants
152 >
154 SwerveDrivetrainConstants const &drivetrainConstants,
155 units::hertz_t odometryUpdateFrequency,
156 std::array<double, 3> const &odometryStandardDeviation,
157 std::array<double, 3> const &visionStandardDeviation,
158 ModuleConstants const &... modules
159 ) :
161 drivetrainConstants, odometryUpdateFrequency,
162 odometryStandardDeviation, visionStandardDeviation,
163 std::span<SwerveModuleConstants<typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration> const>{
164 std::array{modules...}
165 }
166 },
167 _modules{CreateModuleArray(CANBus{drivetrainConstants.CANBusName}, modules...)},
168 _pigeon2{drivetrainConstants.Pigeon2Id, CANBus{drivetrainConstants.CANBusName}},
169 _simDrive{_drivetrain.GetModuleLocations(), _pigeon2.GetSimState(), modules...}
170 {
171 if (drivetrainConstants.Pigeon2Configs) {
173 for (int i = 0; i < kNumConfigAttempts; ++i) {
174 retval = GetPigeon2().GetConfigurator().Apply(*drivetrainConstants.Pigeon2Configs);
175 if (retval.IsOK()) break;
176 }
177 if (!retval.IsOK()) {
178 printf("Pigeon2 ID %d failed config with error: %s\n", GetPigeon2().GetDeviceID(), retval.GetName());
179 }
180 }
181 /* do not start thread until after applying Pigeon 2 configs */
182 GetOdometryThread().Start();
183 }
184
185 virtual ~SwerveDrivetrain() = default;
186
187private:
188 template <typename... ModuleConstants>
189 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> CreateModuleArray(
190 CANBus canbus,
191 ModuleConstants const &... constants
192 ) {
193 std::vector<std::unique_ptr<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>> modules;
194 modules.reserve(sizeof...(ModuleConstants));
195
196 [&]<size_t... Idxs>(std::index_sequence<Idxs...>) {
197 (modules.emplace_back(std::make_unique<SwerveModule<DriveMotorT, SteerMotorT, EncoderT>>(constants, canbus, _drivetrain.GetModule(Idxs))), ...);
198 }(std::index_sequence_for<ModuleConstants...>{});
199
200 return modules;
201 }
202
203public:
204 /**
205 * \brief Updates all the simulation state variables for this
206 * drivetrain class. User provides the update variables for the simulation.
207 *
208 * \param dt time since last update call
209 * \param supplyVoltage voltage as seen at the motor controllers
210 */
211 virtual void UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
212 {
213 _simDrive.Update(dt, supplyVoltage, _modules);
214 }
215
216 /**
217 * \brief Gets whether the drivetrain is on a CAN FD bus.
218 *
219 * \returns true if on CAN FD
220 */
221 bool IsOnCANFD() const
222 {
223 return _drivetrain.IsOnCANFD();
224 }
225
226 /**
227 * \brief Gets the target odometry update frequency.
228 *
229 * \returns Target odometry update frequency
230 */
231 units::hertz_t GetOdometryFrequency() const
232 {
233 return _drivetrain.GetOdometryFrequency();
234 }
235
236 /**
237 * \brief Gets a reference to the odometry thread.
238 *
239 * \returns Odometry thread
240 */
242 {
243 return _drivetrain.GetOdometryThread();
244 }
245
246 /**
247 * \brief Check if the odometry is currently valid.
248 *
249 * \returns True if odometry is valid
250 */
251 virtual bool IsOdometryValid() const
252 {
253 return _drivetrain.IsOdometryValid();
254 }
255
256 /**
257 * \brief Gets a reference to the kinematics used for the drivetrain.
258 *
259 * \returns Swerve kinematics
260 */
262 {
263 return _drivetrain.GetKinematics();
264 }
265
266 /**
267 * \brief Applies the specified control request to this swerve drivetrain.
268 *
269 * This captures the swerve request by reference, so it must live for
270 * at least as long as the drivetrain. This can be done by storing the
271 * request as a member variable of your drivetrain subsystem or robot.
272 *
273 * \param request Request to apply
274 */
275 template <std::derived_from<requests::SwerveRequest> Request>
276 requires (!std::is_const_v<Request>)
277 void SetControl(Request &request)
278 {
279 _drivetrain.SetControl(
280 [&request](auto const &params, auto modules) mutable {
281 return request.Apply(params, modules);
282 }
283 );
284 }
285
286 /**
287 * \brief Applies the specified control request to this swerve drivetrain.
288 *
289 * \param request Request to apply
290 */
291 template <std::derived_from<requests::SwerveRequest> Request>
292 requires (!std::is_const_v<Request>)
293 void SetControl(Request &&request)
294 {
295 _drivetrain.SetControl(
296 [request=std::move(request)](auto const &params, auto modules) mutable {
297 return request.Apply(params, modules);
298 }
299 );
300 }
301
302 /**
303 * \brief Gets the current state of the swerve drivetrain.
304 * This includes information such as the pose estimate,
305 * module states, and chassis speeds.
306 *
307 * \returns Current state of the drivetrain
308 */
310 {
311 return _drivetrain.GetState();
312 }
313
314 /**
315 * \brief Register the specified lambda to be executed whenever the SwerveDriveState
316 * is updated in the odometry thread.
317 *
318 * It is imperative that this function is cheap, as it will be executed synchronously
319 * with the odometry call; if this takes a long time, it may negatively impact the
320 * odometry of this stack.
321 *
322 * This can also be used for logging data if the function performs logging instead of telemetry.
323 * Additionally, the SwerveDriveState object can be cloned and stored for later processing.
324 *
325 * \param telemetryFunction Function to call for telemetry or logging
326 */
327 virtual void RegisterTelemetry(std::function<void(SwerveDriveState const &)> telemetryFunction)
328 {
329 _drivetrain.RegisterTelemetry(std::move(telemetryFunction));
330 }
331
332 /**
333 * \brief Configures the neutral mode to use for all modules' drive motors.
334 *
335 * This will wait up to 0.100 seconds (100ms) by default.
336 *
337 * \param neutralMode The drive motor neutral mode
338 * \returns Status code of the first failed config call, or OK if all succeeded
339 */
341 {
342 return _drivetrain.ConfigNeutralMode(neutralMode);
343 }
344
345 /**
346 * \brief Configures the neutral mode to use for all modules' drive motors.
347 *
348 * \param neutralMode The drive motor neutral mode
349 * \param timeoutSeconds Maximum amount of time to wait when performing each configuration
350 * \returns Status code of the first failed config call, or OK if all succeeded
351 */
352 virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds)
353 {
354 return _drivetrain.ConfigNeutralMode(neutralMode, timeoutSeconds);
355 }
356
357 /**
358 * \brief Zero's this swerve drive's odometry entirely.
359 *
360 * This will zero the entire odometry, and place the robot at 0,0
361 */
362 virtual void TareEverything()
363 {
364 _drivetrain.TareEverything();
365 }
366
367 /**
368 * \brief Resets the rotation of the robot pose to the given value
369 * from the requests#ForwardPerspectiveValue#OperatorPerspective
370 * perspective. This makes the current orientation of the robot minus
371 * `rotation` the X forward for field-centric maneuvers.
372 *
373 * This is equivalent to calling ResetRotation with `rotation +
374 * GetOperatorForwardDirection()`.
375 *
376 * \param rotation Rotation to make the current rotation
377 */
378 virtual void SeedFieldCentric(Rotation2d const &rotation = Rotation2d{})
379 {
380 _drivetrain.SeedFieldCentric(rotation);
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) const
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::span<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 virtual 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 * \brief Gets this drivetrain's Pigeon 2 reference.
630 *
631 * This should be used only to access signals and change configurations that the
632 * swerve drivetrain does not configure itself.
633 *
634 * \returns This drivetrain's Pigeon 2 reference
635 */
637 {
638 return _pigeon2;
639 }
640};
641
642}
643}
644}
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Class description for the Pigeon 2 IMU sensor that measures orientation.
Definition Pigeon2.hpp:34
Simplified swerve drive simulation class.
Definition SimSwerveDrivetrain.hpp:42
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrain.hpp:52
virtual void SetOperatorPerspectiveForward(Rotation2d fieldDirection)
Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the f...
Definition SwerveDrivetrain.hpp:433
virtual void AddVisionMeasurement(Pose2d visionRobotPose, units::second_t timestamp)
Adds a vision measurement to the Kalman Filter.
Definition SwerveDrivetrain.hpp:475
std::span< 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 UpdateSimState(units::second_t dt, units::volt_t supplyVoltage)
Updates all the simulation state variables for this drivetrain class.
Definition SwerveDrivetrain.hpp:211
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > & GetModule(size_t index)
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:572
OdometryThread & GetOdometryThread()
Gets a reference to the odometry thread.
Definition SwerveDrivetrain.hpp:241
virtual void ResetTranslation(Translation2d const &translation)
Resets the translation of the robot pose without affecting rotation.
Definition SwerveDrivetrain.hpp:401
virtual void TareEverything()
Zero's this swerve drive's odometry entirely.
Definition SwerveDrivetrain.hpp:362
virtual void SetStateStdDevs(std::array< double, 3 > const &stateStdDevs)
Sets the pose estimator's trust in robot odometry.
Definition SwerveDrivetrain.hpp:542
void SetControl(Request &request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:277
void SetControl(Request &&request)
Applies the specified control request to this swerve drivetrain.
Definition SwerveDrivetrain.hpp:293
virtual std::optional< Pose2d > SamplePoseAt(units::second_t timestamp) const
Return the pose at a given timestamp, if the buffer is not empty.
Definition SwerveDrivetrain.hpp:560
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
virtual bool IsOdometryValid() const
Check if the odometry is currently valid.
Definition SwerveDrivetrain.hpp:251
impl::SwerveDriveKinematics const & GetKinematics() const
Gets a reference to the kinematics used for the drivetrain.
Definition SwerveDrivetrain.hpp:261
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:340
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:119
virtual ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds)
Configures the neutral mode to use for all modules' drive motors.
Definition SwerveDrivetrain.hpp:352
SwerveDriveState GetState() const
Gets the current state of the swerve drivetrain.
Definition SwerveDrivetrain.hpp:309
units::hertz_t GetOdometryFrequency() const
Gets the target odometry update frequency.
Definition SwerveDrivetrain.hpp:231
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:378
virtual 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 void ResetPose(Pose2d const &pose)
Resets the pose of the robot.
Definition SwerveDrivetrain.hpp:389
bool IsOnCANFD() const
Gets whether the drivetrain is on a CAN FD bus.
Definition SwerveDrivetrain.hpp:221
SwerveDrivetrain(SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
Constructs a CTRE SwerveDrivetrain using the specified constants.
Definition SwerveDrivetrain.hpp:95
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:153
virtual void ResetRotation(Rotation2d const &rotation)
Resets the rotation of the robot pose without affecting translation.
Definition SwerveDrivetrain.hpp:413
hardware::Pigeon2 & GetPigeon2()
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:624
SwerveModule< DriveMotorT, SteerMotorT, EncoderT > const & GetModule(size_t index) const
Get a reference to the module at the specified index.
Definition SwerveDrivetrain.hpp:583
hardware::Pigeon2 const & GetPigeon2() const
Gets this drivetrain's Pigeon 2 reference.
Definition SwerveDrivetrain.hpp:636
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveDrivetrain.hpp:66
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:327
impl::SwerveDrivetrainImpl _drivetrain
The underlying drivetrain instance.
Definition SwerveDrivetrain.hpp:69
std::vector< Translation2d > const & GetModuleLocations() const
Gets the locations of the swerve modules.
Definition SwerveDrivetrain.hpp:603
Rotation2d GetOperatorForwardDirection() const
Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as t...
Definition SwerveDrivetrain.hpp:449
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:52
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:32
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:29
friend class OdometryThread
Definition SwerveDrivetrainImpl.hpp:164
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
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
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148
Plain-Old-Data class holding the state of the swerve drivetrain.
Definition SwerveDrivetrainImpl.hpp:115