114 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
115 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, parameters.moduleLocations[i].Angle()}));
131 this->DriveRequestType = std::move(newDriveRequestType);
144 this->DriveRequestType = std::move(newDriveRequestType);
145 return std::move(*
this);
158 this->SteerRequestType = std::move(newSteerRequestType);
171 this->SteerRequestType = std::move(newSteerRequestType);
172 return std::move(*
this);
249 Translation2d tmp{toApplyX * 1_s, toApplyY * 1_s};
251 toApplyX = tmp.X() / 1_s;
252 toApplyY = tmp.Y() / 1_s;
255 if (units::math::hypot(toApplyX, toApplyY) <
Deadband) {
260 toApplyOmega = 0_rad_per_s;
263 auto const speeds = ChassisSpeeds::Discretize(
264 ChassisSpeeds::FromFieldRelativeSpeeds(
265 {toApplyX, toApplyY, toApplyOmega}, parameters.
currentPose.Rotation()
279 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
280 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
297 this->VelocityX = std::move(newVelocityX);
311 this->VelocityX = std::move(newVelocityX);
312 return std::move(*
this);
327 this->VelocityY = std::move(newVelocityY);
342 this->VelocityY = std::move(newVelocityY);
343 return std::move(*
this);
357 this->RotationalRate = std::move(newRotationalRate);
371 this->RotationalRate = std::move(newRotationalRate);
372 return std::move(*
this);
385 this->Deadband = std::move(newDeadband);
398 this->Deadband = std::move(newDeadband);
399 return std::move(*
this);
412 this->RotationalDeadband = std::move(newRotationalDeadband);
425 this->RotationalDeadband = std::move(newRotationalDeadband);
426 return std::move(*
this);
455 return std::move(*
this);
468 this->DriveRequestType = std::move(newDriveRequestType);
481 this->DriveRequestType = std::move(newDriveRequestType);
482 return std::move(*
this);
495 this->SteerRequestType = std::move(newSteerRequestType);
508 this->SteerRequestType = std::move(newSteerRequestType);
509 return std::move(*
this);
523 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
537 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
538 return std::move(*
this);
551 this->ForwardPerspective = std::move(newForwardPerspective);
564 this->ForwardPerspective = std::move(newForwardPerspective);
565 return std::move(*
this);
635 if (units::math::hypot(toApplyX, toApplyY) <
Deadband) {
640 toApplyOmega = 0_rad_per_s;
642 ChassisSpeeds
const speeds{toApplyX, toApplyY, toApplyOmega};
653 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
654 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
671 this->VelocityX = std::move(newVelocityX);
685 this->VelocityX = std::move(newVelocityX);
686 return std::move(*
this);
701 this->VelocityY = std::move(newVelocityY);
716 this->VelocityY = std::move(newVelocityY);
717 return std::move(*
this);
731 this->RotationalRate = std::move(newRotationalRate);
745 this->RotationalRate = std::move(newRotationalRate);
746 return std::move(*
this);
759 this->Deadband = std::move(newDeadband);
772 this->Deadband = std::move(newDeadband);
773 return std::move(*
this);
786 this->RotationalDeadband = std::move(newRotationalDeadband);
799 this->RotationalDeadband = std::move(newRotationalDeadband);
800 return std::move(*
this);
829 return std::move(*
this);
842 this->DriveRequestType = std::move(newDriveRequestType);
855 this->DriveRequestType = std::move(newDriveRequestType);
856 return std::move(*
this);
869 this->SteerRequestType = std::move(newSteerRequestType);
882 this->SteerRequestType = std::move(newSteerRequestType);
883 return std::move(*
this);
897 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
911 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
912 return std::move(*
this);
941 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
942 modulesToApply[i]->Apply(moduleRequest.WithState({0_mps, ModuleDirection}));
974 return std::move(*
this);
987 this->DriveRequestType = std::move(newDriveRequestType);
1000 this->DriveRequestType = std::move(newDriveRequestType);
1001 return std::move(*
this);
1014 this->SteerRequestType = std::move(newSteerRequestType);
1027 this->SteerRequestType = std::move(newSteerRequestType);
1028 return std::move(*
this);
1098 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
1103 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1120 this->
Speeds = std::move(newSpeeds);
1133 this->
Speeds = std::move(newSpeeds);
1134 return std::move(*
this);
1154 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1174 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1175 return std::move(*
this);
1195 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1215 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1216 return std::move(*
this);
1245 return std::move(*
this);
1258 this->DriveRequestType = std::move(newDriveRequestType);
1271 this->DriveRequestType = std::move(newDriveRequestType);
1272 return std::move(*
this);
1285 this->SteerRequestType = std::move(newSteerRequestType);
1298 this->SteerRequestType = std::move(newSteerRequestType);
1299 return std::move(*
this);
1313 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1327 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1328 return std::move(*
this);
1390 auto fieldSpeeds =
Speeds;
1395 fieldSpeeds.vx = tmp.X() / 1_s;
1396 fieldSpeeds.vy = tmp.Y() / 1_s;
1399 auto const robotSpeeds = ChassisSpeeds::Discretize(
1400 ChassisSpeeds::FromFieldRelativeSpeeds(
1416 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
1421 Translation2d tmp{wheelForceFeedforwardX * 1_m/1_N, wheelForceFeedforwardY * 1_m/1_N};
1427 tmp = tmp.RotateBy(-parameters.
currentPose.Rotation());
1429 wheelForceFeedforwardX = tmp.X() * 1_N/1_m;
1430 wheelForceFeedforwardY = tmp.Y() * 1_N/1_m;
1432 moduleRequest.WithWheelForceFeedforwardX(wheelForceFeedforwardX)
1433 .WithWheelForceFeedforwardY(wheelForceFeedforwardY);
1436 modulesToApply[i]->Apply(moduleRequest.WithState(states[i]));
1452 this->
Speeds = std::move(newSpeeds);
1465 this->
Speeds = std::move(newSpeeds);
1466 return std::move(*
this);
1486 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1506 this->WheelForceFeedforwardsX = std::move(newWheelForceFeedforwardsX);
1507 return std::move(*
this);
1527 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1547 this->WheelForceFeedforwardsY = std::move(newWheelForceFeedforwardsY);
1548 return std::move(*
this);
1577 return std::move(*
this);
1590 this->DriveRequestType = std::move(newDriveRequestType);
1603 this->DriveRequestType = std::move(newDriveRequestType);
1604 return std::move(*
this);
1617 this->SteerRequestType = std::move(newSteerRequestType);
1630 this->SteerRequestType = std::move(newSteerRequestType);
1631 return std::move(*
this);
1645 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1659 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
1660 return std::move(*
this);
1673 this->ForwardPerspective = std::move(newForwardPerspective);
1686 this->ForwardPerspective = std::move(newForwardPerspective);
1687 return std::move(*
this);
1807 parameters.
currentPose.Rotation().Radians().value(),
1808 angleToFace.Radians().value(),
1830 .
Apply(parameters, modulesToApply);
1865 this->VelocityX = std::move(newVelocityX);
1881 this->VelocityY = std::move(newVelocityY);
1914 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
1928 this->Deadband = std::move(newDeadband);
1942 this->RotationalDeadband = std::move(newRotationalDeadband);
1957 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
1986 this->DriveRequestType = std::move(newDriveRequestType);
2000 this->SteerRequestType = std::move(newSteerRequestType);
2015 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
2029 this->ForwardPerspective = std::move(newForwardPerspective);
2045 this->TargetDirectionPerspective = std::move(newTargetDirectionPerspective);
2159 parameters.
currentPose.Rotation().Radians().value(),
2160 angleToFace.Radians().value(),
2181 .
Apply(parameters, modulesToApply);
2216 this->VelocityX = std::move(newVelocityX);
2232 this->VelocityY = std::move(newVelocityY);
2265 this->TargetRateFeedforward = std::move(newTargetRateFeedforward);
2279 this->Deadband = std::move(newDeadband);
2293 this->RotationalDeadband = std::move(newRotationalDeadband);
2308 this->MaxAbsRotationalRate = std::move(newMaxAbsRotationalRate);
2337 this->DriveRequestType = std::move(newDriveRequestType);
2351 this->SteerRequestType = std::move(newSteerRequestType);
2366 this->DesaturateWheelSpeeds = std::move(newDesaturateWheelSpeeds);
2381 this->ForwardPerspective = std::move(newForwardPerspective);
2399 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
2400 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2402 modulesToApply[i]->Apply(
2408 modulesToApply[i]->Apply(
2426 this->VoltsToApply = volts;
2437 this->VoltsToApply = volts;
2438 return std::move(*
this);
2466 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
2468 auto const driveVoltage = speed / parameters.
kMaxSpeed * 12_V;
2470 auto const angle = parameters.
moduleLocations[i].Angle() + Rotation2d{90_deg};
2472 switch (modulesToApply[i]->GetSteerClosedLoopOutputType()) {
2474 modulesToApply[i]->Apply(
2480 modulesToApply[i]->Apply(
2498 this->RotationalRate = rotationalRate;
2509 this->RotationalRate = rotationalRate;
2510 return std::move(*
this);
2527 for (
size_t i = 0; i < modulesToApply.size(); ++i) {
2541 this->VoltsToApply = volts;
2552 this->VoltsToApply = volts;
2553 return std::move(*
this);
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 ¢erOfRotation=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:1337
ApplyFieldSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1545
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1381
ApplyFieldSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1504
ApplyFieldSpeeds && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1684
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1386
ApplyFieldSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1588
ApplyFieldSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1574
ApplyFieldSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1525
ApplyFieldSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1643
ChassisSpeeds Speeds
The field-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1342
ApplyFieldSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1615
ApplyFieldSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1484
ApplyFieldSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1628
std::vector< units::newton_t > WheelForceFeedforwardsX
Field-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1353
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1388
ApplyFieldSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1657
ApplyFieldSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1450
std::vector< units::newton_t > WheelForceFeedforwardsY
Field-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1364
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1368
ApplyFieldSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1463
ApplyFieldSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1560
ApplyFieldSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1601
ApplyFieldSpeeds & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:1671
Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1040
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1087
ApplyRobotSpeeds && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1296
ChassisSpeeds Speeds
The robot-centric chassis speeds to apply to the drivetrain.
Definition SwerveRequest.hpp:1046
std::vector< units::newton_t > WheelForceFeedforwardsY
Robot-centric wheel force feedforwards to apply in the Y direction.
Definition SwerveRequest.hpp:1068
std::vector< units::newton_t > WheelForceFeedforwardsX
Robot-centric wheel force feedforwards to apply in the X direction.
Definition SwerveRequest.hpp:1057
ApplyRobotSpeeds && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1242
ApplyRobotSpeeds & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1256
ApplyRobotSpeeds & WithSpeeds(ChassisSpeeds newSpeeds) &
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1118
ApplyRobotSpeeds & WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1152
ApplyRobotSpeeds && WithSpeeds(ChassisSpeeds newSpeeds) &&
Modifies the Speeds parameter and returns itself.
Definition SwerveRequest.hpp:1131
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1085
ApplyRobotSpeeds & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1283
ApplyRobotSpeeds & WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1193
ApplyRobotSpeeds & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1228
ApplyRobotSpeeds && WithWheelForceFeedforwardsY(std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Definition SwerveRequest.hpp:1213
ApplyRobotSpeeds && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1269
Translation2d CenterOfRotation
The center of rotation to rotate around.
Definition SwerveRequest.hpp:1072
ApplyRobotSpeeds && WithWheelForceFeedforwardsX(std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Definition SwerveRequest.hpp:1172
ApplyRobotSpeeds && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1325
ApplyRobotSpeeds & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:1311
Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:1706
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:1765
TargetDirectionPerspectiveValue TargetDirectionPerspective
The perspective to use when determining which direction is forward for the TargetDirection.
Definition SwerveRequest.hpp:1776
FieldCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:1940
FieldCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:1955
FieldCentricFacingAngle & WithTargetDirectionPerspective(TargetDirectionPerspectiveValue newTargetDirectionPerspective)
Modifies the TargetDirectionPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2043
FieldCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1998
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:1725
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:1746
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:1712
FieldCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2027
FieldCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1895
FieldCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:2013
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:1787
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:1732
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:1751
FieldCentricFacingAngle()
Definition SwerveRequest.hpp:1789
FieldCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1879
FieldCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:1863
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:1737
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:1718
FieldCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:1926
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:1741
FieldCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1984
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:1794
FieldCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:1912
FieldCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:1970
FieldCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:1848
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:1770
Drives the swerve drivetrain in a field-centric manner.
Definition SwerveRequest.hpp:189
FieldCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:369
FieldCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:452
FieldCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:423
FieldCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:438
FieldCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:340
FieldCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:506
FieldCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:410
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:211
FieldCentric & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:549
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:207
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:201
FieldCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:493
FieldCentric && WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective) &&
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:562
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:241
FieldCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:396
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:195
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:220
FieldCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:309
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:234
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward.
Definition SwerveRequest.hpp:239
FieldCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:535
FieldCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:383
FieldCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:355
FieldCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:325
FieldCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:466
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:215
FieldCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:295
FieldCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:479
FieldCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:521
Does nothing to the swerve module state.
Definition SwerveRequest.hpp:84
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:86
Sets the swerve drive modules to point to a specified direction.
Definition SwerveRequest.hpp:919
PointWheelsAt && WithModuleDirection(Rotation2d newModuleDirection) &&
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:971
PointWheelsAt && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:998
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:935
PointWheelsAt && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1025
PointWheelsAt & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:985
PointWheelsAt & WithModuleDirection(Rotation2d newModuleDirection) &
Modifies the ModuleDirection parameter and returns itself.
Definition SwerveRequest.hpp:957
Rotation2d ModuleDirection
The direction to point the modules toward.
Definition SwerveRequest.hpp:925
PointWheelsAt & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:1012
Drives the swerve drivetrain in a robot-centric manner, maintaining a specified heading angle to ensu...
Definition SwerveRequest.hpp:2066
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2149
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:2092
ForwardPerspectiveValue ForwardPerspective
The perspective to use when determining which direction is forward for the target heading.
Definition SwerveRequest.hpp:2131
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:2097
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:2078
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:2125
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:2111
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:2101
RobotCentricFacingAngle & WithMaxAbsRotationalRate(units::radians_per_second_t newMaxAbsRotationalRate)
Modifies the MaxAbsRotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:2306
RobotCentricFacingAngle & WithTargetRateFeedforward(units::radians_per_second_t newTargetRateFeedforward)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2263
RobotCentricFacingAngle & WithSteerRequestType(impl::SteerRequestType newSteerRequestType)
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2349
RobotCentricFacingAngle & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband)
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:2291
RobotCentricFacingAngle & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds)
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:2364
RobotCentricFacingAngle & WithForwardPerspective(ForwardPerspectiveValue newForwardPerspective)
Modifies the ForwardPerspective parameter and returns itself.
Definition SwerveRequest.hpp:2379
RobotCentricFacingAngle & WithVelocityY(units::meters_per_second_t newVelocityY)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2230
RobotCentricFacingAngle()
Definition SwerveRequest.hpp:2144
RobotCentricFacingAngle & WithDeadband(units::meters_per_second_t newDeadband)
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:2277
RobotCentricFacingAngle & WithHeadingPID(double kP, double kI, double kD)
Modifies the PID gains of the HeadingController parameter and returns itself.
Definition SwerveRequest.hpp:2199
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:2072
PhoenixPIDController HeadingController
The PID controller used to maintain the desired heading.
Definition SwerveRequest.hpp:2142
RobotCentricFacingAngle & WithCenterOfRotation(Translation2d newCenterOfRotation)
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:2321
RobotCentricFacingAngle & WithTargetDirection(Rotation2d newTargetDirection)
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:2246
Rotation2d TargetDirection
The desired direction to face.
Definition SwerveRequest.hpp:2085
units::radians_per_second_t MaxAbsRotationalRate
The maximum absolute rotational rate to allow.
Definition SwerveRequest.hpp:2106
RobotCentricFacingAngle & WithDriveRequestType(impl::DriveRequestType newDriveRequestType)
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:2335
RobotCentricFacingAngle & WithVelocityX(units::meters_per_second_t newVelocityX)
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:2214
Drives the swerve drivetrain in a robot-centric manner.
Definition SwerveRequest.hpp:582
units::radians_per_second_t RotationalRate
The angular rate to rotate at.
Definition SwerveRequest.hpp:600
RobotCentric & WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:784
RobotCentric & WithCenterOfRotation(Translation2d newCenterOfRotation) &
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:812
bool DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying.
Definition SwerveRequest.hpp:628
RobotCentric && WithDeadband(units::meters_per_second_t newDeadband) &&
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:770
units::meters_per_second_t VelocityY
The velocity in the Y direction.
Definition SwerveRequest.hpp:594
RobotCentric && WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &&
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:909
RobotCentric && WithRotationalDeadband(units::radians_per_second_t newRotationalDeadband) &&
Modifies the RotationalDeadband parameter and returns itself.
Definition SwerveRequest.hpp:797
RobotCentric && WithRotationalRate(units::radians_per_second_t newRotationalRate) &&
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:743
units::radians_per_second_t RotationalDeadband
The rotational deadband of the request.
Definition SwerveRequest.hpp:609
RobotCentric && WithVelocityX(units::meters_per_second_t newVelocityX) &&
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:683
RobotCentric & WithDeadband(units::meters_per_second_t newDeadband) &
Modifies the Deadband parameter and returns itself.
Definition SwerveRequest.hpp:757
units::meters_per_second_t VelocityX
The velocity in the X direction.
Definition SwerveRequest.hpp:588
RobotCentric & WithRotationalRate(units::radians_per_second_t newRotationalRate) &
Modifies the RotationalRate parameter and returns itself.
Definition SwerveRequest.hpp:729
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:630
RobotCentric && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:880
Translation2d CenterOfRotation
The center of rotation the robot should rotate around.
Definition SwerveRequest.hpp:614
RobotCentric && WithCenterOfRotation(Translation2d newCenterOfRotation) &&
Modifies the CenterOfRotation parameter and returns itself.
Definition SwerveRequest.hpp:826
RobotCentric && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:853
units::meters_per_second_t Deadband
The allowable deadband of the request.
Definition SwerveRequest.hpp:605
RobotCentric & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:840
RobotCentric & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:867
RobotCentric & WithVelocityX(units::meters_per_second_t newVelocityX) &
Modifies the VelocityX parameter and returns itself.
Definition SwerveRequest.hpp:669
RobotCentric & WithVelocityY(units::meters_per_second_t newVelocityY) &
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:699
RobotCentric && WithVelocityY(units::meters_per_second_t newVelocityY) &&
Modifies the VelocityY parameter and returns itself.
Definition SwerveRequest.hpp:714
RobotCentric & WithDesaturateWheelSpeeds(bool newDesaturateWheelSpeeds) &
Modifies the DesaturateWheelSpeeds parameter and returns itself.
Definition SwerveRequest.hpp:895
Sets the swerve drive module states to point inward on the robot in an "X" fashion,...
Definition SwerveRequest.hpp:97
SwerveDriveBrake & WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:129
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:108
SwerveDriveBrake && WithDriveRequestType(impl::DriveRequestType newDriveRequestType) &&
Modifies the DriveRequestType parameter and returns itself.
Definition SwerveRequest.hpp:142
SwerveDriveBrake && WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &&
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:169
SwerveDriveBrake & WithSteerRequestType(impl::SteerRequestType newSteerRequestType) &
Modifies the SteerRequestType parameter and returns itself.
Definition SwerveRequest.hpp:156
Container for all the Swerve Requests.
Definition SwerveRequest.hpp:63
virtual ~SwerveRequest()=default
virtual ctre::phoenix::StatusCode Apply(ControlParameters const ¶meters, 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:2457
units::radians_per_second_t RotationalRate
The angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2462
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2464
SysIdSwerveRotation && WithRotationalRate(units::radians_per_second_t rotationalRate) &&
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2507
SysIdSwerveRotation & WithRotationalRate(units::radians_per_second_t rotationalRate) &
Update the angular rate to rotate at, in radians per second.
Definition SwerveRequest.hpp:2496
SysId-specific SwerveRequest to characterize the steer module characteristics of a swerve drivetrain.
Definition SwerveRequest.hpp:2518
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2525
SysIdSwerveSteerGains && WithVolts(units::volt_t volts) &&
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2550
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2523
SysIdSwerveSteerGains & WithVolts(units::volt_t volts) &
Update the voltage to apply to the drive wheels.
Definition SwerveRequest.hpp:2539
SysId-specific SwerveRequest to characterize the translational characteristics of a swerve drivetrain...
Definition SwerveRequest.hpp:2390
SysIdSwerveTranslation & WithVolts(units::volt_t volts) &
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2424
SysIdSwerveTranslation && WithVolts(units::volt_t volts) &&
Sets the voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2435
units::volt_t VoltsToApply
Voltage to apply to drive wheels.
Definition SwerveRequest.hpp:2395
ctre::phoenix::StatusCode Apply(SwerveRequest::ControlParameters const ¶meters, std::span< std::unique_ptr< impl::SwerveModuleImpl > const > modulesToApply) override
Applies this swerve request to the given modules.
Definition SwerveRequest.hpp:2397
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.
TargetDirectionPerspectiveValue
In field-centric control, the direction of "forward" for the target direction sometimes differs from ...
Definition SwerveRequest.hpp:43
@ UseForwardPerspective
Match the ForwardPerspective parameter for heading control.
@ TorqueCurrentFOC
Requires Pro.
Definition motor_constants.h:14
Contains everything the control requests need to calculate the module state.
Definition SwerveDrivetrainImpl.hpp:142
units::second_t timestamp
The timestamp of the current control apply, in the timebase of utils::GetCurrentTime()
Definition SwerveDrivetrainImpl.hpp:157
units::meters_per_second_t kMaxSpeed
The max speed of the robot at 12 V output.
Definition SwerveDrivetrainImpl.hpp:148
units::second_t updatePeriod
The update period of control apply.
Definition SwerveDrivetrainImpl.hpp:159
impl::SwerveDriveKinematics * kinematics
The kinematics object used for control.
Definition SwerveDrivetrainImpl.hpp:144
Pose2d currentPose
The current pose of the robot.
Definition SwerveDrivetrainImpl.hpp:155
Rotation2d operatorForwardDirection
The forward direction from the operator perspective.
Definition SwerveDrivetrainImpl.hpp:151
Translation2d const * moduleLocations
The locations of the swerve modules.
Definition SwerveDrivetrainImpl.hpp:146
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