CTRE Phoenix 6 C++ 26.0.0-beta-1
Loading...
Searching...
No Matches
SwerveRequest.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
11
12namespace ctre {
13namespace phoenix6 {
14namespace swerve {
15namespace requests {
16
17/**
18 * \brief In field-centric control, the direction of "forward" is sometimes different
19 * depending on perspective. This addresses which forward to use.
20 */
22 /**
23 * \brief "Forward" (positive X) is determined from the operator's perspective.
24 * This is important for most teleop driven field-centric requests, where positive
25 * X means to drive away from the operator.
26 *
27 * Important: Users must specify the OperatorPerspective in the SwerveDrivetrain object
28 */
30 /**
31 * \brief "Forward" (positive X) is always from the perspective of the blue alliance (i.e.
32 * towards the red alliance). This is important in situations such as path following where
33 * positive X is always from the blue alliance perspective, regardless of where the operator
34 * is physically located.
35 */
36 BlueAlliance = 1,
37};
38
39/**
40 * \brief Container for all the Swerve Requests. Use this to find all applicable swerve
41 * drive requests.
42 *
43 * This is also an interface common to all swerve drive control requests that
44 * allow the request to calculate the state to apply to the modules.
45 */
47public:
49
50 virtual ~SwerveRequest() = default;
51
52 /**
53 * \brief Applies this swerve request to the given modules.
54 * This is typically called by the SwerveDrivetrain.
55 *
56 * \param parameters Parameters the control request needs to calculate the module state
57 * \param modulesToApply Modules to which the control request is applied
58 * \returns Status code of sending the request
59 */
60 virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) = 0;
61};
62
63/**
64 * \brief Does nothing to the swerve module state. This is the default state of a newly
65 * created swerve drive mechanism.
66 */
67class Idle : public SwerveRequest {
68public:
69 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> ) override
70 {
72 }
73};
74
75/**
76 * \brief Sets the swerve drive module states to point inward on the
77 * robot in an "X" fashion, creating a natural brake which will
78 * oppose any motion.
79 */
81public:
82 /**
83 * \brief The type of control request to use for the drive motor.
84 */
86 /**
87 * \brief The type of control request to use for the steer motor.
88 */
90
91 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
92 {
93 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
96 .WithUpdatePeriod(parameters.updatePeriod);
97 for (size_t i = 0; i < modulesToApply.size(); ++i) {
98 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, parameters.moduleLocations[i].Angle()}));
99 }
100
102 }
103
104 /**
105 * \brief Modifies the DriveRequestType parameter and returns itself.
106 *
107 * The type of control request to use for the drive motor.
108 *
109 * \param newDriveRequestType Parameter to modify
110 * \returns this object
111 */
113 {
114 this->DriveRequestType = std::move(newDriveRequestType);
115 return *this;
116 }
117 /**
118 * \brief Modifies the DriveRequestType parameter and returns itself.
119 *
120 * The type of control request to use for the drive motor.
121 *
122 * \param newDriveRequestType Parameter to modify
123 * \returns this object
124 */
126 {
127 this->DriveRequestType = std::move(newDriveRequestType);
128 return std::move(*this);
129 }
130
131 /**
132 * \brief Modifies the SteerRequestType parameter and returns itself.
133 *
134 * The type of control request to use for the steer motor.
135 *
136 * \param newSteerRequestType Parameter to modify
137 * \returns this object
138 */
140 {
141 this->SteerRequestType = std::move(newSteerRequestType);
142 return *this;
143 }
144 /**
145 * \brief Modifies the SteerRequestType parameter and returns itself.
146 *
147 * The type of control request to use for the steer motor.
148 *
149 * \param newSteerRequestType Parameter to modify
150 * \returns this object
151 */
153 {
154 this->SteerRequestType = std::move(newSteerRequestType);
155 return std::move(*this);
156 }
157};
158
159/**
160 * \brief Drives the swerve drivetrain in a field-centric manner. This request
161 * is optimized for joystick control during teleop with built-in deadbands.
162 *
163 * This request specifies the direction the robot should travel oriented against
164 * the field, and the rate at which their robot should rotate about the center
165 * of the robot.
166 *
167 * An example scenario is that the robot is oriented to the field +Y (left), the
168 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In
169 * this scenario, the robot would drive along the field +X (forward) at 5 m/s
170 * and turn counterclockwise at 0.5 rad/s.
171 */
173public:
174 /**
175 * \brief The velocity in the X direction. X is defined as forward according
176 * toWPILib convention, so this determines how fast to travel forward.
177 */
178 units::meters_per_second_t VelocityX = 0_mps;
179 /**
180 * \brief The velocity in the Y direction. Y is defined as to the left
181 * according to WPILib convention, so this determines how fast to travel to
182 * the left.
183 */
184 units::meters_per_second_t VelocityY = 0_mps;
185 /**
186 * \brief The angular rate to rotate at. Angular rate is defined as
187 * counterclockwise positive, so this determines how fast to turn
188 * counterclockwise.
189 */
190 units::radians_per_second_t RotationalRate = 0_rad_per_s;
191 /**
192 * \brief The allowable deadband of the request.
193 */
194 units::meters_per_second_t Deadband = 0_mps;
195 /**
196 * \brief The rotational deadband of the request.
197 */
198 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
199 /**
200 * \brief The center of rotation the robot should rotate around. This is
201 * (0,0) by default, which will rotate around the center of the robot.
202 */
203 Translation2d CenterOfRotation{};
204
205 /**
206 * \brief The type of control request to use for the drive motor.
207 */
209 /**
210 * \brief The type of control request to use for the steer motor.
211 */
213 /**
214 * \brief Whether to desaturate wheel speeds before applying.
215 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
216 */
218
219 /**
220 * \brief The perspective to use when determining which direction is forward.
221 */
223
224 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
225 {
226 auto toApplyX = VelocityX;
227 auto toApplyY = VelocityY;
228 auto toApplyOmega = RotationalRate;
229
231 /* If we're operator perspective, modify the X/Y translation by the angle */
232 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
233 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
234 toApplyX = tmp.X() / 1_s;
235 toApplyY = tmp.Y() / 1_s;
236 }
237
238 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
239 toApplyX = 0_mps;
240 toApplyY = 0_mps;
241 }
242 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
243 toApplyOmega = 0_rad_per_s;
244 }
245
246 auto const speeds = ChassisSpeeds::Discretize(
247 ChassisSpeeds::FromFieldRelativeSpeeds(
248 {toApplyX, toApplyY, toApplyOmega}, parameters.currentPose.Rotation()
249 ),
250 parameters.updatePeriod
251 );
252
253 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
254 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
256 }
257
258 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
261 .WithUpdatePeriod(parameters.updatePeriod);
262 for (size_t i = 0; i < modulesToApply.size(); ++i) {
263 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
264 }
265
267 }
268
269 /**
270 * \brief Modifies the VelocityX parameter and returns itself.
271 *
272 * The velocity in the X direction. X is defined as forward according to
273 * WPILib convention, so this determines how fast to travel forward.
274 *
275 * \param newVelocityX Parameter to modify
276 * \returns this object
277 */
278 FieldCentric &WithVelocityX(units::meters_per_second_t newVelocityX) &
279 {
280 this->VelocityX = std::move(newVelocityX);
281 return *this;
282 }
283 /**
284 * \brief Modifies the VelocityX parameter and returns itself.
285 *
286 * The velocity in the X direction. X is defined as forward according to
287 * WPILib convention, so this determines how fast to travel forward.
288 *
289 * \param newVelocityX Parameter to modify
290 * \returns this object
291 */
292 FieldCentric &&WithVelocityX(units::meters_per_second_t newVelocityX) &&
293 {
294 this->VelocityX = std::move(newVelocityX);
295 return std::move(*this);
296 }
297
298 /**
299 * \brief Modifies the VelocityY parameter and returns itself.
300 *
301 * The velocity in the Y direction. Y is defined as to the left according
302 * to WPILib convention, so this determines how fast to travel to the
303 * left.
304 *
305 * \param newVelocityY Parameter to modify
306 * \returns this object
307 */
308 FieldCentric &WithVelocityY(units::meters_per_second_t newVelocityY) &
309 {
310 this->VelocityY = std::move(newVelocityY);
311 return *this;
312 }
313 /**
314 * \brief Modifies the VelocityY parameter and returns itself.
315 *
316 * The velocity in the Y direction. Y is defined as to the left according
317 * to WPILib convention, so this determines how fast to travel to the
318 * left.
319 *
320 * \param newVelocityY Parameter to modify
321 * \returns this object
322 */
323 FieldCentric &&WithVelocityY(units::meters_per_second_t newVelocityY) &&
324 {
325 this->VelocityY = std::move(newVelocityY);
326 return std::move(*this);
327 }
328
329 /**
330 * \brief Modifies the RotationalRate parameter and returns itself.
331 *
332 * The angular rate to rotate at. Angular rate is defined as counterclockwise
333 * positive, so this determines how fast to turn counterclockwise.
334 *
335 * \param newRotationalRate Parameter to modify
336 * \returns this object
337 */
338 FieldCentric &WithRotationalRate(units::radians_per_second_t newRotationalRate) &
339 {
340 this->RotationalRate = std::move(newRotationalRate);
341 return *this;
342 }
343 /**
344 * \brief Modifies the RotationalRate parameter and returns itself.
345 *
346 * The angular rate to rotate at. Angular rate is defined as counterclockwise
347 * positive, so this determines how fast to turn counterclockwise.
348 *
349 * \param newRotationalRate Parameter to modify
350 * \returns this object
351 */
352 FieldCentric &&WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
353 {
354 this->RotationalRate = std::move(newRotationalRate);
355 return std::move(*this);
356 }
357
358 /**
359 * \brief Modifies the Deadband parameter and returns itself.
360 *
361 * The allowable deadband of the request.
362 *
363 * \param newDeadband Parameter to modify
364 * \returns this object
365 */
366 FieldCentric &WithDeadband(units::meters_per_second_t newDeadband) &
367 {
368 this->Deadband = std::move(newDeadband);
369 return *this;
370 }
371 /**
372 * \brief Modifies the Deadband parameter and returns itself.
373 *
374 * The allowable deadband of the request.
375 *
376 * \param newDeadband Parameter to modify
377 * \returns this object
378 */
379 FieldCentric &&WithDeadband(units::meters_per_second_t newDeadband) &&
380 {
381 this->Deadband = std::move(newDeadband);
382 return std::move(*this);
383 }
384
385 /**
386 * \brief Modifies the RotationalDeadband parameter and returns itself.
387 *
388 * The rotational deadband of the request.
389 *
390 * \param newRotationalDeadband Parameter to modify
391 * \returns this object
392 */
393 FieldCentric &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
394 {
395 this->RotationalDeadband = std::move(newRotationalDeadband);
396 return *this;
397 }
398 /**
399 * \brief Modifies the RotationalDeadband parameter and returns itself.
400 *
401 * The rotational deadband of the request.
402 *
403 * \param newRotationalDeadband Parameter to modify
404 * \returns this object
405 */
406 FieldCentric &&WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
407 {
408 this->RotationalDeadband = std::move(newRotationalDeadband);
409 return std::move(*this);
410 }
411
412 /**
413 * \brief Modifies the CenterOfRotation parameter and returns itself.
414 *
415 * The center of rotation the robot should rotate around. This is (0,0) by
416 * default, which will rotate around the center of the robot.
417 *
418 * \param newCenterOfRotation Parameter to modify
419 * \returns this object
420 */
421 FieldCentric &WithCenterOfRotation(Translation2d newCenterOfRotation) &
422 {
423 this->CenterOfRotation = std::move(newCenterOfRotation);
424 return *this;
425 }
426 /**
427 * \brief Modifies the CenterOfRotation parameter and returns itself.
428 *
429 * The center of rotation the robot should rotate around. This is (0,0) by
430 * default, which will rotate around the center of the robot.
431 *
432 * \param newCenterOfRotation Parameter to modify
433 * \returns this object
434 */
435 FieldCentric &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
436 {
437 this->CenterOfRotation = std::move(newCenterOfRotation);
438 return std::move(*this);
439 }
440
441 /**
442 * \brief Modifies the DriveRequestType parameter and returns itself.
443 *
444 * The type of control request to use for the drive motor.
445 *
446 * \param newDriveRequestType Parameter to modify
447 * \returns this object
448 */
450 {
451 this->DriveRequestType = std::move(newDriveRequestType);
452 return *this;
453 }
454 /**
455 * \brief Modifies the DriveRequestType parameter and returns itself.
456 *
457 * The type of control request to use for the drive motor.
458 *
459 * \param newDriveRequestType Parameter to modify
460 * \returns this object
461 */
463 {
464 this->DriveRequestType = std::move(newDriveRequestType);
465 return std::move(*this);
466 }
467
468 /**
469 * \brief Modifies the SteerRequestType parameter and returns itself.
470 *
471 * The type of control request to use for the steer motor.
472 *
473 * \param newSteerRequestType Parameter to modify
474 * \returns this object
475 */
477 {
478 this->SteerRequestType = std::move(newSteerRequestType);
479 return *this;
480 }
481 /**
482 * \brief Modifies the SteerRequestType parameter and returns itself.
483 *
484 * The type of control request to use for the steer motor.
485 *
486 * \param newSteerRequestType Parameter to modify
487 * \returns this object
488 */
490 {
491 this->SteerRequestType = std::move(newSteerRequestType);
492 return std::move(*this);
493 }
494
495 /**
496 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
497 *
498 * Whether to desaturate wheel speeds before applying. For more information, see
499 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
500 *
501 * \param newDesaturateWheelSpeeds Parameter to modify
502 * \returns this object
503 */
504 FieldCentric &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
505 {
506 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
507 return *this;
508 }
509 /**
510 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
511 *
512 * Whether to desaturate wheel speeds before applying. For more information, see
513 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
514 *
515 * \param newDesaturateWheelSpeeds Parameter to modify
516 * \returns this object
517 */
518 FieldCentric &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
519 {
520 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
521 return std::move(*this);
522 }
523
524 /**
525 * \brief Modifies the ForwardPerspective parameter and returns itself.
526 *
527 * The perspective to use when determining which direction is forward.
528 *
529 * \param newForwardPerspective Parameter to modify
530 * \returns this object
531 */
533 {
534 this->ForwardPerspective = std::move(newForwardPerspective);
535 return *this;
536 }
537 /**
538 * \brief Modifies the ForwardPerspective parameter and returns itself.
539 *
540 * The perspective to use when determining which direction is forward.
541 *
542 * \param newForwardPerspective Parameter to modify
543 * \returns this object
544 */
546 {
547 this->ForwardPerspective = std::move(newForwardPerspective);
548 return std::move(*this);
549 }
550};
551
552/**
553 * \brief Drives the swerve drivetrain in a robot-centric manner. This request
554 * is optimized for joystick control during teleop with built-in deadbands.
555 *
556 * This request specifies the direction the robot should travel oriented against
557 * the robot itself, and the rate at which their robot should rotate about the
558 * center of the robot.
559 *
560 * An example scenario is that the robot is oriented to the field +Y (left), the
561 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In
562 * this scenario, the robot would drive forward relative to itself (or left
563 * along the field +Y) at 5 m/s and turn counterclockwise at 0.5 rad/s.
564 */
566public:
567 /**
568 * \brief The velocity in the X direction. X is defined as forward according
569 * toWPILib convention, so this determines how fast to travel forward.
570 */
571 units::meters_per_second_t VelocityX = 0_mps;
572 /**
573 * \brief The velocity in the Y direction. Y is defined as to the left
574 * according to WPILib convention, so this determines how fast to travel to
575 * the left.
576 */
577 units::meters_per_second_t VelocityY = 0_mps;
578 /**
579 * \brief The angular rate to rotate at. Angular rate is defined as
580 * counterclockwise positive, so this determines how fast to turn
581 * counterclockwise.
582 */
583 units::radians_per_second_t RotationalRate = 0_rad_per_s;
584
585 /**
586 * \brief The allowable deadband of the request.
587 */
588 units::meters_per_second_t Deadband = 0_mps;
589 /**
590 * \brief The rotational deadband of the request.
591 */
592 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
593 /**
594 * \brief The center of rotation the robot should rotate around. This is
595 * (0,0) by default, which will rotate around the center of the robot.
596 */
597 Translation2d CenterOfRotation{};
598
599 /**
600 * \brief The type of control request to use for the drive motor.
601 */
603 /**
604 * \brief The type of control request to use for the steer motor.
605 */
607 /**
608 * \brief Whether to desaturate wheel speeds before applying.
609 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
610 */
612
613 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
614 {
615 auto toApplyX = VelocityX;
616 auto toApplyY = VelocityY;
617 auto toApplyOmega = RotationalRate;
618 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
619 toApplyX = 0_mps;
620 toApplyY = 0_mps;
621 }
622 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
623 toApplyOmega = 0_rad_per_s;
624 }
625 ChassisSpeeds const speeds{toApplyX, toApplyY, toApplyOmega};
626
627 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
628 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
630 }
631
632 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
635 .WithUpdatePeriod(parameters.updatePeriod);
636 for (size_t i = 0; i < modulesToApply.size(); ++i) {
637 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
638 }
639
641 }
642
643 /**
644 * \brief Modifies the VelocityX parameter and returns itself.
645 *
646 * The velocity in the X direction. X is defined as forward according to
647 * WPILib convention, so this determines how fast to travel forward.
648 *
649 * \param newVelocityX Parameter to modify
650 * \returns this object
651 */
652 RobotCentric &WithVelocityX(units::meters_per_second_t newVelocityX) &
653 {
654 this->VelocityX = std::move(newVelocityX);
655 return *this;
656 }
657 /**
658 * \brief Modifies the VelocityX parameter and returns itself.
659 *
660 * The velocity in the X direction. X is defined as forward according to
661 * WPILib convention, so this determines how fast to travel forward.
662 *
663 * \param newVelocityX Parameter to modify
664 * \returns this object
665 */
666 RobotCentric &&WithVelocityX(units::meters_per_second_t newVelocityX) &&
667 {
668 this->VelocityX = std::move(newVelocityX);
669 return std::move(*this);
670 }
671
672 /**
673 * \brief Modifies the VelocityY parameter and returns itself.
674 *
675 * The velocity in the Y direction. Y is defined as to the left according
676 * to WPILib convention, so this determines how fast to travel to the
677 * left.
678 *
679 * \param newVelocityY Parameter to modify
680 * \returns this object
681 */
682 RobotCentric &WithVelocityY(units::meters_per_second_t newVelocityY) &
683 {
684 this->VelocityY = std::move(newVelocityY);
685 return *this;
686 }
687 /**
688 * \brief Modifies the VelocityY parameter and returns itself.
689 *
690 * The velocity in the Y direction. Y is defined as to the left according
691 * to WPILib convention, so this determines how fast to travel to the
692 * left.
693 *
694 * \param newVelocityY Parameter to modify
695 * \returns this object
696 */
697 RobotCentric &&WithVelocityY(units::meters_per_second_t newVelocityY) &&
698 {
699 this->VelocityY = std::move(newVelocityY);
700 return std::move(*this);
701 }
702
703 /**
704 * \brief Modifies the RotationalRate parameter and returns itself.
705 *
706 * The angular rate to rotate at. Angular rate is defined as counterclockwise
707 * positive, so this determines how fast to turn counterclockwise.
708 *
709 * \param newRotationalRate Parameter to modify
710 * \returns this object
711 */
712 RobotCentric &WithRotationalRate(units::radians_per_second_t newRotationalRate) &
713 {
714 this->RotationalRate = std::move(newRotationalRate);
715 return *this;
716 }
717 /**
718 * \brief Modifies the RotationalRate parameter and returns itself.
719 *
720 * The angular rate to rotate at. Angular rate is defined as counterclockwise
721 * positive, so this determines how fast to turn counterclockwise.
722 *
723 * \param newRotationalRate Parameter to modify
724 * \returns this object
725 */
726 RobotCentric &&WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
727 {
728 this->RotationalRate = std::move(newRotationalRate);
729 return std::move(*this);
730 }
731
732 /**
733 * \brief Modifies the Deadband parameter and returns itself.
734 *
735 * The allowable deadband of the request.
736 *
737 * \param newDeadband Parameter to modify
738 * \returns this object
739 */
740 RobotCentric &WithDeadband(units::meters_per_second_t newDeadband) &
741 {
742 this->Deadband = std::move(newDeadband);
743 return *this;
744 }
745 /**
746 * \brief Modifies the Deadband parameter and returns itself.
747 *
748 * The allowable deadband of the request.
749 *
750 * \param newDeadband Parameter to modify
751 * \returns this object
752 */
753 RobotCentric &&WithDeadband(units::meters_per_second_t newDeadband) &&
754 {
755 this->Deadband = std::move(newDeadband);
756 return std::move(*this);
757 }
758
759 /**
760 * \brief Modifies the RotationalDeadband parameter and returns itself.
761 *
762 * The rotational deadband of the request.
763 *
764 * \param newRotationalDeadband Parameter to modify
765 * \returns this object
766 */
767 RobotCentric &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
768 {
769 this->RotationalDeadband = std::move(newRotationalDeadband);
770 return *this;
771 }
772 /**
773 * \brief Modifies the RotationalDeadband parameter and returns itself.
774 *
775 * The rotational deadband of the request.
776 *
777 * \param newRotationalDeadband Parameter to modify
778 * \returns this object
779 */
780 RobotCentric &&WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
781 {
782 this->RotationalDeadband = std::move(newRotationalDeadband);
783 return std::move(*this);
784 }
785
786 /**
787 * \brief Modifies the CenterOfRotation parameter and returns itself.
788 *
789 * The center of rotation the robot should rotate around. This is (0,0) by
790 * default, which will rotate around the center of the robot.
791 *
792 * \param newCenterOfRotation Parameter to modify
793 * \returns this object
794 */
795 RobotCentric &WithCenterOfRotation(Translation2d newCenterOfRotation) &
796 {
797 this->CenterOfRotation = std::move(newCenterOfRotation);
798 return *this;
799 }
800 /**
801 * \brief Modifies the CenterOfRotation parameter and returns itself.
802 *
803 * The center of rotation the robot should rotate around. This is (0,0) by
804 * default, which will rotate around the center of the robot.
805 *
806 * \param newCenterOfRotation Parameter to modify
807 * \returns this object
808 */
809 RobotCentric &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
810 {
811 this->CenterOfRotation = std::move(newCenterOfRotation);
812 return std::move(*this);
813 }
814
815 /**
816 * \brief Modifies the DriveRequestType parameter and returns itself.
817 *
818 * The type of control request to use for the drive motor.
819 *
820 * \param newDriveRequestType Parameter to modify
821 * \returns this object
822 */
824 {
825 this->DriveRequestType = std::move(newDriveRequestType);
826 return *this;
827 }
828 /**
829 * \brief Modifies the DriveRequestType parameter and returns itself.
830 *
831 * The type of control request to use for the drive motor.
832 *
833 * \param newDriveRequestType Parameter to modify
834 * \returns this object
835 */
837 {
838 this->DriveRequestType = std::move(newDriveRequestType);
839 return std::move(*this);
840 }
841
842 /**
843 * \brief Modifies the SteerRequestType parameter and returns itself.
844 *
845 * The type of control request to use for the steer motor.
846 *
847 * \param newSteerRequestType Parameter to modify
848 * \returns this object
849 */
851 {
852 this->SteerRequestType = std::move(newSteerRequestType);
853 return *this;
854 }
855 /**
856 * \brief Modifies the SteerRequestType parameter and returns itself.
857 *
858 * The type of control request to use for the steer motor.
859 *
860 * \param newSteerRequestType Parameter to modify
861 * \returns this object
862 */
864 {
865 this->SteerRequestType = std::move(newSteerRequestType);
866 return std::move(*this);
867 }
868
869 /**
870 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
871 *
872 * Whether to desaturate wheel speeds before applying. For more information, see
873 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
874 *
875 * \param newDesaturateWheelSpeeds Parameter to modify
876 * \returns this object
877 */
878 RobotCentric &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
879 {
880 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
881 return *this;
882 }
883 /**
884 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
885 *
886 * Whether to desaturate wheel speeds before applying. For more information, see
887 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
888 *
889 * \param newDesaturateWheelSpeeds Parameter to modify
890 * \returns this object
891 */
892 RobotCentric &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
893 {
894 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
895 return std::move(*this);
896 }
897};
898
899/**
900 * \brief Sets the swerve drive modules to point to a specified direction.
901 */
903public:
904 /**
905 * \brief The direction to point the modules toward. This direction is still
906 * optimized to what the module was previously at.
907 */
908 Rotation2d ModuleDirection{};
909 /**
910 * \brief The type of control request to use for the drive motor.
911 */
913 /**
914 * \brief The type of control request to use for the steer motor.
915 */
917
918 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
919 {
920 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
923 .WithUpdatePeriod(parameters.updatePeriod);
924 for (size_t i = 0; i < modulesToApply.size(); ++i) {
925 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, ModuleDirection}));
926 }
927
929 }
930
931 /**
932 * \brief Modifies the ModuleDirection parameter and returns itself.
933 *
934 * The direction to point the modules toward. This direction is still optimized
935 * to what the module was previously at.
936 *
937 * \param newModuleDirection Parameter to modify
938 * \returns this object
939 */
940 PointWheelsAt &WithModuleDirection(Rotation2d newModuleDirection) &
941 {
942 this->ModuleDirection = std::move(newModuleDirection);
943 return *this;
944 }
945 /**
946 * \brief Modifies the ModuleDirection parameter and returns itself.
947 *
948 * The direction to point the modules toward. This direction is still optimized
949 * to what the module was previously at.
950 *
951 * \param newModuleDirection Parameter to modify
952 * \returns this object
953 */
954 PointWheelsAt &&WithModuleDirection(Rotation2d newModuleDirection) &&
955 {
956 this->ModuleDirection = std::move(newModuleDirection);
957 return std::move(*this);
958 }
959
960 /**
961 * \brief Modifies the DriveRequestType parameter and returns itself.
962 *
963 * The type of control request to use for the drive motor.
964 *
965 * \param newDriveRequestType Parameter to modify
966 * \returns this object
967 */
969 {
970 this->DriveRequestType = std::move(newDriveRequestType);
971 return *this;
972 }
973 /**
974 * \brief Modifies the DriveRequestType parameter and returns itself.
975 *
976 * The type of control request to use for the drive motor.
977 *
978 * \param newDriveRequestType Parameter to modify
979 * \returns this object
980 */
982 {
983 this->DriveRequestType = std::move(newDriveRequestType);
984 return std::move(*this);
985 }
986
987 /**
988 * \brief Modifies the SteerRequestType parameter and returns itself.
989 *
990 * The type of control request to use for the steer motor.
991 *
992 * \param newSteerRequestType Parameter to modify
993 * \returns this object
994 */
996 {
997 this->SteerRequestType = std::move(newSteerRequestType);
998 return *this;
999 }
1000 /**
1001 * \brief Modifies the SteerRequestType parameter and returns itself.
1002 *
1003 * The type of control request to use for the steer motor.
1004 *
1005 * \param newSteerRequestType Parameter to modify
1006 * \returns this object
1007 */
1009 {
1010 this->SteerRequestType = std::move(newSteerRequestType);
1011 return std::move(*this);
1012 }
1013};
1014
1015/**
1016 * \brief Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.
1017 * This request is optimized for autonomous or profiled control, which typically
1018 * directly provides ChassisSpeeds and optionally wheel force feedforwards.
1019 *
1020 * Unlike the field-centric requests, this request does not automatically
1021 * discretize the provided ChassisSpeeds.
1022 */
1024public:
1025 /**
1026 * \brief The robot-centric chassis speeds to apply to the drivetrain.
1027 * Users must manually discretize these speeds if appropriate.
1028 */
1029 ChassisSpeeds Speeds{};
1030 /**
1031 * \brief Robot-centric wheel force feedforwards to apply in the
1032 * X direction. X is defined as forward according to WPILib
1033 * convention, so this determines the forward forces to apply.
1034 *
1035 * These forces should include friction applied to the ground.
1036 *
1037 * The order of the forces should match the order of the modules
1038 * returned from SwerveDrivetrain.
1039 */
1040 std::vector<units::newton_t> WheelForceFeedforwardsX;
1041 /**
1042 * \brief Robot-centric wheel force feedforwards to apply in the
1043 * Y direction. Y is defined as to the left according to WPILib
1044 * convention, so this determines the forces to apply to the left.
1045 *
1046 * These forces should include friction applied to the ground.
1047 *
1048 * The order of the forces should match the order of the modules
1049 * returned from SwerveDrivetrain.
1050 */
1051 std::vector<units::newton_t> WheelForceFeedforwardsY;
1052 /**
1053 * \brief The center of rotation to rotate around.
1054 */
1055 Translation2d CenterOfRotation{};
1056 /**
1057 * \brief The type of control request to use for the drive motor.
1058 */
1060 /**
1061 * \brief The type of control request to use for the steer motor.
1062 */
1064 /**
1065 * \brief Whether to desaturate wheel speeds before applying.
1066 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1067 */
1069
1070 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1071 {
1072 auto states = parameters.kinematics->ToSwerveModuleStates(Speeds, CenterOfRotation);
1073 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
1075 }
1076
1077 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
1080 .WithUpdatePeriod(parameters.updatePeriod);
1081 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1082 if (i < WheelForceFeedforwardsX.size() && i < WheelForceFeedforwardsY.size()) {
1083 moduleRequest.WithWheelForceFeedforwardX(WheelForceFeedforwardsX[i])
1084 .WithWheelForceFeedforwardY(WheelForceFeedforwardsY[i]);
1085 }
1086 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1087 }
1088
1090 }
1091
1092 /**
1093 * \brief Modifies the Speeds parameter and returns itself.
1094 *
1095 * The robot-centric chassis speeds to apply to the drivetrain.
1096 * Users must manually discretize these speeds if appropriate.
1097 *
1098 * \param newSpeeds Parameter to modify
1099 * \returns this object
1100 */
1101 ApplyRobotSpeeds &WithSpeeds(ChassisSpeeds newSpeeds) &
1102 {
1103 this->Speeds = std::move(newSpeeds);
1104 return *this;
1105 }
1106 /**
1107 * \brief Modifies the Speeds parameter and returns itself.
1108 *
1109 * The robot-centric chassis speeds to apply to the drivetrain.
1110 *
1111 * \param newSpeeds Parameter to modify
1112 * \returns this object
1113 */
1114 ApplyRobotSpeeds &&WithSpeeds(ChassisSpeeds newSpeeds) &&
1115 {
1116 this->Speeds = std::move(newSpeeds);
1117 return std::move(*this);
1118 }
1119
1120 /**
1121 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1122 *
1123 * Robot-centric wheel force feedforwards to apply in the
1124 * X direction. X is defined as forward according to WPILib
1125 * convention, so this determines the forward forces to apply.
1126 *
1127 * These forces should include friction applied to the ground.
1128 *
1129 * The order of the forces should match the order of the modules
1130 * returned from SwerveDrivetrain.
1131 *
1132 * \param newWheelForceFeedforwardsX Parameter to modify
1133 * \returns this object
1134 */
1135 ApplyRobotSpeeds &WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &
1136 {
1137 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1138 return *this;
1139 }
1140 /**
1141 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1142 *
1143 * Robot-centric wheel force feedforwards to apply in the
1144 * X direction. X is defined as forward according to WPILib
1145 * convention, so this determines the forward forces to apply.
1146 *
1147 * These forces should include friction applied to the ground.
1148 *
1149 * The order of the forces should match the order of the modules
1150 * returned from SwerveDrivetrain.
1151 *
1152 * \param newWheelForceFeedforwardsX Parameter to modify
1153 * \returns this object
1154 */
1155 ApplyRobotSpeeds &&WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &&
1156 {
1157 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1158 return std::move(*this);
1159 }
1160
1161 /**
1162 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1163 *
1164 * Robot-centric wheel force feedforwards to apply in the
1165 * Y direction. Y is defined as to the left according to WPILib
1166 * convention, so this determines the forces to apply to the left.
1167 *
1168 * These forces should include friction applied to the ground.
1169 *
1170 * The order of the forces should match the order of the modules
1171 * returned from SwerveDrivetrain.
1172 *
1173 * \param newWheelForceFeedforwardsY Parameter to modify
1174 * \returns this object
1175 */
1176 ApplyRobotSpeeds &WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &
1177 {
1178 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1179 return *this;
1180 }
1181 /**
1182 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1183 *
1184 * Robot-centric wheel force feedforwards to apply in the
1185 * Y direction. Y is defined as to the left according to WPILib
1186 * convention, so this determines the forces to apply to the left.
1187 *
1188 * These forces should include friction applied to the ground.
1189 *
1190 * The order of the forces should match the order of the modules
1191 * returned from SwerveDrivetrain.
1192 *
1193 * \param newWheelForceFeedforwardsY Parameter to modify
1194 * \returns this object
1195 */
1196 ApplyRobotSpeeds &&WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &&
1197 {
1198 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1199 return std::move(*this);
1200 }
1201
1202 /**
1203 * \brief Modifies the CenterOfRotation parameter and returns itself.
1204 *
1205 * The center of rotation the robot should rotate around. This is (0,0) by
1206 * default, which will rotate around the center of the robot.
1207 *
1208 * \param newCenterOfRotation Parameter to modify
1209 * \return this object
1210 */
1211 ApplyRobotSpeeds &WithCenterOfRotation(Translation2d newCenterOfRotation) &
1212 {
1213 this->CenterOfRotation = std::move(newCenterOfRotation);
1214 return *this;
1215 }
1216 /**
1217 * \brief Modifies the CenterOfRotation parameter and returns itself.
1218 *
1219 * The center of rotation the robot should rotate around. This is (0,0) by
1220 * default, which will rotate around the center of the robot.
1221 *
1222 * \param newCenterOfRotation Parameter to modify
1223 * \return this object
1224 */
1225 ApplyRobotSpeeds &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
1226 {
1227 this->CenterOfRotation = std::move(newCenterOfRotation);
1228 return std::move(*this);
1229 }
1230
1231 /**
1232 * \brief Modifies the DriveRequestType parameter and returns itself.
1233 *
1234 * The type of control request to use for the drive motor.
1235 *
1236 * \param newDriveRequestType Parameter to modify
1237 * \returns this object
1238 */
1240 {
1241 this->DriveRequestType = std::move(newDriveRequestType);
1242 return *this;
1243 }
1244 /**
1245 * \brief Modifies the DriveRequestType parameter and returns itself.
1246 *
1247 * The type of control request to use for the drive motor.
1248 *
1249 * \param newDriveRequestType Parameter to modify
1250 * \returns this object
1251 */
1253 {
1254 this->DriveRequestType = std::move(newDriveRequestType);
1255 return std::move(*this);
1256 }
1257
1258 /**
1259 * \brief Modifies the SteerRequestType parameter and returns itself.
1260 *
1261 * The type of control request to use for the steer motor.
1262 *
1263 * \param newSteerRequestType Parameter to modify
1264 * \returns this object
1265 */
1267 {
1268 this->SteerRequestType = std::move(newSteerRequestType);
1269 return *this;
1270 }
1271 /**
1272 * \brief Modifies the SteerRequestType parameter and returns itself.
1273 *
1274 * The type of control request to use for the steer motor.
1275 *
1276 * \param newSteerRequestType Parameter to modify
1277 * \returns this object
1278 */
1280 {
1281 this->SteerRequestType = std::move(newSteerRequestType);
1282 return std::move(*this);
1283 }
1284
1285 /**
1286 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1287 *
1288 * Whether to desaturate wheel speeds before applying. For more information, see
1289 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1290 *
1291 * \param newDesaturateWheelSpeeds Parameter to modify
1292 * \returns this object
1293 */
1294 ApplyRobotSpeeds &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
1295 {
1296 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1297 return *this;
1298 }
1299 /**
1300 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1301 *
1302 * Whether to desaturate wheel speeds before applying. For more information, see
1303 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1304 *
1305 * \param newDesaturateWheelSpeeds Parameter to modify
1306 * \returns this object
1307 */
1308 ApplyRobotSpeeds &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
1309 {
1310 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1311 return std::move(*this);
1312 }
1313};
1314
1315/**
1316 * \brief Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.
1317 * This request is optimized for autonomous or profiled control, which typically
1318 * directly provides ChassisSpeeds and optionally wheel force feedforwards.
1319 */
1321public:
1322 /**
1323 * \brief The field-centric chassis speeds to apply to the drivetrain.
1324 */
1325 ChassisSpeeds Speeds{};
1326 /**
1327 * \brief Field-centric wheel force feedforwards to apply in the
1328 * X direction. X is defined as forward according to WPILib
1329 * convention, so this determines the forward forces to apply.
1330 *
1331 * These forces should include friction applied to the ground.
1332 *
1333 * The order of the forces should match the order of the modules
1334 * returned from SwerveDrivetrain.
1335 */
1336 std::vector<units::newton_t> WheelForceFeedforwardsX;
1337 /**
1338 * \brief Field-centric wheel force feedforwards to apply in the
1339 * Y direction. Y is defined as to the left according to WPILib
1340 * convention, so this determines the forces to apply to the left.
1341 *
1342 * These forces should include friction applied to the ground.
1343 *
1344 * The order of the forces should match the order of the modules
1345 * returned from SwerveDrivetrain.
1346 */
1347 std::vector<units::newton_t> WheelForceFeedforwardsY;
1348 /**
1349 * \brief The center of rotation to rotate around.
1350 */
1351 Translation2d CenterOfRotation{};
1352 /**
1353 * \brief The type of control request to use for the drive motor.
1354 */
1356 /**
1357 * \brief The type of control request to use for the steer motor.
1358 */
1360 /**
1361 * \brief Whether to desaturate wheel speeds before applying.
1362 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1363 */
1365
1366 /**
1367 * \brief The perspective to use when determining which direction is forward.
1368 */
1370
1371 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1372 {
1373 auto fieldSpeeds = Speeds;
1375 /* If we're operator perspective, modify the X/Y translation by the angle */
1376 Translation2d tmp{Speeds.vx * 1_s, Speeds.vy * 1_s};
1377 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
1378 fieldSpeeds.vx = tmp.X() / 1_s;
1379 fieldSpeeds.vy = tmp.Y() / 1_s;
1380 }
1381
1382 auto const robotSpeeds = ChassisSpeeds::Discretize(
1383 ChassisSpeeds::FromFieldRelativeSpeeds(
1384 fieldSpeeds, parameters.currentPose.Rotation()
1385 ),
1386 parameters.updatePeriod
1387 );
1388
1389 auto states = parameters.kinematics->ToSwerveModuleStates(robotSpeeds, CenterOfRotation);
1390 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
1392 }
1393
1394 auto moduleRequest = impl::SwerveModuleImpl::ModuleRequest{}
1397 .WithUpdatePeriod(parameters.updatePeriod);
1398
1399 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1400 if (i < WheelForceFeedforwardsX.size() && i < WheelForceFeedforwardsY.size()) {
1401 auto wheelForceFeedforwardX = WheelForceFeedforwardsX[i];
1402 auto wheelForceFeedforwardY = WheelForceFeedforwardsY[i];
1403
1404 Translation2d tmp{wheelForceFeedforwardX * 1_m/1_N, wheelForceFeedforwardY * 1_m/1_N};
1406 /* If we're operator perspective, modify the X/Y forces by the angle */
1407 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
1408 }
1409 /* Convert to robot-centric forces */
1410 tmp = tmp.RotateBy(-parameters.currentPose.Rotation());
1411
1412 wheelForceFeedforwardX = tmp.X() * 1_N/1_m;
1413 wheelForceFeedforwardY = tmp.Y() * 1_N/1_m;
1414
1415 moduleRequest.WithWheelForceFeedforwardX(wheelForceFeedforwardX)
1416 .WithWheelForceFeedforwardY(wheelForceFeedforwardY);
1417 }
1418
1419 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1420 }
1421
1423 }
1424
1425 /**
1426 * \brief Modifies the Speeds parameter and returns itself.
1427 *
1428 * The field-centric chassis speeds to apply to the drivetrain.
1429 *
1430 * \param newSpeeds Parameter to modify
1431 * \returns this object
1432 */
1433 ApplyFieldSpeeds &WithSpeeds(ChassisSpeeds newSpeeds) &
1434 {
1435 this->Speeds = std::move(newSpeeds);
1436 return *this;
1437 }
1438 /**
1439 * \brief Modifies the Speeds parameter and returns itself.
1440 *
1441 * The field-centric chassis speeds to apply to the drivetrain.
1442 *
1443 * \param newSpeeds Parameter to modify
1444 * \returns this object
1445 */
1446 ApplyFieldSpeeds &&WithSpeeds(ChassisSpeeds newSpeeds) &&
1447 {
1448 this->Speeds = std::move(newSpeeds);
1449 return std::move(*this);
1450 }
1451
1452 /**
1453 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1454 *
1455 * Field-centric wheel force feedforwards to apply in the
1456 * X direction. X is defined as forward according to WPILib
1457 * convention, so this determines the forward forces to apply.
1458 *
1459 * These forces should include friction applied to the ground.
1460 *
1461 * The order of the forces should match the order of the modules
1462 * returned from SwerveDrivetrain.
1463 *
1464 * \param newWheelForceFeedforwardsX Parameter to modify
1465 * \returns this object
1466 */
1467 ApplyFieldSpeeds &WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &
1468 {
1469 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1470 return *this;
1471 }
1472 /**
1473 * \brief Modifies the WheelForceFeedforwardsX parameter and returns itself.
1474 *
1475 * Field-centric wheel force feedforwards to apply in the
1476 * X direction. X is defined as forward according to WPILib
1477 * convention, so this determines the forward forces to apply.
1478 *
1479 * These forces should include friction applied to the ground.
1480 *
1481 * The order of the forces should match the order of the modules
1482 * returned from SwerveDrivetrain.
1483 *
1484 * \param newWheelForceFeedforwardsX Parameter to modify
1485 * \returns this object
1486 */
1487 ApplyFieldSpeeds &&WithWheelForceFeedforwardsX(std::vector<units::newton_t> newWheelForceFeedforwardsX) &&
1488 {
1489 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1490 return std::move(*this);
1491 }
1492
1493 /**
1494 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1495 *
1496 * Field-centric wheel force feedforwards to apply in the
1497 * Y direction. Y is defined as to the left according to WPILib
1498 * convention, so this determines the forces to apply to the left.
1499 *
1500 * These forces should include friction applied to the ground.
1501 *
1502 * The order of the forces should match the order of the modules
1503 * returned from SwerveDrivetrain.
1504 *
1505 * \param newWheelForceFeedforwardsY Parameter to modify
1506 * \returns this object
1507 */
1508 ApplyFieldSpeeds &WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &
1509 {
1510 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1511 return *this;
1512 }
1513 /**
1514 * \brief Modifies the WheelForceFeedforwardsY parameter and returns itself.
1515 *
1516 * Field-centric wheel force feedforwards to apply in the
1517 * Y direction. Y is defined as to the left according to WPILib
1518 * convention, so this determines the forces to apply to the left.
1519 *
1520 * These forces should include friction applied to the ground.
1521 *
1522 * The order of the forces should match the order of the modules
1523 * returned from SwerveDrivetrain.
1524 *
1525 * \param newWheelForceFeedforwardsY Parameter to modify
1526 * \returns this object
1527 */
1528 ApplyFieldSpeeds &&WithWheelForceFeedforwardsY(std::vector<units::newton_t> newWheelForceFeedforwardsY) &&
1529 {
1530 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1531 return std::move(*this);
1532 }
1533
1534 /**
1535 * \brief Modifies the CenterOfRotation parameter and returns itself.
1536 *
1537 * The center of rotation the robot should rotate around. This is (0,0) by
1538 * default, which will rotate around the center of the robot.
1539 *
1540 * \param newCenterOfRotation Parameter to modify
1541 * \return this object
1542 */
1543 ApplyFieldSpeeds &WithCenterOfRotation(Translation2d newCenterOfRotation) &
1544 {
1545 this->CenterOfRotation = std::move(newCenterOfRotation);
1546 return *this;
1547 }
1548 /**
1549 * \brief Modifies the CenterOfRotation parameter and returns itself.
1550 *
1551 * The center of rotation the robot should rotate around. This is (0,0) by
1552 * default, which will rotate around the center of the robot.
1553 *
1554 * \param newCenterOfRotation Parameter to modify
1555 * \return this object
1556 */
1557 ApplyFieldSpeeds &&WithCenterOfRotation(Translation2d newCenterOfRotation) &&
1558 {
1559 this->CenterOfRotation = std::move(newCenterOfRotation);
1560 return std::move(*this);
1561 }
1562
1563 /**
1564 * \brief Modifies the DriveRequestType parameter and returns itself.
1565 *
1566 * The type of control request to use for the drive motor.
1567 *
1568 * \param newDriveRequestType Parameter to modify
1569 * \returns this object
1570 */
1572 {
1573 this->DriveRequestType = std::move(newDriveRequestType);
1574 return *this;
1575 }
1576 /**
1577 * \brief Modifies the DriveRequestType parameter and returns itself.
1578 *
1579 * The type of control request to use for the drive motor.
1580 *
1581 * \param newDriveRequestType Parameter to modify
1582 * \returns this object
1583 */
1585 {
1586 this->DriveRequestType = std::move(newDriveRequestType);
1587 return std::move(*this);
1588 }
1589
1590 /**
1591 * \brief Modifies the SteerRequestType parameter and returns itself.
1592 *
1593 * The type of control request to use for the steer motor.
1594 *
1595 * \param newSteerRequestType Parameter to modify
1596 * \returns this object
1597 */
1599 {
1600 this->SteerRequestType = std::move(newSteerRequestType);
1601 return *this;
1602 }
1603 /**
1604 * \brief Modifies the SteerRequestType parameter and returns itself.
1605 *
1606 * The type of control request to use for the steer motor.
1607 *
1608 * \param newSteerRequestType Parameter to modify
1609 * \returns this object
1610 */
1612 {
1613 this->SteerRequestType = std::move(newSteerRequestType);
1614 return std::move(*this);
1615 }
1616
1617 /**
1618 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1619 *
1620 * Whether to desaturate wheel speeds before applying. For more information, see
1621 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1622 *
1623 * \param newDesaturateWheelSpeeds Parameter to modify
1624 * \returns this object
1625 */
1626 ApplyFieldSpeeds &WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
1627 {
1628 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1629 return *this;
1630 }
1631 /**
1632 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1633 *
1634 * Whether to desaturate wheel speeds before applying. For more information, see
1635 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1636 *
1637 * \param newDesaturateWheelSpeeds Parameter to modify
1638 * \returns this object
1639 */
1640 ApplyFieldSpeeds &&WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
1641 {
1642 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1643 return std::move(*this);
1644 }
1645
1646 /**
1647 * \brief Modifies the ForwardPerspective parameter and returns itself.
1648 *
1649 * The perspective to use when determining which direction is forward.
1650 *
1651 * \param newForwardPerspective Parameter to modify
1652 * \returns this object
1653 */
1655 {
1656 this->ForwardPerspective = std::move(newForwardPerspective);
1657 return *this;
1658 }
1659 /**
1660 * \brief Modifies the ForwardPerspective parameter and returns itself.
1661 *
1662 * The perspective to use when determining which direction is forward.
1663 *
1664 * \param newForwardPerspective Parameter to modify
1665 * \returns this object
1666 */
1668 {
1669 this->ForwardPerspective = std::move(newForwardPerspective);
1670 return std::move(*this);
1671 }
1672};
1673
1674/**
1675 * \brief Drives the swerve drivetrain in a field-centric manner, maintaining a
1676 * specified heading angle to ensure the robot is facing the desired direction
1677 *
1678 * When users use this request, they specify the direction the robot should
1679 * travel oriented against the field, and the direction the robot should be facing.
1680 *
1681 * An example scenario is that the robot is oriented to the east, the VelocityX
1682 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees.
1683 * In this scenario, the robot would drive northward at 5 m/s and turn clockwise
1684 * to a target of 180 degrees.
1685 *
1686 * This control request is especially useful for autonomous control, where the
1687 * robot should be facing a changing direction throughout the motion.
1688 */
1690public:
1691 /**
1692 * \brief The velocity in the X direction. X is defined as forward according
1693 * to WPILib convention, so this determines how fast to travel forward.
1694 */
1695 units::meters_per_second_t VelocityX = 0_mps;
1696 /**
1697 * \brief The velocity in the Y direction. Y is defined as to the left
1698 * according to WPILib convention, so this determines how fast to travel to
1699 * the left.
1700 */
1701 units::meters_per_second_t VelocityY = 0_mps;
1702 /**
1703 * \brief The desired direction to face.
1704 * 0 Degrees is defined as in the direction of the X axis.
1705 * As a result, a TargetDirection of 90 degrees will point along
1706 * the Y axis, or to the left.
1707 */
1708 Rotation2d TargetDirection{};
1709 /**
1710 * \brief The rotational rate feedforward to add to the output of the heading
1711 * controller, in radians per second. When using a motion profile for the
1712 * target direction, this can be set to the current velocity reference of
1713 * the profile.
1714 */
1715 units::radians_per_second_t TargetRateFeedforward = 0_rad_per_s;
1716
1717 /**
1718 * \brief The allowable deadband of the request.
1719 */
1720 units::meters_per_second_t Deadband = 0_mps;
1721 /**
1722 * \brief The rotational deadband of the request.
1723 */
1724 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
1725 /**
1726 * \brief The maximum absolute rotational rate to allow.
1727 * Setting this to 0 results in no cap to rotational rate.
1728 */
1729 units::radians_per_second_t MaxAbsRotationalRate = 0_rad_per_s;
1730 /**
1731 * \brief The center of rotation the robot should rotate around. This is
1732 * (0,0) by default, which will rotate around the center of the robot.
1733 */
1734 Translation2d CenterOfRotation{};
1735
1736 /**
1737 * \brief The type of control request to use for the drive motor.
1738 */
1740 /**
1741 * \brief The type of control request to use for the steer motor.
1742 */
1744 /**
1745 * \brief Whether to desaturate wheel speeds before applying.
1746 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1747 */
1749
1750 /**
1751 * \brief The perspective to use when determining which direction is forward.
1752 */
1754
1755 /**
1756 * \brief The PID controller used to maintain the desired heading.
1757 * Users can specify the PID gains to change how aggressively to maintain
1758 * heading.
1759 *
1760 * This PID controller operates on heading radians and outputs a target
1761 * rotational rate in radians per second. Note that continuous input should
1762 * be enabled on the range [-pi, pi].
1763 */
1765
1767 {
1768 HeadingController.EnableContinuousInput(-units::constants::detail::PI_VAL, units::constants::detail::PI_VAL);
1769 }
1770
1771 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
1772 {
1773 Rotation2d angleToFace = TargetDirection;
1775 /* If we're operator perspective, rotate the direction we want to face by the angle */
1776 angleToFace = angleToFace.RotateBy(parameters.operatorForwardDirection);
1777 }
1778
1779 units::radians_per_second_t toApplyOmega = TargetRateFeedforward +
1780 units::radians_per_second_t{HeadingController.Calculate(
1781 parameters.currentPose.Rotation().Radians().value(),
1782 angleToFace.Radians().value(),
1783 parameters.timestamp
1784 )};
1785 if (MaxAbsRotationalRate > 0_rad_per_s) {
1786 if (toApplyOmega > MaxAbsRotationalRate) {
1787 toApplyOmega = MaxAbsRotationalRate;
1788 } else if (toApplyOmega < -MaxAbsRotationalRate) {
1789 toApplyOmega = -MaxAbsRotationalRate;
1790 }
1791 }
1792
1793 return FieldCentric{}
1796 .WithRotationalRate(toApplyOmega)
1804 .Apply(parameters, modulesToApply);
1805 }
1806
1807 /**
1808 * \brief Modifies the PID gains of the HeadingController parameter and returns itself.
1809 *
1810 * Sets the proportional, integral, and differential coefficients used to maintain
1811 * the desired heading. Users can specify the PID gains to change how aggressively to
1812 * maintain heading.
1813 *
1814 * This PID controller operates on heading radians and outputs a target
1815 * rotational rate in radians per second.
1816 *
1817 * \param kP The proportional coefficient; must be >= 0
1818 * \param kI The integral coefficient; must be >= 0
1819 * \param kD The differential coefficient; must be >= 0
1820 * \returns this object
1821 */
1822 FieldCentricFacingAngle &WithHeadingPID(double kP, double kI, double kD)
1823 {
1824 this->HeadingController.SetPID(kP, kI, kD);
1825 return *this;
1826 }
1827
1828 /**
1829 * \brief Modifies the VelocityX parameter and returns itself.
1830 *
1831 * The velocity in the X direction. X is defined as forward according to
1832 * WPILib convention, so this determines how fast to travel forward.
1833 *
1834 * \param newVelocityX Parameter to modify
1835 * \returns this object
1836 */
1837 FieldCentricFacingAngle &WithVelocityX(units::meters_per_second_t newVelocityX)
1838 {
1839 this->VelocityX = std::move(newVelocityX);
1840 return *this;
1841 }
1842
1843 /**
1844 * \brief Modifies the VelocityY parameter and returns itself.
1845 *
1846 * The velocity in the Y direction. Y is defined as to the left according
1847 * to WPILib convention, so this determines how fast to travel to the
1848 * left.
1849 *
1850 * \param newVelocityY Parameter to modify
1851 * \returns this object
1852 */
1853 FieldCentricFacingAngle &WithVelocityY(units::meters_per_second_t newVelocityY)
1854 {
1855 this->VelocityY = std::move(newVelocityY);
1856 return *this;
1857 }
1858
1859 /**
1860 * \brief Modifies the VelocityY parameter and returns itself.
1861 *
1862 * The desired direction to face. 0 Degrees is defined as in the direction of
1863 * the X axis. As a result, a TargetDirection of 90 degrees will point along
1864 * the Y axis, or to the left.
1865 *
1866 * \param newTargetDirection Parameter to modify
1867 * \returns this object
1868 */
1869 FieldCentricFacingAngle &WithTargetDirection(Rotation2d newTargetDirection)
1870 {
1871 this->TargetDirection = std::move(newTargetDirection);
1872 return *this;
1873 }
1874
1875 /**
1876 * \brief Modifies the VelocityY parameter and returns itself.
1877 *
1878 * The rotational rate feedforward to add to the output of the heading
1879 * controller, in radians per second. When using a motion profile for the
1880 * target direction, this can be set to the current velocity reference of
1881 * the profile.
1882 *
1883 * \param newTargetRateFeedforward Parameter to modify
1884 * \returns this object
1885 */
1886 FieldCentricFacingAngle &WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
1887 {
1888 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
1889 return *this;
1890 }
1891
1892 /**
1893 * \brief Modifies the Deadband parameter and returns itself.
1894 *
1895 * The allowable deadband of the request.
1896 *
1897 * \param newDeadband Parameter to modify
1898 * \returns this object
1899 */
1900 FieldCentricFacingAngle &WithDeadband(units::meters_per_second_t newDeadband)
1901 {
1902 this->Deadband = std::move(newDeadband);
1903 return *this;
1904 }
1905
1906 /**
1907 * \brief Modifies the RotationalDeadband parameter and returns itself.
1908 *
1909 * The rotational deadband of the request.
1910 *
1911 * \param newRotationalDeadband Parameter to modify
1912 * \returns this object
1913 */
1914 FieldCentricFacingAngle &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
1915 {
1916 this->RotationalDeadband = std::move(newRotationalDeadband);
1917 return *this;
1918 }
1919
1920 /**
1921 * \brief Modifies the MaxAbsRotationalRate parameter and returns itself.
1922 *
1923 * The maximum absolute rotational rate to allow.
1924 * Setting this to 0 results in no cap to rotational rate.
1925 *
1926 * \param newMaxAbsRotationalRate Parameter to modify
1927 * \returns this object
1928 */
1929 FieldCentricFacingAngle &WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
1930 {
1931 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
1932 return *this;
1933 }
1934
1935 /**
1936 * \brief Modifies the CenterOfRotation parameter and returns itself.
1937 *
1938 * The center of rotation the robot should rotate around. This is (0,0) by
1939 * default, which will rotate around the center of the robot.
1940 *
1941 * \param newCenterOfRotation Parameter to modify
1942 * \returns this object
1943 */
1944 FieldCentricFacingAngle &WithCenterOfRotation(Translation2d newCenterOfRotation)
1945 {
1946 this->CenterOfRotation = std::move(newCenterOfRotation);
1947 return *this;
1948 }
1949
1950 /**
1951 * \brief Modifies the DriveRequestType parameter and returns itself.
1952 *
1953 * The type of control request to use for the drive motor.
1954 *
1955 * \param newDriveRequestType Parameter to modify
1956 * \returns this object
1957 */
1959 {
1960 this->DriveRequestType = std::move(newDriveRequestType);
1961 return *this;
1962 }
1963
1964 /**
1965 * \brief Modifies the SteerRequestType parameter and returns itself.
1966 *
1967 * The type of control request to use for the steer motor.
1968 *
1969 * \param newSteerRequestType Parameter to modify
1970 * \returns this object
1971 */
1973 {
1974 this->SteerRequestType = std::move(newSteerRequestType);
1975 return *this;
1976 }
1977
1978 /**
1979 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
1980 *
1981 * Whether to desaturate wheel speeds before applying. For more information, see
1982 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
1983 *
1984 * \param newDesaturateWheelSpeeds Parameter to modify
1985 * \returns this object
1986 */
1988 {
1989 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1990 return *this;
1991 }
1992
1993 /**
1994 * \brief Modifies the ForwardPerspective parameter and returns itself.
1995 *
1996 * The perspective to use when determining which direction is forward.
1997 *
1998 * \param newForwardPerspective Parameter to modify
1999 * \returns this object
2000 */
2002 {
2003 this->ForwardPerspective = std::move(newForwardPerspective);
2004 return *this;
2005 }
2006};
2007
2008/**
2009 * \brief Drives the swerve drivetrain in a robot-centric manner, maintaining a
2010 * specified heading angle to ensure the robot is facing the desired direction
2011 *
2012 * When users use this request, they specify the direction the robot should
2013 * travel oriented against the robot itself, and the direction the robot should
2014 * be facing relative to the field.
2015 *
2016 * An example scenario is that the robot is oriented to the east, the VelocityX
2017 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees.
2018 * In this scenario, the robot would drive forward at 5 m/s and turn clockwise
2019 * to a target of 180 degrees.
2020 *
2021 * This control request is especially useful for vision control, where the
2022 * robot should be facing a vision target throughout the motion.
2023 */
2025public:
2026 /**
2027 * \brief The velocity in the X direction. X is defined as forward according
2028 * to WPILib convention, so this determines how fast to travel forward.
2029 */
2030 units::meters_per_second_t VelocityX = 0_mps;
2031 /**
2032 * \brief The velocity in the Y direction. Y is defined as to the left
2033 * according to WPILib convention, so this determines how fast to travel to
2034 * the left.
2035 */
2036 units::meters_per_second_t VelocityY = 0_mps;
2037 /**
2038 * \brief The desired direction to face.
2039 * 0 Degrees is defined as in the direction of the X axis.
2040 * As a result, a TargetDirection of 90 degrees will point along
2041 * the Y axis, or to the left.
2042 */
2043 Rotation2d TargetDirection{};
2044 /**
2045 * \brief The rotational rate feedforward to add to the output of the heading
2046 * controller, in radians per second. When using a motion profile for the
2047 * target direction, this can be set to the current velocity reference of
2048 * the profile.
2049 */
2050 units::radians_per_second_t TargetRateFeedforward = 0_rad_per_s;
2051
2052 /**
2053 * \brief The allowable deadband of the request.
2054 */
2055 units::meters_per_second_t Deadband = 0_mps;
2056 /**
2057 * \brief The rotational deadband of the request.
2058 */
2059 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
2060 /**
2061 * \brief The maximum absolute rotational rate to allow.
2062 * Setting this to 0 results in no cap to rotational rate.
2063 */
2064 units::radians_per_second_t MaxAbsRotationalRate = 0_rad_per_s;
2065 /**
2066 * \brief The center of rotation the robot should rotate around. This is
2067 * (0,0) by default, which will rotate around the center of the robot.
2068 */
2069 Translation2d CenterOfRotation{};
2070
2071 /**
2072 * \brief The type of control request to use for the drive motor.
2073 */
2075 /**
2076 * \brief The type of control request to use for the steer motor.
2077 */
2079 /**
2080 * \brief Whether to desaturate wheel speeds before applying.
2081 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
2082 */
2084
2085 /**
2086 * \brief The perspective to use when determining which direction is forward
2087 * for the target heading.
2088 */
2090
2091 /**
2092 * \brief The PID controller used to maintain the desired heading.
2093 * Users can specify the PID gains to change how aggressively to maintain
2094 * heading.
2095 *
2096 * This PID controller operates on heading radians and outputs a target
2097 * rotational rate in radians per second. Note that continuous input should
2098 * be enabled on the range [-pi, pi].
2099 */
2101
2103 {
2104 HeadingController.EnableContinuousInput(-units::constants::detail::PI_VAL, units::constants::detail::PI_VAL);
2105 }
2106
2107 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2108 {
2109 Rotation2d angleToFace = TargetDirection;
2111 /* If we're operator perspective, rotate the direction we want to face by the angle */
2112 angleToFace = angleToFace.RotateBy(parameters.operatorForwardDirection);
2113 }
2114
2115 units::radians_per_second_t toApplyOmega = TargetRateFeedforward +
2116 units::radians_per_second_t{HeadingController.Calculate(
2117 parameters.currentPose.Rotation().Radians().value(),
2118 angleToFace.Radians().value(),
2119 parameters.timestamp
2120 )};
2121 if (MaxAbsRotationalRate > 0_rad_per_s) {
2122 if (toApplyOmega > MaxAbsRotationalRate) {
2123 toApplyOmega = MaxAbsRotationalRate;
2124 } else if (toApplyOmega < -MaxAbsRotationalRate) {
2125 toApplyOmega = -MaxAbsRotationalRate;
2126 }
2127 }
2128
2129 return RobotCentric{}
2132 .WithRotationalRate(toApplyOmega)
2139 .Apply(parameters, modulesToApply);
2140 }
2141
2142 /**
2143 * \brief Modifies the PID gains of the HeadingController parameter and returns itself.
2144 *
2145 * Sets the proportional, integral, and differential coefficients used to maintain
2146 * the desired heading. Users can specify the PID gains to change how aggressively to
2147 * maintain heading.
2148 *
2149 * This PID controller operates on heading radians and outputs a target
2150 * rotational rate in radians per second.
2151 *
2152 * \param kP The proportional coefficient; must be >= 0
2153 * \param kI The integral coefficient; must be >= 0
2154 * \param kD The differential coefficient; must be >= 0
2155 * \returns this object
2156 */
2157 RobotCentricFacingAngle &WithHeadingPID(double kP, double kI, double kD)
2158 {
2159 this->HeadingController.SetPID(kP, kI, kD);
2160 return *this;
2161 }
2162
2163 /**
2164 * \brief Modifies the VelocityX parameter and returns itself.
2165 *
2166 * The velocity in the X direction. X is defined as forward according to
2167 * WPILib convention, so this determines how fast to travel forward.
2168 *
2169 * \param newVelocityX Parameter to modify
2170 * \returns this object
2171 */
2172 RobotCentricFacingAngle &WithVelocityX(units::meters_per_second_t newVelocityX)
2173 {
2174 this->VelocityX = std::move(newVelocityX);
2175 return *this;
2176 }
2177
2178 /**
2179 * \brief Modifies the VelocityY parameter and returns itself.
2180 *
2181 * The velocity in the Y direction. Y is defined as to the left according
2182 * to WPILib convention, so this determines how fast to travel to the
2183 * left.
2184 *
2185 * \param newVelocityY Parameter to modify
2186 * \returns this object
2187 */
2188 RobotCentricFacingAngle &WithVelocityY(units::meters_per_second_t newVelocityY)
2189 {
2190 this->VelocityY = std::move(newVelocityY);
2191 return *this;
2192 }
2193
2194 /**
2195 * \brief Modifies the VelocityY parameter and returns itself.
2196 *
2197 * The desired direction to face. 0 Degrees is defined as in the direction of
2198 * the X axis. As a result, a TargetDirection of 90 degrees will point along
2199 * the Y axis, or to the left.
2200 *
2201 * \param newTargetDirection Parameter to modify
2202 * \returns this object
2203 */
2204 RobotCentricFacingAngle &WithTargetDirection(Rotation2d newTargetDirection)
2205 {
2206 this->TargetDirection = std::move(newTargetDirection);
2207 return *this;
2208 }
2209
2210 /**
2211 * \brief Modifies the VelocityY parameter and returns itself.
2212 *
2213 * The rotational rate feedforward to add to the output of the heading
2214 * controller, in radians per second. When using a motion profile for the
2215 * target direction, this can be set to the current velocity reference of
2216 * the profile.
2217 *
2218 * \param newTargetRateFeedforward Parameter to modify
2219 * \returns this object
2220 */
2221 RobotCentricFacingAngle &WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
2222 {
2223 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
2224 return *this;
2225 }
2226
2227 /**
2228 * \brief Modifies the Deadband parameter and returns itself.
2229 *
2230 * The allowable deadband of the request.
2231 *
2232 * \param newDeadband Parameter to modify
2233 * \returns this object
2234 */
2235 RobotCentricFacingAngle &WithDeadband(units::meters_per_second_t newDeadband)
2236 {
2237 this->Deadband = std::move(newDeadband);
2238 return *this;
2239 }
2240
2241 /**
2242 * \brief Modifies the RotationalDeadband parameter and returns itself.
2243 *
2244 * The rotational deadband of the request.
2245 *
2246 * \param newRotationalDeadband Parameter to modify
2247 * \returns this object
2248 */
2249 RobotCentricFacingAngle &WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
2250 {
2251 this->RotationalDeadband = std::move(newRotationalDeadband);
2252 return *this;
2253 }
2254
2255 /**
2256 * \brief Modifies the MaxAbsRotationalRate parameter and returns itself.
2257 *
2258 * The maximum absolute rotational rate to allow.
2259 * Setting this to 0 results in no cap to rotational rate.
2260 *
2261 * \param newMaxAbsRotationalRate Parameter to modify
2262 * \returns this object
2263 */
2264 RobotCentricFacingAngle &WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
2265 {
2266 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
2267 return *this;
2268 }
2269
2270 /**
2271 * \brief Modifies the CenterOfRotation parameter and returns itself.
2272 *
2273 * The center of rotation the robot should rotate around. This is (0,0) by
2274 * default, which will rotate around the center of the robot.
2275 *
2276 * \param newCenterOfRotation Parameter to modify
2277 * \returns this object
2278 */
2279 RobotCentricFacingAngle &WithCenterOfRotation(Translation2d newCenterOfRotation)
2280 {
2281 this->CenterOfRotation = std::move(newCenterOfRotation);
2282 return *this;
2283 }
2284
2285 /**
2286 * \brief Modifies the DriveRequestType parameter and returns itself.
2287 *
2288 * The type of control request to use for the drive motor.
2289 *
2290 * \param newDriveRequestType Parameter to modify
2291 * \returns this object
2292 */
2294 {
2295 this->DriveRequestType = std::move(newDriveRequestType);
2296 return *this;
2297 }
2298
2299 /**
2300 * \brief Modifies the SteerRequestType parameter and returns itself.
2301 *
2302 * The type of control request to use for the steer motor.
2303 *
2304 * \param newSteerRequestType Parameter to modify
2305 * \returns this object
2306 */
2308 {
2309 this->SteerRequestType = std::move(newSteerRequestType);
2310 return *this;
2311 }
2312
2313 /**
2314 * \brief Modifies the DesaturateWheelSpeeds parameter and returns itself.
2315 *
2316 * Whether to desaturate wheel speeds before applying. For more information, see
2317 * the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
2318 *
2319 * \param newDesaturateWheelSpeeds Parameter to modify
2320 * \returns this object
2321 */
2323 {
2324 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
2325 return *this;
2326 }
2327
2328 /**
2329 * \brief Modifies the ForwardPerspective parameter and returns itself.
2330 *
2331 * The perspective to use when determining which direction is forward
2332 * for the target heading.
2333 *
2334 * \param newForwardPerspective Parameter to modify
2335 * \returns this object
2336 */
2338 {
2339 this->ForwardPerspective = std::move(newForwardPerspective);
2340 return *this;
2341 }
2342};
2343
2344/**
2345 * \brief SysId-specific SwerveRequest to characterize the translational
2346 * characteristics of a swerve drivetrain.
2347 */
2349public:
2350 /**
2351 * \brief Voltage to apply to drive wheels.
2352 */
2353 units::volt_t VoltsToApply = 0_V;
2354
2355 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2356 {
2357 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2358 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2360 modulesToApply[i]->Apply(
2363 );
2364 break;
2366 modulesToApply[i]->Apply(
2369 );
2370 break;
2371 }
2372 }
2374 }
2375
2376 /**
2377 * \brief Sets the voltage to apply to drive wheels.
2378 *
2379 * \param volts Voltage to apply
2380 * \returns this request
2381 */
2382 SysIdSwerveTranslation &WithVolts(units::volt_t volts) &
2383 {
2384 this->VoltsToApply = volts;
2385 return *this;
2386 }
2387 /**
2388 * \brief Sets the voltage to apply to drive wheels.
2389 *
2390 * \param volts Voltage to apply
2391 * \returns this request
2392 */
2393 SysIdSwerveTranslation &&WithVolts(units::volt_t volts) &&
2394 {
2395 this->VoltsToApply = volts;
2396 return std::move(*this);
2397 }
2398};
2399
2400/**
2401 * \brief SysId-specific SwerveRequest to characterize the rotational
2402 * characteristics of a swerve drivetrain. This is useful to
2403 * characterize the heading controller for FieldCentricFacingAngle.
2404 *
2405 * The RotationalRate of this swerve request should be logged.
2406 * When importing the log to SysId, set the "voltage" to
2407 * RotationalRate, "position" to the Pigeon 2 Yaw, and "velocity"
2408 * to the Pigeon 2 AngularVelocityZWorld. Note that the position
2409 * and velocity will both need to be scaled by pi/180.
2410 *
2411 * Alternatively, the MotorVoltage of one of the drive motors can
2412 * be loaded into the SysId "voltage" field, which can be useful
2413 * when determining the MOI of the robot.
2414 */
2416public:
2417 /**
2418 * \brief The angular rate to rotate at, in radians per second.
2419 */
2420 units::radians_per_second_t RotationalRate = 0_rad_per_s;
2421
2422 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2423 {
2424 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2425 auto const speed = RotationalRate * (parameters.moduleLocations[i].Norm() / 1_rad);
2426 auto const driveVoltage = speed / parameters.kMaxSpeed * 12_V;
2427
2428 auto const angle = parameters.moduleLocations[i].Angle() + Rotation2d{90_deg};
2429
2430 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2432 modulesToApply[i]->Apply(
2433 controls::VoltageOut{driveVoltage},
2434 controls::PositionVoltage{angle.Radians()}
2435 );
2436 break;
2438 modulesToApply[i]->Apply(
2439 controls::VoltageOut{driveVoltage},
2440 controls::PositionTorqueCurrentFOC{angle.Radians()}
2441 );
2442 break;
2443 }
2444 }
2446 }
2447
2448 /**
2449 * \brief Update the angular rate to rotate at, in radians per second.
2450 *
2451 * \param rotationalRate Angular rate to rotate at
2452 * \returns this request
2453 */
2454 SysIdSwerveRotation &WithRotationalRate(units::radians_per_second_t rotationalRate) &
2455 {
2456 this->RotationalRate = rotationalRate;
2457 return *this;
2458 }
2459 /**
2460 * \brief Update the angular rate to rotate at, in radians per second.
2461 *
2462 * \param rotationalRate Angular rate to rotate at
2463 * \returns this request
2464 */
2465 SysIdSwerveRotation &&WithRotationalRate(units::radians_per_second_t rotationalRate) &&
2466 {
2467 this->RotationalRate = rotationalRate;
2468 return std::move(*this);
2469 }
2470};
2471
2472/**
2473 * \brief SysId-specific SwerveRequest to characterize the steer module
2474 * characteristics of a swerve drivetrain.
2475 */
2477public:
2478 /**
2479 * \brief Voltage to apply to drive wheels.
2480 */
2481 units::volt_t VoltsToApply = 0_V;
2482
2483 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span<std::unique_ptr<impl::SwerveModuleImpl> const> modulesToApply) override
2484 {
2485 for (size_t i = 0; i < modulesToApply.size(); ++i) {
2486 modulesToApply[i]->Apply(controls::CoastOut{}, controls::VoltageOut{VoltsToApply});
2487 }
2489 }
2490
2491 /**
2492 * \brief Update the voltage to apply to the drive wheels.
2493 *
2494 * \param volts Voltage to apply
2495 * \returns this request
2496 */
2497 SysIdSwerveSteerGains &WithVolts(units::volt_t volts) &
2498 {
2499 this->VoltsToApply = volts;
2500 return *this;
2501 }
2502 /**
2503 * \brief Update the voltage to apply to the drive wheels.
2504 *
2505 * \param volts Voltage to apply
2506 * \returns this request
2507 */
2508 SysIdSwerveSteerGains &&WithVolts(units::volt_t volts) &&
2509 {
2510 this->VoltsToApply = volts;
2511 return std::move(*this);
2512 }
2513};
2514
2515}
2516}
2517}
2518}
Request coast neutral output of actuator.
Definition CoastOut.hpp:21
Requires Phoenix Pro; Request PID to target position with torque current feedforward.
Definition PositionTorqueCurrentFOC.hpp:27
Request PID to target position with voltage feedforward.
Definition PositionVoltage.hpp:26
Request a specified voltage.
Definition VoltageOut.hpp:24
Phoenix-centric PID controller taken from WPI's frc#PIDController class.
Definition PhoenixPIDController.hpp:22
double Calculate(double measurement, double setpoint, units::second_t currentTimestamp)
Returns the next output of the PID controller.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
static void DesaturateWheelSpeeds(WheelSpeeds *moduleStates, units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
WheelSpeeds ToSwerveModuleStates(ChassisSpeeds const &chassisSpeeds, Translation2d const &centerOfRotation=Translation2d{})
Performs inverse kinematics to return the module states from a desired chassis velocity.
Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1320
ApplyFieldSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1528
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1364
ApplyFieldSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1487
ApplyFieldSpeeds && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1667
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1369
ApplyFieldSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1571
ApplyFieldSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1557
ApplyFieldSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1508
ApplyFieldSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1626
ChassisSpeeds Speeds
The field-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1325
ApplyFieldSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1598
ApplyFieldSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1467
ApplyFieldSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1611
std::vector< units::newton_t > WheelForceFeedforwardsX
Field-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1336
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1371
ApplyFieldSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1640
ApplyFieldSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1433
std::vector< units::newton_t > WheelForceFeedforwardsY
Field-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1347
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1351
ApplyFieldSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1446
ApplyFieldSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1543
ApplyFieldSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1584
ApplyFieldSpeeds & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1654
Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1023
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1070
ApplyRobotSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1279
ChassisSpeeds Speeds
The robot-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1029
std::vector< units::newton_t > WheelForceFeedforwardsY
Robot-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1051
std::vector< units::newton_t > WheelForceFeedforwardsX
Robot-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1040
ApplyRobotSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1225
ApplyRobotSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1239
ApplyRobotSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1101
ApplyRobotSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1135
ApplyRobotSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1114
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1068
ApplyRobotSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1266
ApplyRobotSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1176
ApplyRobotSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1211
ApplyRobotSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1196
ApplyRobotSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1252
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1055
ApplyRobotSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1155
ApplyRobotSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1308
ApplyRobotSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1294
Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:1689
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1748
FieldCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:1914
FieldCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:1929
FieldCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1972
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:1708
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:1729
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:1695
FieldCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2001
FieldCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1869
FieldCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1987
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:1764
units::radians_per_second_t TargetRateFeedforward
The rotational rate feedforward to add to the output of the heading controller, in radians per second...
Definition SwerveRequest.hpp:1715
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:1734
FieldCentricFacingAngle()
Definition SwerveRequest.hpp:1766
FieldCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1853
FieldCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:1837
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:1720
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:1701
FieldCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:1900
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:1724
FieldCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1958
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1771
FieldCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1886
FieldCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1944
FieldCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:1822
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1753
Drives the swerve drivetrain in a field-centric manner.
Definition SwerveRequest.hpp:172
FieldCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:352
FieldCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:435
FieldCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:406
FieldCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:421
FieldCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:323
FieldCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:489
FieldCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:393
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:194
FieldCentric & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:532
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:190
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:184
FieldCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:476
FieldCentric && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:545
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:224
FieldCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:379
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:178
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:203
FieldCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:292
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:217
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:222
FieldCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:518
FieldCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:366
FieldCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:338
FieldCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:308
FieldCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:449
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:198
FieldCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:278
FieldCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:462
FieldCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:504
Does nothing to the swerve module state.
Definition SwerveRequest.hpp:67
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::span< std::unique_ptr< impl::SwerveModuleImpl > const >) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:69
Sets the swerve drive modules to point to a specified direction.
Definition SwerveRequest.hpp:902
PointWheelsAt && WithModuleDirection(Rotation2d newModuleDirection) &&
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:954
PointWheelsAt && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:981
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:918
PointWheelsAt && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1008
PointWheelsAt & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:968
PointWheelsAt & WithModuleDirection(Rotation2d newModuleDirection) &
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:940
Rotation2d ModuleDirection
The direction to point the modules toward.
Definition SwerveRequest.hpp:908
PointWheelsAt & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:995
Drives the swerve drivetrain in a robot-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:2024
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2107
units::radians_per_second_t TargetRateFeedforward
The rotational rate feedforward to add to the output of the heading controller, in radians per second...
Definition SwerveRequest.hpp:2050
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward for the target heading.
Definition SwerveRequest.hpp:2089
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:2055
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:2036
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:2083
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:2069
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:2059
RobotCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:2264
RobotCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2221
RobotCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2307
RobotCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:2249
RobotCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:2322
RobotCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2337
RobotCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2188
RobotCentricFacingAngle()
Definition SwerveRequest.hpp:2102
RobotCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:2235
RobotCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:2157
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:2030
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:2100
RobotCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:2279
RobotCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2204
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:2043
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:2064
RobotCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2293
RobotCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:2172
Drives the swerve drivetrain in a robot-centric manner.
Definition SwerveRequest.hpp:565
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:583
RobotCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:767
RobotCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:795
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:611
RobotCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:753
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:577
RobotCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:892
RobotCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:780
RobotCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:726
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:592
RobotCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:666
RobotCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:740
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:571
RobotCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:712
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:613
RobotCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:863
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:597
RobotCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:809
RobotCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:836
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:588
RobotCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:823
RobotCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:850
RobotCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:652
RobotCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:682
RobotCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:697
RobotCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:878
Sets the swerve drive module states to point inward on the robot in an "X" fashion,...
Definition SwerveRequest.hpp:80
SwerveDriveBrake & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:112
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:91
SwerveDriveBrake && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:125
SwerveDriveBrake && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:152
SwerveDriveBrake & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:139
Container for all the Swerve Requests.
Definition SwerveRequest.hpp:46
virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply)=0
Applies this swerve request to the given modules.
SysId-specific SwerveRequest to characterize the rotational characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2415
units::radians_per_second_t RotationalRate
The angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2420
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2422
SysIdSwerveRotation && WithRotationalRate(units::radians_per_second_t rotationalRate) &&
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2465
SysIdSwerveRotation & WithRotationalRate(units::radians_per_second_t rotationalRate) &
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2454
SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2476
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2483
SysIdSwerveSteerGains && WithVolts(units::volt_t volts) &&
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2508
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2481
SysIdSwerveSteerGains & WithVolts(units::volt_t volts) &
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2497
SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain...
Definition SwerveRequest.hpp:2348
SysIdSwerveTranslation & WithVolts(units::volt_t volts) &
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2382
SysIdSwerveTranslation && WithVolts(units::volt_t volts) &&
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2393
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2353
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2355
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
static constexpr int OK
No Error.
Definition StatusCodes.h:35
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:25
@ Position
Control the drive motor using an unprofiled position request.
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:41
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
ForwardPerspectiveValue
In field-centric control, the direction of "forward" is sometimes different depending on perspective.
Definition SwerveRequest.hpp:21
@ BlueAlliance
"Forward" (positive X) is always from the perspective of the blue alliance (i.e.
@ OperatorPerspective
"Forward" (positive X) is determined from the operator's perspective.
Definition motor_constants.h:14
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:141
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:156
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:147
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:158
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:143
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:154
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:150
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:145
Contains everything the swerve module needs to apply a request.
Definition SwerveModuleImpl.hpp:66
ModuleRequest & WithSteerRequest(SteerRequestType newSteerRequest)
Modifies the SteerRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:190
ModuleRequest & WithDriveRequest(DriveRequestType newDriveRequest)
Modifies the DriveRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:177
ModuleRequest & WithUpdatePeriod(units::second_t newUpdatePeriod)
Modifies the UpdatePeriod parameter and returns itself.
Definition SwerveModuleImpl.hpp:205