WPILibC++ 2024.3.2
SwerveControllerCommand.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#include <functional>
6
7#include <frc/Timer.h>
11#include <frc/geometry/Pose2d.h>
16#include <units/length.h>
17#include <units/time.h>
18#include <units/voltage.h>
19
23
24#pragma once
25
26namespace frc2 {
27
28/**
29 * A command that uses two PID controllers (PIDController) and a profiled PID
30 * controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a
31 * swerve drive.
32 *
33 * <p>The command handles trajectory-following, Velocity PID calculations, and
34 * feedforwards internally. This is intended to be a more-or-less "complete
35 * solution" that can be used by teams without a great deal of controls
36 * expertise.
37 *
38 * <p>Advanced teams seeking more flexibility (for example, those who wish to
39 * use the onboard PID functionality of a "smart" motor controller) may use the
40 * secondary constructor that omits the PID and feedforward functionality,
41 * returning only the raw module states from the position PID controllers.
42 *
43 * <p>The robot angle controller does not follow the angle given by
44 * the trajectory but rather goes to the angle given in the final state of the
45 * trajectory.
46 *
47 * This class is provided by the NewCommands VendorDep
48 */
49template <size_t NumModules>
51 : public CommandHelper<Command, SwerveControllerCommand<NumModules>> {
52 using voltsecondspermeter =
53 units::compound_unit<units::voltage::volt, units::second,
55 using voltsecondssquaredpermeter =
58
59 public:
60 /**
61 * Constructs a new SwerveControllerCommand that when executed will follow the
62 * provided trajectory. This command will not return output voltages but
63 * rather raw module states from the position controllers which need to be put
64 * into a velocity PID.
65 *
66 * <p>Note: The controllers will *not* set the outputVolts to zero upon
67 * completion of the path- this is left to the user, since it is not
68 * appropriate for paths with nonstationary endstates.
69 *
70 * @param trajectory The trajectory to follow.
71 * @param pose A function that supplies the robot pose,
72 * provided by the odometry class.
73 * @param kinematics The kinematics for the robot drivetrain.
74 * @param xController The Trajectory Tracker PID controller
75 * for the robot's x position.
76 * @param yController The Trajectory Tracker PID controller
77 * for the robot's y position.
78 * @param thetaController The Trajectory Tracker PID controller
79 * for angle for the robot.
80 * @param desiredRotation The angle that the drivetrain should be
81 * facing. This is sampled at each time step.
82 * @param output The raw output module states from the
83 * position controllers.
84 * @param requirements The subsystems to require.
85 */
87 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
89 frc::PIDController xController, frc::PIDController yController,
91 std::function<frc::Rotation2d()> desiredRotation,
92 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
93 output,
94 Requirements requirements = {});
95
96 /**
97 * Constructs a new SwerveControllerCommand that when executed will follow the
98 * provided trajectory. This command will not return output voltages but
99 * rather raw module states from the position controllers which need to be put
100 * into a velocity PID.
101 *
102 * <p>Note: The controllers will *not* set the outputVolts to zero upon
103 * completion of the path- this is left to the user, since it is not
104 * appropriate for paths with nonstationary endstates.
105 *
106 * <p>Note 2: The final rotation of the robot will be set to the rotation of
107 * the final pose in the trajectory. The robot will not follow the rotations
108 * from the poses at each timestep. If alternate rotation behavior is desired,
109 * the other constructor with a supplier for rotation should be used.
110 *
111 * @param trajectory The trajectory to follow.
112 * @param pose A function that supplies the robot pose,
113 * provided by the odometry class.
114 * @param kinematics The kinematics for the robot drivetrain.
115 * @param xController The Trajectory Tracker PID controller
116 * for the robot's x position.
117 * @param yController The Trajectory Tracker PID controller
118 * for the robot's y position.
119 * @param thetaController The Trajectory Tracker PID controller
120 * for angle for the robot.
121 * @param output The raw output module states from the
122 * position controllers.
123 * @param requirements The subsystems to require.
124 */
126 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
128 frc::PIDController xController, frc::PIDController yController,
130 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
131 output,
132 Requirements requirements = {});
133
134 /**
135 * Constructs a new SwerveControllerCommand that when executed will follow the
136 * provided trajectory. This command will not return output voltages but
137 * rather raw module states from the position controllers which need to be put
138 * into a velocity PID.
139 *
140 * <p>Note: The controllers will *not* set the outputVolts to zero upon
141 * completion of the path- this is left to the user, since it is not
142 * appropriate for paths with nonstationary endstates.
143 *
144 * @param trajectory The trajectory to follow.
145 * @param pose A function that supplies the robot pose,
146 * provided by the odometry class.
147 * @param kinematics The kinematics for the robot drivetrain.
148 * @param controller The HolonomicDriveController for the drivetrain.
149 * @param desiredRotation The angle that the drivetrain should be
150 * facing. This is sampled at each time step.
151 * @param output The raw output module states from the
152 * position controllers.
153 * @param requirements The subsystems to require.
154 */
156 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
159 std::function<frc::Rotation2d()> desiredRotation,
160 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
161 output,
162 Requirements requirements = {});
163
164 /**
165 * Constructs a new SwerveControllerCommand that when executed will follow the
166 * provided trajectory. This command will not return output voltages but
167 * rather raw module states from the position controllers which need to be put
168 * into a velocity PID.
169 *
170 * <p>Note: The controllers will *not* set the outputVolts to zero upon
171 * completion of the path- this is left to the user, since it is not
172 * appropriate for paths with nonstationary endstates.
173 *
174 * <p>Note 2: The final rotation of the robot will be set to the rotation of
175 * the final pose in the trajectory. The robot will not follow the rotations
176 * from the poses at each timestep. If alternate rotation behavior is desired,
177 * the other constructor with a supplier for rotation should be used.
178 *
179 * @param trajectory The trajectory to follow.
180 * @param pose A function that supplies the robot pose,
181 * provided by the odometry class.
182 * @param kinematics The kinematics for the robot drivetrain.
183 * @param controller The HolonomicDriveController for the drivetrain.
184 * @param output The raw output module states from the
185 * position controllers.
186 * @param requirements The subsystems to require.
187 */
189 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
192 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
193 output,
194 Requirements requirements = {});
195
196 void Initialize() override;
197
198 void Execute() override;
199
200 void End(bool interrupted) override;
201
202 bool IsFinished() override;
203
204 private:
205 frc::Trajectory m_trajectory;
206 std::function<frc::Pose2d()> m_pose;
209 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
210 m_outputStates;
211
212 std::function<frc::Rotation2d()> m_desiredRotation;
213
214 frc::Timer m_timer;
215 units::second_t m_prevTime;
216 frc::Rotation2d m_finalRotation;
217};
218} // namespace frc2
219
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:27
Represents requirements for a command, which is a set of (pointers to) subsystems.
Definition: Requirements.h:20
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: SwerveControllerCommand.h:51
SwerveControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc::PIDController xController, frc::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, Requirements requirements={})
Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.
Definition: SwerveControllerCommand.inc:16
void End(bool interrupted) override
Definition: SwerveControllerCommand.inc:105
void Execute() override
Definition: SwerveControllerCommand.inc:92
void Initialize() override
Definition: SwerveControllerCommand.inc:82
bool IsFinished() override
Definition: SwerveControllerCommand.inc:110
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Implements a PID control loop.
Definition: PIDController.h:23
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
Definition: ProfiledPIDController.h:35
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual module ...
Definition: SwerveDriveKinematics.h:56
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:25
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1134
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1434
Definition: TrapezoidProfileSubsystem.h:12
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13