WPILibC++ 2023.4.3-108-ge5452e3
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 <cmath>
6#include <functional>
7#include <initializer_list>
8#include <memory>
9#include <span>
10
11#include <frc/Timer.h>
15#include <frc/geometry/Pose2d.h>
20#include <units/length.h>
21#include <units/time.h>
22#include <units/voltage.h>
23
24#include "CommandBase.h"
25#include "CommandHelper.h"
26
27#pragma once
28
29namespace frc2 {
30
31/**
32 * A command that uses two PID controllers (PIDController) and a profiled PID
33 * controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a
34 * swerve drive.
35 *
36 * <p>The command handles trajectory-following, Velocity PID calculations, and
37 * feedforwards internally. This is intended to be a more-or-less "complete
38 * solution" that can be used by teams without a great deal of controls
39 * expertise.
40 *
41 * <p>Advanced teams seeking more flexibility (for example, those who wish to
42 * use the onboard PID functionality of a "smart" motor controller) may use the
43 * secondary constructor that omits the PID and feedforward functionality,
44 * returning only the raw module states from the position PID controllers.
45 *
46 * <p>The robot angle controller does not follow the angle given by
47 * the trajectory but rather goes to the angle given in the final state of the
48 * trajectory.
49 *
50 * This class is provided by the NewCommands VendorDep
51 */
52template <size_t NumModules>
54 : public CommandHelper<CommandBase, SwerveControllerCommand<NumModules>> {
55 using voltsecondspermeter =
56 units::compound_unit<units::voltage::volt, units::second,
58 using voltsecondssquaredpermeter =
61
62 public:
63 /**
64 * Constructs a new SwerveControllerCommand that when executed will follow the
65 * provided trajectory. This command will not return output voltages but
66 * rather raw module states from the position controllers which need to be put
67 * into a velocity PID.
68 *
69 * <p>Note: The controllers will *not* set the outputVolts to zero upon
70 * completion of the path- this is left to the user, since it is not
71 * appropriate for paths with nonstationary endstates.
72 *
73 * @param trajectory The trajectory to follow.
74 * @param pose A function that supplies the robot pose,
75 * provided by the odometry class.
76 * @param kinematics The kinematics for the robot drivetrain.
77 * @param xController The Trajectory Tracker PID controller
78 * for the robot's x position.
79 * @param yController The Trajectory Tracker PID controller
80 * for the robot's y position.
81 * @param thetaController The Trajectory Tracker PID controller
82 * for angle for the robot.
83 * @param desiredRotation The angle that the drivetrain should be
84 * facing. This is sampled at each time step.
85 * @param output The raw output module states from the
86 * position controllers.
87 * @param requirements The subsystems to require.
88 */
90 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
92 frc2::PIDController xController, frc2::PIDController yController,
94 std::function<frc::Rotation2d()> desiredRotation,
95 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
96 output,
97 std::initializer_list<Subsystem*> requirements);
98
99 /**
100 * Constructs a new SwerveControllerCommand that when executed will follow the
101 * provided trajectory. This command will not return output voltages but
102 * rather raw module states from the position controllers which need to be put
103 * into a velocity PID.
104 *
105 * <p>Note: The controllers will *not* set the outputVolts to zero upon
106 * completion of the path- this is left to the user, since it is not
107 * appropriate for paths with nonstationary endstates.
108 *
109 * <p>Note 2: The final rotation of the robot will be set to the rotation of
110 * the final pose in the trajectory. The robot will not follow the rotations
111 * from the poses at each timestep. If alternate rotation behavior is desired,
112 * the other constructor with a supplier for rotation should be used.
113 *
114 * @param trajectory The trajectory to follow.
115 * @param pose A function that supplies the robot pose,
116 * provided by the odometry class.
117 * @param kinematics The kinematics for the robot drivetrain.
118 * @param xController The Trajectory Tracker PID controller
119 * for the robot's x position.
120 * @param yController The Trajectory Tracker PID controller
121 * for the robot's y position.
122 * @param thetaController The Trajectory Tracker PID controller
123 * for angle for the robot.
124 * @param output The raw output module states from the
125 * position controllers.
126 * @param requirements The subsystems to require.
127 */
129 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
131 frc2::PIDController xController, frc2::PIDController yController,
133 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
134 output,
135 std::initializer_list<Subsystem*> requirements);
136
137 /**
138 * Constructs a new SwerveControllerCommand that when executed will follow the
139 * provided trajectory. This command will not return output voltages but
140 * rather raw module states from the position controllers which need to be put
141 * into a velocity PID.
142 *
143 * <p>Note: The controllers will *not* set the outputVolts to zero upon
144 * completion of the path- this is left to the user, since it is not
145 * appropriate for paths with nonstationary endstates.
146 *
147 *
148 * @param trajectory The trajectory to follow.
149 * @param pose A function that supplies the robot pose,
150 * provided by the odometry class.
151 * @param kinematics The kinematics for the robot drivetrain.
152 * @param xController The Trajectory Tracker PID controller
153 * for the robot's x position.
154 * @param yController The Trajectory Tracker PID controller
155 * for the robot's y position.
156 * @param thetaController The Trajectory Tracker PID controller
157 * for angle for the robot.
158 * @param desiredRotation The angle that the drivetrain should be
159 * facing. This is sampled at each time step.
160 * @param output The raw output module states from the
161 * position controllers.
162 * @param requirements The subsystems to require.
163 */
165 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
167 frc2::PIDController xController, frc2::PIDController yController,
169 std::function<frc::Rotation2d()> desiredRotation,
170 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
171 output,
172 std::span<Subsystem* const> requirements = {});
173
174 /**
175 * Constructs a new SwerveControllerCommand that when executed will follow the
176 * provided trajectory. This command will not return output voltages but
177 * rather raw module states from the position controllers which need to be put
178 * into a velocity PID.
179 *
180 * <p>Note: The controllers will *not* set the outputVolts to zero upon
181 * completion of the path- this is left to the user, since it is not
182 * appropriate for paths with nonstationary endstates.
183 *
184 * <p>Note 2: The final rotation of the robot will be set to the rotation of
185 * the final pose in the trajectory. The robot will not follow the rotations
186 * from the poses at each timestep. If alternate rotation behavior is desired,
187 * the other constructor with a supplier for rotation should be used.
188 *
189 * @param trajectory The trajectory to follow.
190 * @param pose A function that supplies the robot pose,
191 * provided by the odometry class.
192 * @param kinematics The kinematics for the robot drivetrain.
193 * @param xController The Trajectory Tracker PID controller
194 * for the robot's x position.
195 * @param yController The Trajectory Tracker PID controller
196 * for the robot's y position.
197 * @param thetaController The Trajectory Tracker PID controller
198 * for angle for the robot.
199 * @param output The raw output module states from the
200 * position controllers.
201 * @param requirements The subsystems to require.
202 */
204 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
206 frc2::PIDController xController, frc2::PIDController yController,
208 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
209 output,
210 std::span<Subsystem* const> requirements = {});
211
212 /**
213 * Constructs a new SwerveControllerCommand that when executed will follow the
214 * provided trajectory. This command will not return output voltages but
215 * rather raw module states from the position controllers which need to be put
216 * into a velocity PID.
217 *
218 * <p>Note: The controllers will *not* set the outputVolts to zero upon
219 * completion of the path- this is left to the user, since it is not
220 * appropriate for paths with nonstationary endstates.
221 *
222 * @param trajectory The trajectory to follow.
223 * @param pose A function that supplies the robot pose,
224 * provided by the odometry class.
225 * @param kinematics The kinematics for the robot drivetrain.
226 * @param controller The HolonomicDriveController for the drivetrain.
227 * @param desiredRotation The angle that the drivetrain should be
228 * facing. This is sampled at each time step.
229 * @param output The raw output module states from the
230 * position controllers.
231 * @param requirements The subsystems to require.
232 */
234 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
237 std::function<frc::Rotation2d()> desiredRotation,
238 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
239 output,
240 std::initializer_list<Subsystem*> requirements);
241
242 /**
243 * Constructs a new SwerveControllerCommand that when executed will follow the
244 * provided trajectory. This command will not return output voltages but
245 * rather raw module states from the position controllers which need to be put
246 * into a velocity PID.
247 *
248 * <p>Note: The controllers will *not* set the outputVolts to zero upon
249 * completion of the path- this is left to the user, since it is not
250 * appropriate for paths with nonstationary endstates.
251 *
252 * <p>Note 2: The final rotation of the robot will be set to the rotation of
253 * the final pose in the trajectory. The robot will not follow the rotations
254 * from the poses at each timestep. If alternate rotation behavior is desired,
255 * the other constructor with a supplier for rotation should be used.
256 *
257 * @param trajectory The trajectory to follow.
258 * @param pose A function that supplies the robot pose,
259 * provided by the odometry class.
260 * @param kinematics The kinematics for the robot drivetrain.
261 * @param controller The HolonomicDriveController for the drivetrain.
262 * @param output The raw output module states from the
263 * position controllers.
264 * @param requirements The subsystems to require.
265 */
267 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
270 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
271 output,
272 std::initializer_list<Subsystem*> requirements);
273
274 /**
275 * Constructs a new SwerveControllerCommand that when executed will follow the
276 * provided trajectory. This command will not return output voltages but
277 * rather raw module states from the position controllers which need to be put
278 * into a velocity PID.
279 *
280 * <p>Note: The controllers will *not* set the outputVolts to zero upon
281 * completion of the path- this is left to the user, since it is not
282 * appropriate for paths with nonstationary endstates.
283 *
284 *
285 * @param trajectory The trajectory to follow.
286 * @param pose A function that supplies the robot pose,
287 * provided by the odometry class.
288 * @param kinematics The kinematics for the robot drivetrain.
289 * @param controller The HolonomicDriveController for the robot.
290 * @param desiredRotation The angle that the drivetrain should be
291 * facing. This is sampled at each time step.
292 * @param output The raw output module states from the
293 * position controllers.
294 * @param requirements The subsystems to require.
295 */
297 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
300 std::function<frc::Rotation2d()> desiredRotation,
301 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
302 output,
303 std::span<Subsystem* const> requirements = {});
304
305 /**
306 * Constructs a new SwerveControllerCommand that when executed will follow the
307 * provided trajectory. This command will not return output voltages but
308 * rather raw module states from the position controllers which need to be put
309 * into a velocity PID.
310 *
311 * <p>Note: The controllers will *not* set the outputVolts to zero upon
312 * completion of the path- this is left to the user, since it is not
313 * appropriate for paths with nonstationary endstates.
314 *
315 * <p>Note 2: The final rotation of the robot will be set to the rotation of
316 * the final pose in the trajectory. The robot will not follow the rotations
317 * from the poses at each timestep. If alternate rotation behavior is desired,
318 * the other constructor with a supplier for rotation should be used.
319 *
320 * @param trajectory The trajectory to follow.
321 * @param pose A function that supplies the robot pose,
322 * provided by the odometry class.
323 * @param kinematics The kinematics for the robot drivetrain.
324 * @param controller The HolonomicDriveController for the drivetrain.
325 * @param output The raw output module states from the
326 * position controllers.
327 * @param requirements The subsystems to require.
328 */
330 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
333 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
334 output,
335 std::span<Subsystem* const> requirements = {});
336
337 void Initialize() override;
338
339 void Execute() override;
340
341 void End(bool interrupted) override;
342
343 bool IsFinished() override;
344
345 private:
346 frc::Trajectory m_trajectory;
347 std::function<frc::Pose2d()> m_pose;
350 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
351 m_outputStates;
352
353 std::function<frc::Rotation2d()> m_desiredRotation;
354
355 frc::Timer m_timer;
356 units::second_t m_prevTime;
357 frc::Rotation2d m_finalRotation;
358};
359} // namespace frc2
360
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:25
Implements a PID control loop.
Definition: PIDController.h:23
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: SwerveControllerCommand.h:54
void End(bool interrupted) override
Definition: SwerveControllerCommand.inc:170
void Execute() override
Definition: SwerveControllerCommand.inc:157
void Initialize() override
Definition: SwerveControllerCommand.inc:147
SwerveControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SwerveDriveKinematics< NumModules > kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, std::function< void(std::array< frc::SwerveModuleState, NumModules >)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new SwerveControllerCommand that when executed will follow the provided trajectory.
Definition: SwerveControllerCommand.inc:15
bool IsFinished() override
Definition: SwerveControllerCommand.inc:175
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
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:26
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:28
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1145
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1445
Definition: ProfiledPIDCommand.h:18
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13