CTRE Phoenix 6 C++ 24.50.0-alpha-2
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 The reference for "forward" is sometimes different if you're talking
19 * about field relative. This addresses which forward to use.
20 */
22 /**
23 * \brief This forward reference makes it so "forward" (positive X) is always towards the red alliance.
24 * This is important in situations such as path following where positive X is always towards the
25 * red alliance wall, regardless of where the operator physically are located.
26 */
27 RedAlliance = 0,
28 /**
29 * \brief This forward references makes it so "forward" (positive X) is determined from the operator's
30 * perspective. This is important for most teleop driven field-centric requests, where positive
31 * X really means to drive away from the operator.
32 *
33 * Important: Users must specify the OperatorPerspective in the SwerveDrivetrain object
34 */
36};
37
38/**
39 * \brief Container for all the Swerve Requests. Use this to find all applicable swerve
40 * drive requests.
41 *
42 * This is also an interface common to all swerve drive control requests that
43 * allow the request to calculate the state to apply to the modules.
44 */
46public:
48
49 virtual ~SwerveRequest() = default;
50
51 /**
52 * \brief Applies this swerve request to the given modules.
53 * This is typically called by the SwerveDrivetrain.
54 *
55 * \param parameters Parameters the control request needs to calculate the module state
56 * \param modulesToApply Modules to which the control request is applied
57 * \returns Status code of sending the request
58 */
59 virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) = 0;
60};
61
62/**
63 * \brief Does nothing to the swerve module state. This is the default state of a newly
64 * created swerve drive mechanism.
65 */
66class Idle : public SwerveRequest {
67public:
68 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &) override
69 {
71 }
72};
73
74/**
75 * \brief Sets the swerve drive module states to point inward on the
76 * robot in an "X" fashion, creating a natural brake which will
77 * oppose any motion.
78 */
80public:
81 /**
82 * The type of control request to use for the drive motor.
83 */
85 /**
86 * The type of control request to use for the steer motor.
87 */
89
90 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
91 {
92 for (size_t i = 0; i < modulesToApply.size(); ++i) {
93 impl::SwerveModuleState const state{0_mps, parameters.swervePositions[i].Angle()};
94 modulesToApply[i]->Apply(state, DriveRequestType, SteerRequestType);
95 }
96
98 }
99
100 /**
101 * \brief Sets the type of control request to use for the drive motor.
102 *
103 * \param driveRequestType The type of control request to use for the drive motor
104 * \returns this request
105 */
107 {
108 this->DriveRequestType = driveRequestType;
109 return *this;
110 }
111 /**
112 * \brief Sets the type of control request to use for the steer motor.
113 *
114 * \param steerRequestType The type of control request to use for the steer motor
115 * \returns this request
116 */
118 {
119 this->SteerRequestType = steerRequestType;
120 return *this;
121 }
122};
123
124/**
125 * \brief Drives the swerve drivetrain in a field-centric manner.
126 *
127 * When users use this request, they specify the direction the robot should
128 * travel oriented against the field, and the rate at which their robot should
129 * rotate about the center of the robot.
130 *
131 * An example scenario is that the robot is oriented to the east, the
132 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s.
133 * In this scenario, the robot would drive northward at 5 m/s and turn
134 * counterclockwise at 0.5 rad/s.
135 */
137public:
138 /**
139 * \brief The velocity in the X direction.
140 * X is defined as forward according to WPILib convention,
141 * so this determines how fast to travel forward.
142 */
143 units::meters_per_second_t VelocityX = 0_mps;
144 /**
145 * \brief The velocity in the Y direction.
146 * Y is defined as to the left according to WPILib convention,
147 * so this determines how fast to travel to the left.
148 */
149 units::meters_per_second_t VelocityY = 0_mps;
150 /**
151 * \brief The angular rate to rotate at.
152 * Angular rate is defined as counterclockwise positive,
153 * so this determines how fast to turn counterclockwise.
154 */
155 units::radians_per_second_t RotationalRate = 0_rad_per_s;
156 /**
157 * \brief The allowable deadband of the request.
158 */
159 units::meters_per_second_t Deadband = 0_mps;
160 /**
161 * \brief The rotational deadband of the request.
162 */
163 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
164 /**
165 * \brief The center of rotation the robot should rotate around.
166 * This is (0,0) by default, which will rotate around the center of the robot.
167 */
168 Translation2d CenterOfRotation{};
169
170 /**
171 * \brief The type of control request to use for the drive motor.
172 */
174 /**
175 * \brief The type of control request to use for the steer motor.
176 */
178 /**
179 * \brief Whether to desaturate wheel speeds before applying.
180 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
181 */
183
184 /**
185 * \brief The perspective to use when determining which direction is forward.
186 */
188
189public:
190 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
191 {
192 auto toApplyX = VelocityX;
193 auto toApplyY = VelocityY;
195 /* If we're operator perspective, modify the X/Y translation by the angle */
196 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
197 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
198 toApplyX = tmp.X() / 1_s;
199 toApplyY = tmp.Y() / 1_s;
200 }
201 auto toApplyOmega = RotationalRate;
202 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
203 toApplyX = 0_mps;
204 toApplyY = 0_mps;
205 }
206 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
207 toApplyOmega = 0_rad_per_s;
208 }
209
210 auto const speeds = impl::ChassisSpeeds::Discretize(impl::ChassisSpeeds::FromFieldRelativeSpeeds({toApplyX, toApplyY, toApplyOmega},
211 parameters.currentPose.Rotation()), parameters.updatePeriod);
212
213 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
214 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
216 }
217
218 for (size_t i = 0; i < modulesToApply.size(); ++i) {
219 modulesToApply[i]->Apply(states[i], DriveRequestType, SteerRequestType);
220 }
221
223 }
224
225 /**
226 * \brief Sets the velocity in the X direction.
227 * X is defined as forward according to WPILib convention,
228 * so this determines how fast to travel forward.
229 *
230 * \param velocityX Velocity in the X direction
231 * \returns this request
232 */
233 FieldCentric &WithVelocityX(units::meters_per_second_t velocityX)
234 {
235 this->VelocityX = velocityX;
236 return *this;
237 }
238
239 /**
240 * \brief Sets the velocity in the Y direction.
241 * Y is defined as to the left according to WPILib convention,
242 * so this determines how fast to travel to the left.
243 *
244 * \param velocityY Velocity in the Y direction
245 * \returns this request
246 */
247 FieldCentric &WithVelocityY(units::meters_per_second_t velocityY)
248 {
249 this->VelocityY = velocityY;
250 return *this;
251 }
252
253 /**
254 * \brief The angular rate to rotate at.
255 * Angular rate is defined as counterclockwise positive,
256 * so this determines how fast to turn counterclockwise.
257 *
258 * \param rotationalRate Angular rate to rotate at
259 * \returns this request
260 */
261 FieldCentric &WithRotationalRate(units::radians_per_second_t rotationalRate)
262 {
263 this->RotationalRate = rotationalRate;
264 return *this;
265 }
266
267 /**
268 * \brief Sets the allowable deadband of the request.
269 *
270 * \param deadband Allowable deadband of the request
271 * \returns this request
272 */
273 FieldCentric &WithDeadband(units::meters_per_second_t deadband)
274 {
275 this->Deadband = deadband;
276 return *this;
277 }
278 /**
279 * \brief Sets the rotational deadband of the request.
280 *
281 * \param rotationalDeadband Rotational deadband of the request
282 * \returns this request
283 */
284 FieldCentric &WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
285 {
286 this->RotationalDeadband = rotationalDeadband;
287 return *this;
288 }
289 /**
290 * \brief Sets the center of rotation of the request
291 *
292 * \param centerOfRotation The center of rotation the robot should rotate around.
293 * \returns this request
294 */
295 FieldCentric &WithCenterOfRotation(Translation2d centerOfRotation)
296 {
297 this->CenterOfRotation = centerOfRotation;
298 return *this;
299 }
300
301 /**
302 * \brief Sets the type of control request to use for the drive motor.
303 *
304 * \param driveRequestType The type of control request to use for the drive motor
305 * \returns this request
306 */
308 {
309 this->DriveRequestType = driveRequestType;
310 return *this;
311 }
312 /**
313 * \brief Sets the type of control request to use for the steer motor.
314 *
315 * \param steerRequestType The type of control request to use for the steer motor
316 * \returns this request
317 */
319 {
320 this->SteerRequestType = steerRequestType;
321 return *this;
322 }
323
324 /**
325 * \brief Sets whether to desaturate wheel speeds before applying.
326 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
327 *
328 * \param desaturateWheelSpeeds Whether to desaturate wheel speeds
329 * \returns this request
330 */
331 FieldCentric &WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
332 {
333 this->DesaturateWheelSpeeds = desaturateWheelSpeeds;
334 return *this;
335 }
336
337 /**
338 * \brief Sets the perspective to use when determining which direction is forward.
339 *
340 * \param desaturateWheelSpeeds The perspective to use when determining which direction is forward
341 * \returns this request
342 */
344 {
345 this->ForwardReference = forwardReference;
346 return *this;
347 }
348};
349
350/**
351 * \brief Drives the swerve drivetrain in a field-centric manner, maintaining a
352 * specified heading angle to ensure the robot is facing the desired direction
353 *
354 * When users use this request, they specify the direction the robot should
355 * travel oriented against the field, and the direction the robot should be facing.
356 *
357 * An example scenario is that the robot is oriented to the east, the VelocityX
358 * is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees.
359 * In this scenario, the robot would drive northward at 5 m/s and turn clockwise
360 * to a target of 180 degrees.
361 *
362 * This control request is especially useful for autonomous control, where the
363 * robot should be facing a changing direction throughout the motion.
364 */
366public:
367 /**
368 * \brief The velocity in the X direction.
369 * X is defined as forward according to WPILib convention,
370 * so this determines how fast to travel forward.
371 */
372 units::meters_per_second_t VelocityX = 0_mps;
373 /**
374 * \brief The velocity in the Y direction.
375 * Y is defined as to the left according to WPILib convention,
376 * so this determines how fast to travel to the left.
377 */
378 units::meters_per_second_t VelocityY = 0_mps;
379 /**
380 * \brief The desired direction to face.
381 * 0 Degrees is defined as in the direction of the X axis.
382 * As a result, a TargetDirection of 90 degrees will point along
383 * the Y axis, or to the left.
384 */
385 Rotation2d TargetDirection{};
386
387 /**
388 * \brief The allowable deadband of the request.
389 */
390 units::meters_per_second_t Deadband = 0_mps;
391 /**
392 * \brief The rotational deadband of the request.
393 */
394 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
395 /**
396 * \brief The center of rotation the robot should rotate around.
397 * This is (0,0) by default, which will rotate around the center of the robot.
398 */
399 Translation2d CenterOfRotation{};
400
401 /**
402 * \brief The type of control request to use for the drive motor.
403 */
405 /**
406 * \brief The type of control request to use for the steer motor.
407 */
409 /**
410 * \brief Whether to desaturate wheel speeds before applying.
411 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
412 */
414
415 /**
416 * \brief The perspective to use when determining which direction is forward.
417 */
419
420 /**
421 * \brief The PID controller used to maintain the desired heading.
422 * Users can specify the PID gains to change how aggressively to maintain
423 * heading.
424 *
425 * This PID controller operates on heading radians and outputs a target
426 * rotational rate in radians per second.
427 */
429
430 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
431 {
432 auto toApplyX = VelocityX;
433 auto toApplyY = VelocityY;
434 Rotation2d angleToFace = TargetDirection;
436 /* If we're operator perspective, modify the X/Y translation by the angle */
437 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
438 tmp = tmp.RotateBy(parameters.operatorForwardDirection);
439 toApplyX = tmp.X() / 1_s;
440 toApplyY = tmp.Y() / 1_s;
441 /* And rotate the direction we want to face by the angle */
442 angleToFace = angleToFace.RotateBy(parameters.operatorForwardDirection);
443 }
444
445 units::radians_per_second_t toApplyOmega{HeadingController.Calculate(parameters.currentPose.Rotation().Radians().value(),
446 angleToFace.Radians().value(), parameters.timestamp)};
447 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
448 toApplyX = 0_mps;
449 toApplyY = 0_mps;
450 }
451 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
452 toApplyOmega = 0_rad_per_s;
453 }
454
455 auto const speeds = impl::ChassisSpeeds::Discretize(impl::ChassisSpeeds::FromFieldRelativeSpeeds({toApplyX, toApplyY, toApplyOmega},
456 parameters.currentPose.Rotation()), parameters.updatePeriod);
457
458 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
459 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
461 }
462
463 for (size_t i = 0; i < modulesToApply.size(); ++i) {
464 modulesToApply[i]->Apply(states[i], DriveRequestType, SteerRequestType);
465 }
466
468 }
469
470 /**
471 * \brief Sets the velocity in the X direction.
472 * X is defined as forward according to WPILib convention,
473 * so this determines how fast to travel forward.
474 *
475 * \param velocityX Velocity in the X direction
476 * \returns this request
477 */
478 FieldCentricFacingAngle &WithVelocityX(units::meters_per_second_t velocityX)
479 {
480 this->VelocityX = velocityX;
481 return *this;
482 }
483
484 /**
485 * \brief Sets the velocity in the Y direction.
486 * Y is defined as to the left according to WPILib convention,
487 * so this determines how fast to travel to the left.
488 *
489 * \param velocityY Velocity in the Y direction
490 * \returns this request
491 */
492 FieldCentricFacingAngle &WithVelocityY(units::meters_per_second_t velocityY)
493 {
494 this->VelocityY = velocityY;
495 return *this;
496 }
497
498 /**
499 * \brief Sets the desired direction to face.
500 * 0 Degrees is defined as in the direction of the X axis.
501 * As a result, a TargetDirection of 90 degrees will point along
502 * the Y axis, or to the left.
503 *
504 * \param targetDirection Desired direction to face
505 * \returns this request
506 */
507 FieldCentricFacingAngle &WithTargetDirection(Rotation2d targetDirection)
508 {
509 this->TargetDirection = targetDirection;
510 return *this;
511 }
512
513 /**
514 * \brief Sets the allowable deadband of the request.
515 *
516 * \param deadband Allowable deadband of the request
517 * \returns this request
518 */
519 FieldCentricFacingAngle &WithDeadband(units::meters_per_second_t deadband)
520 {
521 this->Deadband = deadband;
522 return *this;
523 }
524 /**
525 * \brief Sets the rotational deadband of the request.
526 *
527 * \param rotationalDeadband Rotational deadband of the request
528 * \returns this request
529 */
530 FieldCentricFacingAngle &WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
531 {
532 this->RotationalDeadband = rotationalDeadband;
533 return *this;
534 }
535 /**
536 * \brief Sets the center of rotation of the request
537 *
538 * \param centerOfRotation The center of rotation the robot should rotate around.
539 * \returns this request
540 */
541 FieldCentricFacingAngle &WithCenterOfRotation(Translation2d centerOfRotation)
542 {
543 this->CenterOfRotation = centerOfRotation;
544 return *this;
545 }
546
547 /**
548 * \brief Sets the type of control request to use for the drive motor.
549 *
550 * \param driveRequestType The type of control request to use for the drive motor
551 * \returns this request
552 */
554 {
555 this->DriveRequestType = driveRequestType;
556 return *this;
557 }
558 /**
559 * \brief Sets the type of control request to use for the steer motor.
560 *
561 * \param steerRequestType The type of control request to use for the steer motor
562 * \returns this request
563 */
565 {
566 this->SteerRequestType = steerRequestType;
567 return *this;
568 }
569
570 /**
571 * \brief Sets whether to desaturate wheel speeds before applying.
572 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
573 *
574 * \param desaturateWheelSpeeds Whether to desaturate wheel speeds
575 * \returns this request
576 */
578 {
579 this->DesaturateWheelSpeeds = desaturateWheelSpeeds;
580 return *this;
581 }
582
583 /**
584 * \brief Sets the perspective to use when determining which direction is forward.
585 *
586 * \param desaturateWheelSpeeds The perspective to use when determining which direction is forward
587 * \returns this request
588 */
590 {
591 this->ForwardReference = forwardReference;
592 return *this;
593 }
594};
595
596/**
597 * \brief Sets the swerve drive modules to point to a specified direction.
598 */
600public:
601 /**
602 * \brief The direction to point the modules toward.
603 * This direction will still be optimized to what the module was previously at.
604 */
605 Rotation2d ModuleDirection{};
606 /**
607 * \brief The type of control request to use for the drive motor.
608 */
610 /**
611 * \brief The type of control request to use for the steer motor.
612 */
614
615 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
616 {
617 for (size_t i = 0; i < modulesToApply.size(); ++i) {
619 modulesToApply[i]->Apply(state, DriveRequestType, SteerRequestType);
620 }
621
623 }
624
625 /**
626 * \brief Sets the direction to point the modules toward.
627 * This direction is still optimized to what the module was previously at.
628 *
629 * \param moduleDirection Direction to point the modules toward
630 * \returns this request
631 */
632 PointWheelsAt &WithModuleDirection(Rotation2d moduleDirection)
633 {
634 this->ModuleDirection = moduleDirection;
635 return *this;
636 }
637
638 /**
639 * \brief Sets the type of control request to use for the drive motor.
640 *
641 * \param driveRequestType The type of control request to use for the drive motor
642 * \returns this request
643 */
645 {
646 this->DriveRequestType = driveRequestType;
647 return *this;
648 }
649 /**
650 * \brief Sets the type of control request to use for the steer motor.
651 *
652 * \param steerRequestType The type of control request to use for the steer motor
653 * \returns this request
654 */
656 {
657 this->SteerRequestType = steerRequestType;
658 return *this;
659 }
660};
661
662/**
663 * \brief Drives the swerve drivetrain in a robot-centric manner.
664 *
665 * When users use this request, they specify the direction the robot should
666 * travel oriented against the robot itself, and the rate at which their
667 * robot should rotate about the center of the robot.
668 *
669 * An example scenario is that the robot is oriented to the east, the
670 * VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s.
671 * In this scenario, the robot would drive eastward at 5 m/s and turn
672 * counterclockwise at 0.5 rad/s.
673 */
675public:
676 /**
677 * \brief The velocity in the X direction.
678 * X is defined as forward according to WPILib convention,
679 * so this determines how fast to travel forward.
680 */
681 units::meters_per_second_t VelocityX = 0_mps;
682 /**
683 * \brief The velocity in the Y direction.
684 * Y is defined as to the left according to WPILib convention,
685 * so this determines how fast to travel to the left.
686 */
687 units::meters_per_second_t VelocityY = 0_mps;
688 /**
689 * \brief The angular rate to rotate at.
690 * Angular rate is defined as counterclockwise positive,
691 * so this determines how fast to turn counterclockwise.
692 */
693 units::radians_per_second_t RotationalRate = 0_rad_per_s;
694
695 /**
696 * \brief The allowable deadband of the request.
697 */
698 units::meters_per_second_t Deadband = 0_mps;
699 /**
700 * \brief The rotational deadband of the request.
701 */
702 units::radians_per_second_t RotationalDeadband = 0_rad_per_s;
703 /**
704 * \brief The center of rotation the robot should rotate around.
705 * This is (0,0) by default, which will rotate around the center of the robot.
706 */
707 Translation2d CenterOfRotation{};
708
709 /**
710 * \brief The type of control request to use for the drive motor.
711 */
713 /**
714 * \brief The type of control request to use for the steer motor.
715 */
717 /**
718 * \brief Whether to desaturate wheel speeds before applying.
719 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
720 */
722
723 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
724 {
725 auto toApplyX = VelocityX;
726 auto toApplyY = VelocityY;
727 auto toApplyOmega = RotationalRate;
728 if (units::math::hypot(toApplyX, toApplyY) < Deadband) {
729 toApplyX = 0_mps;
730 toApplyY = 0_mps;
731 }
732 if (units::math::abs(toApplyOmega) < RotationalDeadband) {
733 toApplyOmega = 0_rad_per_s;
734 }
735 impl::ChassisSpeeds const speeds{toApplyX, toApplyY, toApplyOmega};
736
737 auto states = parameters.kinematics->ToSwerveModuleStates(speeds, CenterOfRotation);
738 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
740 }
741
742 for (size_t i = 0; i < modulesToApply.size(); ++i) {
743 modulesToApply[i]->Apply(states[i], DriveRequestType, SteerRequestType);
744 }
745
747 }
748
749 /**
750 * \brief Sets the velocity in the X direction.
751 * X is defined as forward according to WPILib convention,
752 * so this determines how fast to travel forward.
753 *
754 * \param velocityX Velocity in the X direction
755 * \returns this request
756 */
757 RobotCentric &WithVelocityX(units::meters_per_second_t velocityX)
758 {
759 this->VelocityX = velocityX;
760 return *this;
761 }
762
763 /**
764 * \brief Sets the velocity in the Y direction.
765 * Y is defined as to the left according to WPILib convention,
766 * so this determines how fast to travel to the left.
767 *
768 * \param velocityY Velocity in the Y direction
769 * \returns this request
770 */
771 RobotCentric &WithVelocityY(units::meters_per_second_t velocityY)
772 {
773 this->VelocityY = velocityY;
774 return *this;
775 }
776
777 /**
778 * \brief The angular rate to rotate at.
779 * Angular rate is defined as counterclockwise positive,
780 * so this determines how fast to turn counterclockwise.
781 *
782 * \param rotationalRate Angular rate to rotate at
783 * \returns this request
784 */
785 RobotCentric &WithRotationalRate(units::radians_per_second_t rotationalRate)
786 {
787 this->RotationalRate = rotationalRate;
788 return *this;
789 }
790
791 /**
792 * \brief Sets the allowable deadband of the request.
793 *
794 * \param deadband Allowable deadband of the request
795 * \returns this request
796 */
797 RobotCentric &WithDeadband(units::meters_per_second_t deadband)
798 {
799 this->Deadband = deadband;
800 return *this;
801 }
802 /**
803 * \brief Sets the rotational deadband of the request.
804 *
805 * \param rotationalDeadband Rotational deadband of the request
806 * \returns this request
807 */
808 RobotCentric &WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
809 {
810 this->RotationalDeadband = rotationalDeadband;
811 return *this;
812 }
813 /**
814 * \brief Sets the center of rotation of the request
815 *
816 * \param centerOfRotation The center of rotation the robot should rotate around.
817 * \returns this request
818 */
819 RobotCentric &WithCenterOfRotation(Translation2d centerOfRotation)
820 {
821 this->CenterOfRotation = centerOfRotation;
822 return *this;
823 }
824
825 /**
826 * \brief Sets the type of control request to use for the drive motor.
827 *
828 * \param driveRequestType The type of control request to use for the drive motor
829 * \returns this request
830 */
832 {
833 this->DriveRequestType = driveRequestType;
834 return *this;
835 }
836 /**
837 * \brief Sets the type of control request to use for the steer motor.
838 *
839 * \param steerRequestType The type of control request to use for the steer motor
840 * \returns this request
841 */
843 {
844 this->SteerRequestType = steerRequestType;
845 return *this;
846 }
847
848 /**
849 * \brief Sets whether to desaturate wheel speeds before applying.
850 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
851 *
852 * \param desaturateWheelSpeeds Whether to desaturate wheel speeds
853 * \returns this request
854 */
855 RobotCentric &WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
856 {
857 this->DesaturateWheelSpeeds = desaturateWheelSpeeds;
858 return *this;
859 }
860};
861
862/**
863 * \brief Accepts a generic ChassisSpeeds to apply to the drivetrain.
864 */
866public:
867 /**
868 * \brief The chassis speeds to apply to the drivetrain.
869 */
871 /**
872 * \brief The center of rotation to rotate around.
873 */
874 Translation2d CenterOfRotation{};
875 /**
876 * \brief The type of control request to use for the drive motor.
877 */
879 /**
880 * \brief The type of control request to use for the steer motor.
881 */
883 /**
884 * \brief Whether to desaturate wheel speeds before applying.
885 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
886 */
888
889 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
890 {
891 auto states = parameters.kinematics->ToSwerveModuleStates(Speeds, CenterOfRotation);
892 if (DesaturateWheelSpeeds && parameters.kMaxSpeed > 0_mps) {
894 }
895
896 for (size_t i = 0; i < modulesToApply.size(); ++i) {
897 modulesToApply[i]->Apply(states[i], DriveRequestType, SteerRequestType);
898 }
899
901 }
902
903 /**
904 * \brief Sets the chassis speeds to apply to the drivetrain.
905 *
906 * \param speeds Chassis speeds to apply to the drivetrain
907 * \returns this request
908 */
910 {
911 this->Speeds = speeds;
912 return *this;
913 }
914 /**
915 * \brief Sets the center of rotation to rotate around.
916 *
917 * \param centerOfRotation Center of rotation to rotate around
918 * \returns this request
919 */
920 ApplyChassisSpeeds &WithCenterOfRotation(Translation2d centerOfRotation)
921 {
922 this->CenterOfRotation = centerOfRotation;
923 return *this;
924 }
925
926 /**
927 * \brief Sets the type of control request to use for the drive motor.
928 *
929 * \param driveRequestType The type of control request to use for the drive motor
930 * \returns this request
931 */
933 {
934 this->DriveRequestType = driveRequestType;
935 return *this;
936 }
937 /**
938 * \brief Sets the type of control request to use for the steer motor.
939 *
940 * \param steerRequestType The type of control request to use for the steer motor
941 * \returns this request
942 */
944 {
945 this->SteerRequestType = steerRequestType;
946 return *this;
947 }
948
949 /**
950 * \brief Sets whether to desaturate wheel speeds before applying.
951 * For more information, see the documentation of impl#SwerveDriveKinematics#DesaturateWheelSpeeds.
952 *
953 * \param desaturateWheelSpeeds Whether to desaturate wheel speeds
954 * \returns this request
955 */
957 {
958 this->DesaturateWheelSpeeds = desaturateWheelSpeeds;
959 return *this;
960 }
961};
962
963/**
964 * \brief SysId-specific SwerveRequest to characterize the translational
965 * characteristics of a swerve drivetrain.
966 */
968public:
969 /**
970 * \brief Voltage to apply to drive wheels.
971 */
972 units::volt_t VoltsToApply = 0_V;
973
974 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
975 {
976 for (size_t i = 0; i < modulesToApply.size(); ++i) {
977 modulesToApply[i]->Apply(controls::VoltageOut{VoltsToApply}, controls::PositionVoltage{0_tr});
978 }
980 }
981
982 /**
983 * \brief Sets the voltage to apply to drive wheels.
984 *
985 * \param volts Voltage to apply
986 * \returns this request
987 */
988 SysIdSwerveTranslation &WithVolts(units::volt_t volts)
989 {
990 this->VoltsToApply = volts;
991 return *this;
992 }
993};
994
995/**
996 * \brief SysId-specific SwerveRequest to characterize the rotational
997 * characteristics of a swerve drivetrain.
998 */
1000public:
1001 /**
1002 * \brief Voltage to apply to drive wheels.
1003 */
1004 units::volt_t VoltsToApply = 0_V;
1005
1006 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
1007 {
1008 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1009 modulesToApply[i]->Apply(controls::VoltageOut{VoltsToApply},
1010 controls::PositionVoltage{(parameters.swervePositions[i].Angle() + Rotation2d{90_deg}).Radians()});
1011 }
1013 }
1014
1015 /**
1016 * \brief Update the voltage to apply to the drive wheels.
1017 *
1018 * \param volts Voltage to apply
1019 * \returns this request
1020 */
1021 SysIdSwerveRotation &WithVolts(units::volt_t volts)
1022 {
1023 this->VoltsToApply = volts;
1024 return *this;
1025 }
1026};
1027
1028/**
1029 * \brief SysId-specific SwerveRequest to characterize the steer module
1030 * characteristics of a swerve drivetrain.
1031 */
1033public:
1034 /**
1035 * \brief Voltage to apply to drive wheels.
1036 */
1037 units::volt_t VoltsToApply = 0_V;
1038
1039 ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector<std::unique_ptr<impl::SwerveModuleImpl>> const &modulesToApply) override
1040 {
1041 for (size_t i = 0; i < modulesToApply.size(); ++i) {
1042 modulesToApply[i]->Apply(controls::VoltageOut{0_V}, controls::VoltageOut{VoltsToApply});
1043 }
1045 }
1046
1047 /**
1048 * \brief Update the voltage to apply to the drive wheels.
1049 *
1050 * \param volts Voltage to apply
1051 * \returns this request
1052 */
1053 SysIdSwerveSteerGains &WithVolts(units::volt_t volts)
1054 {
1055 this->VoltsToApply = volts;
1056 return *this;
1057 }
1058};
1059
1060}
1061}
1062}
1063}
its the or e mails sent from or on behalf of the Company are free of trojan timebombs or other harmful components Some jurisdictions do not allow the exclusion of certain types of warranties or limitations on applicable statutory rights of a so some or all of the above exclusions and limitations may not apply to You But in such a case the exclusions and limitations set forth in this section shall be applied to the greatest extent enforceable under applicable law To the extent any warranty exists under law that cannot be the Company shall be solely responsible for such warranty Severability and Waiver Severability If any provision of this Agreement is held to be unenforceable or such provision will be changed and interpreted to accomplish the objectives of such provision to the greatest extent possible under applicable law and the remaining provisions will continue in full force and effect Waiver Except as provided the failure to exercise a right or to require performance of an obligation under this Agreement shall not affect a party s ability to exercise such right or require such performance at any time thereafter nor shall the waiver of a breach constitute waiver of any subsequent breach Product Claims The Company does not make any warranties concerning the Software United States Legal Compliance You represent and warrant or that has been designated by the United States government as a terrorist supporting at its sole to modify or replace this Agreement at any time If a revision is material we will provide at least days notice prior to any new terms taking effect What constitutes a material change will be determined at the sole discretion of the Company By continuing to access or use the Software after any revisions become You agree to be bound by the revised terms If You do not agree to the new You are no longer authorized to use the Software Governing Law The laws of the State of United States of excluding its conflicts of law shall govern this Agreement and your use of the Software Your use of the Software may also be subject to other state
Definition: CTRE_LICENSE.txt:283
Request PID to target position with voltage feedforward.
Definition: PositionVoltage.hpp:31
Request a specified voltage.
Definition: VoltageOut.hpp:29
Phoenix-centric PID controller taken from WPI's frc::PIDController class.
Definition: PhoenixPIDController.hpp:23
double Calculate(double measurement, double setpoint, units::second_t currentTimestamp)
Returns the next output of the PID controller.
WheelSpeeds ToSwerveModuleStates(ChassisSpeeds const &speeds, Translation2d const &centerOfRotation=Translation2d{})
Performs inverse kinematics to return the module states from a desired chassis velocity.
static void DesaturateWheelSpeeds(WheelSpeeds *moduleStates, units::meters_per_second_t attainableMaxSpeed)
Renormalizes the wheel speeds if any individual speed is above the specified maximum.
DriveRequestType
All possible control requests for the module drive motor.
Definition: SwerveModuleImpl.hpp:48
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
SteerRequestType
All possible control requests for the module steer motor.
Definition: SwerveModuleImpl.hpp:32
@ MotionMagicExpo
Control the drive motor using a Motion Magic® Expo request.
Accepts a generic ChassisSpeeds to apply to the drivetrain.
Definition: SwerveRequest.hpp:865
ApplyChassisSpeeds & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:932
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:887
ApplyChassisSpeeds & WithSpeeds(impl::ChassisSpeeds speeds)
Sets the chassis speeds to apply to the drivetrain.
Definition: SwerveRequest.hpp:909
ApplyChassisSpeeds & WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
Sets whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:956
impl::ChassisSpeeds Speeds
The chassis speeds to apply to the drivetrain.
Definition: SwerveRequest.hpp:870
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:878
ApplyChassisSpeeds & WithCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation to rotate around.
Definition: SwerveRequest.hpp:920
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition: SwerveRequest.hpp:874
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:889
ApplyChassisSpeeds & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:943
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:882
Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensu...
Definition: SwerveRequest.hpp:365
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:413
FieldCentricFacingAngle & WithDeadband(units::meters_per_second_t deadband)
Sets the allowable deadband of the request.
Definition: SwerveRequest.hpp:519
FieldCentricFacingAngle & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:564
Rotation2d TargetDirection
The desired direction to face.
Definition: SwerveRequest.hpp:385
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition: SwerveRequest.hpp:372
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:404
FieldCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
Sets the rotational deadband of the request.
Definition: SwerveRequest.hpp:530
FieldCentricFacingAngle & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:553
FieldCentricFacingAngle & WithCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation of the request.
Definition: SwerveRequest.hpp:541
FieldCentricFacingAngle & WithTargetDirection(Rotation2d targetDirection)
Sets the desired direction to face.
Definition: SwerveRequest.hpp:507
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition: SwerveRequest.hpp:428
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:408
ForwardReferenceValue ForwardReference
The perspective to use when determining which direction is forward.
Definition: SwerveRequest.hpp:418
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition: SwerveRequest.hpp:399
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition: SwerveRequest.hpp:390
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:430
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition: SwerveRequest.hpp:378
FieldCentricFacingAngle & WithVelocityY(units::meters_per_second_t velocityY)
Sets the velocity in the Y direction.
Definition: SwerveRequest.hpp:492
FieldCentricFacingAngle & WithVelocityX(units::meters_per_second_t velocityX)
Sets the velocity in the X direction.
Definition: SwerveRequest.hpp:478
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition: SwerveRequest.hpp:394
FieldCentricFacingAngle & WithForwardReference(ForwardReferenceValue forwardReference)
Sets the perspective to use when determining which direction is forward.
Definition: SwerveRequest.hpp:589
FieldCentricFacingAngle & WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
Sets whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:577
Drives the swerve drivetrain in a field-centric manner.
Definition: SwerveRequest.hpp:136
FieldCentric & WithVelocityY(units::meters_per_second_t velocityY)
Sets the velocity in the Y direction.
Definition: SwerveRequest.hpp:247
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:173
FieldCentric & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:307
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition: SwerveRequest.hpp:159
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition: SwerveRequest.hpp:155
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition: SwerveRequest.hpp:149
ForwardReferenceValue ForwardReference
The perspective to use when determining which direction is forward.
Definition: SwerveRequest.hpp:187
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:190
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition: SwerveRequest.hpp:143
FieldCentric & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:318
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition: SwerveRequest.hpp:168
FieldCentric & WithVelocityX(units::meters_per_second_t velocityX)
Sets the velocity in the X direction.
Definition: SwerveRequest.hpp:233
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:182
FieldCentric & WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
Sets the rotational deadband of the request.
Definition: SwerveRequest.hpp:284
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:177
FieldCentric & WithForwardReference(ForwardReferenceValue forwardReference)
Sets the perspective to use when determining which direction is forward.
Definition: SwerveRequest.hpp:343
FieldCentric & WithRotationalRate(units::radians_per_second_t rotationalRate)
The angular rate to rotate at.
Definition: SwerveRequest.hpp:261
FieldCentric & WithCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation of the request.
Definition: SwerveRequest.hpp:295
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition: SwerveRequest.hpp:163
FieldCentric & WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
Sets whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:331
FieldCentric & WithDeadband(units::meters_per_second_t deadband)
Sets the allowable deadband of the request.
Definition: SwerveRequest.hpp:273
Does nothing to the swerve module state.
Definition: SwerveRequest.hpp:66
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:68
Sets the swerve drive modules to point to a specified direction.
Definition: SwerveRequest.hpp:599
PointWheelsAt & WithModuleDirection(Rotation2d moduleDirection)
Sets the direction to point the modules toward.
Definition: SwerveRequest.hpp:632
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:613
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:615
PointWheelsAt & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:644
PointWheelsAt & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:655
Rotation2d ModuleDirection
The direction to point the modules toward.
Definition: SwerveRequest.hpp:605
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:609
Drives the swerve drivetrain in a robot-centric manner.
Definition: SwerveRequest.hpp:674
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition: SwerveRequest.hpp:693
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:721
RobotCentric & WithCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation of the request.
Definition: SwerveRequest.hpp:819
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition: SwerveRequest.hpp:687
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition: SwerveRequest.hpp:702
RobotCentric & WithVelocityX(units::meters_per_second_t velocityX)
Sets the velocity in the X direction.
Definition: SwerveRequest.hpp:757
RobotCentric & WithDesaturateWheelSpeeds(bool desaturateWheelSpeeds)
Sets whether to desaturate wheel speeds before applying.
Definition: SwerveRequest.hpp:855
RobotCentric & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:842
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition: SwerveRequest.hpp:681
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition: SwerveRequest.hpp:707
RobotCentric & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:831
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition: SwerveRequest.hpp:698
RobotCentric & WithDeadband(units::meters_per_second_t deadband)
Sets the allowable deadband of the request.
Definition: SwerveRequest.hpp:797
RobotCentric & WithVelocityY(units::meters_per_second_t velocityY)
Sets the velocity in the Y direction.
Definition: SwerveRequest.hpp:771
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:716
RobotCentric & WithRotationalRate(units::radians_per_second_t rotationalRate)
The angular rate to rotate at.
Definition: SwerveRequest.hpp:785
RobotCentric & WithRotationalDeadband(units::radians_per_second_t rotationalDeadband)
Sets the rotational deadband of the request.
Definition: SwerveRequest.hpp:808
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:723
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:712
Sets the swerve drive module states to point inward on the robot in an "X" fashion,...
Definition: SwerveRequest.hpp:79
SwerveDriveBrake & WithSteerRequestType(impl::SwerveModuleImpl::SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:117
impl::SwerveModuleImpl::SteerRequestType SteerRequestType
The type of control request to use for the steer motor.
Definition: SwerveRequest.hpp:88
impl::SwerveModuleImpl::DriveRequestType DriveRequestType
The type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:84
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:90
SwerveDriveBrake & WithDriveRequestType(impl::SwerveModuleImpl::DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.
Definition: SwerveRequest.hpp:106
Container for all the Swerve Requests.
Definition: SwerveRequest.hpp:45
virtual ctre::phoenix::StatusCode Apply(ControlParameters const &parameters, std::vector< 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:999
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition: SwerveRequest.hpp:1004
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:1006
SysIdSwerveRotation & WithVolts(units::volt_t volts)
Update the voltage to apply to the drive wheels.
Definition: SwerveRequest.hpp:1021
SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.
Definition: SwerveRequest.hpp:1032
SysIdSwerveSteerGains & WithVolts(units::volt_t volts)
Update the voltage to apply to the drive wheels.
Definition: SwerveRequest.hpp:1053
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition: SwerveRequest.hpp:1037
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:1039
SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain...
Definition: SwerveRequest.hpp:967
SysIdSwerveTranslation & WithVolts(units::volt_t volts)
Sets the voltage to apply to drive wheels.
Definition: SwerveRequest.hpp:988
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
Applies this swerve request to the given modules.
Definition: SwerveRequest.hpp:974
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition: SwerveRequest.hpp:972
Status codes reported by APIs, including OK, warnings, and errors.
Definition: StatusCodes.h:27
static constexpr int OK
No Error.
Definition: StatusCodes.h:34
ForwardReferenceValue
The reference for "forward" is sometimes different if you're talking about field relative.
Definition: SwerveRequest.hpp:21
@ RedAlliance
This forward reference makes it so "forward" (positive X) is always towards the red alliance.
@ OperatorPerspective
This forward references makes it so "forward" (positive X) is determined from the operator's perspect...
Represents the state of one swerve module.
Definition: StatusCodes.h:18
Represents the speed of a robot chassis.
Definition: SwerveDriveKinematics.hpp:96
static ChassisSpeeds FromFieldRelativeSpeeds(ChassisSpeeds const &fieldRelativeSpeeds, Rotation2d const &robotAngle)
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds obje...
Definition: SwerveDriveKinematics.hpp:160
static ChassisSpeeds Discretize(ChassisSpeeds const &continuousSpeeds, units::second_t dt)
Disretizes a continuous-time chassis speed.
Definition: SwerveDriveKinematics.hpp:139
Contains everything the control requests need to calculate the module state.
Definition: SwerveDrivetrainImpl.hpp:124
units::second_t timestamp
Definition: SwerveDrivetrainImpl.hpp:132
Translation2d const * swervePositions
Definition: SwerveDrivetrainImpl.hpp:126
units::meters_per_second_t kMaxSpeed
Definition: SwerveDrivetrainImpl.hpp:127
units::second_t updatePeriod
Definition: SwerveDrivetrainImpl.hpp:133
impl::SwerveDriveKinematics * kinematics
Definition: SwerveDrivetrainImpl.hpp:125
Pose2d currentPose
Definition: SwerveDrivetrainImpl.hpp:131
Rotation2d operatorForwardDirection
Definition: SwerveDrivetrainImpl.hpp:129
Definition: SwerveDriveKinematics.hpp:23