WPILibC++ 2023.4.3
MecanumControllerCommand.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>
16#include <frc/geometry/Pose2d.h>
21#include <units/angle.h>
22#include <units/length.h>
23#include <units/velocity.h>
24#include <units/voltage.h>
25
26#include "CommandBase.h"
27#include "CommandHelper.h"
28
29#pragma once
30
31namespace frc2 {
32/**
33 * A command that uses two PID controllers (PIDController) and a profiled PID
34 * controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a
35 * mecanum drive.
36 *
37 * <p>The command handles trajectory-following,
38 * Velocity PID calculations, and feedforwards internally. This
39 * is intended to be a more-or-less "complete solution" that can be used by
40 * teams without a great deal of controls expertise.
41 *
42 * <p>Advanced teams seeking more flexibility (for example, those who wish to
43 * use the onboard PID functionality of a "smart" motor controller) may use the
44 * secondary constructor that omits the PID and feedforward functionality,
45 * returning only the raw wheel speeds from the PID controllers.
46 *
47 * <p>The robot angle controller does not follow the angle given by
48 * the trajectory but rather goes to the angle given in the final state of the
49 * trajectory.
50 *
51 * This class is provided by the NewCommands VendorDep
52 */
54 : public CommandHelper<CommandBase, MecanumControllerCommand> {
55 public:
56 /**
57 * Constructs a new MecanumControllerCommand that when executed will follow
58 * the provided trajectory. PID control and feedforward are handled
59 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
60 * motor.
61 *
62 * <p>Note: The controllers will *not* set the outputVolts to zero upon
63 * completion of the path this is left to the user, since it is not
64 * appropriate for paths with nonstationary endstates.
65 *
66 * @param trajectory The trajectory to follow.
67 * @param pose A function that supplies the robot pose,
68 * provided by the odometry class.
69 * @param feedforward The feedforward to use for the drivetrain.
70 * @param kinematics The kinematics for the robot drivetrain.
71 * @param xController The Trajectory Tracker PID controller
72 * for the robot's x position.
73 * @param yController The Trajectory Tracker PID controller
74 * for the robot's y position.
75 * @param thetaController The Trajectory Tracker PID controller
76 * for angle for the robot.
77 * @param desiredRotation The angle that the robot should be facing.
78 * This is sampled at each time step.
79 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
80 * @param frontLeftController The front left wheel velocity PID.
81 * @param rearLeftController The rear left wheel velocity PID.
82 * @param frontRightController The front right wheel velocity PID.
83 * @param rearRightController The rear right wheel velocity PID.
84 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
85 * the current wheel speeds.
86 * @param output The output of the velocity PIDs.
87 * @param requirements The subsystems to require.
88 */
90 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
93 frc2::PIDController yController,
95 std::function<frc::Rotation2d()> desiredRotation,
96 units::meters_per_second_t maxWheelVelocity,
97 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
98 frc2::PIDController frontLeftController,
99 frc2::PIDController rearLeftController,
100 frc2::PIDController frontRightController,
101 frc2::PIDController rearRightController,
102 std::function<void(units::volt_t, units::volt_t, units::volt_t,
103 units::volt_t)>
104 output,
105 std::initializer_list<Subsystem*> requirements);
106
107 /**
108 * Constructs a new MecanumControllerCommand that when executed will follow
109 * the provided trajectory. PID control and feedforward are handled
110 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
111 * motor.
112 *
113 * <p>Note: The controllers will *not* set the outputVolts to zero upon
114 * completion of the path this is left to the user, since it is not
115 * appropriate for paths with nonstationary endstates.
116 *
117 * <p>Note 2: The final rotation of the robot will be set to the rotation of
118 * the final pose in the trajectory. The robot will not follow the rotations
119 * from the poses at each timestep. If alternate rotation behavior is desired,
120 * the other constructor with a supplier for rotation should be used.
121 *
122 * @param trajectory The trajectory to follow.
123 * @param pose A function that supplies the robot pose,
124 * provided by the odometry class.
125 * @param feedforward The feedforward to use for the drivetrain.
126 * @param kinematics The kinematics for the robot drivetrain.
127 * @param xController The Trajectory Tracker PID controller
128 * for the robot's x position.
129 * @param yController The Trajectory Tracker PID controller
130 * for the robot's y position.
131 * @param thetaController The Trajectory Tracker PID controller
132 * for angle for the robot.
133 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
134 * @param frontLeftController The front left wheel velocity PID.
135 * @param rearLeftController The rear left wheel velocity PID.
136 * @param frontRightController The front right wheel velocity PID.
137 * @param rearRightController The rear right wheel velocity PID.
138 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
139 * the current wheel speeds.
140 * @param output The output of the velocity PIDs.
141 * @param requirements The subsystems to require.
142 */
144 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
146 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
147 frc2::PIDController yController,
149 units::meters_per_second_t maxWheelVelocity,
150 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
151 frc2::PIDController frontLeftController,
152 frc2::PIDController rearLeftController,
153 frc2::PIDController frontRightController,
154 frc2::PIDController rearRightController,
155 std::function<void(units::volt_t, units::volt_t, units::volt_t,
156 units::volt_t)>
157 output,
158 std::initializer_list<Subsystem*> requirements);
159
160 /**
161 * Constructs a new MecanumControllerCommand that when executed will follow
162 * the provided trajectory. PID control and feedforward are handled
163 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
164 * motor.
165 *
166 * <p>Note: The controllers will *not* set the outputVolts to zero upon
167 * completion of the path this is left to the user, since it is not
168 * appropriate for paths with nonstationary endstates.
169 *
170 * @param trajectory The trajectory to follow.
171 * @param pose A function that supplies the robot pose,
172 * provided by the odometry class.
173 * @param feedforward The feedforward to use for the drivetrain.
174 * @param kinematics The kinematics for the robot drivetrain.
175 * @param xController The Trajectory Tracker PID controller
176 * for the robot's x position.
177 * @param yController The Trajectory Tracker PID controller
178 * for the robot's y position.
179 * @param thetaController The Trajectory Tracker PID controller
180 * for angle for the robot.
181 * @param desiredRotation The angle that the robot should be facing.
182 * This is sampled at each time step.
183 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
184 * @param frontLeftController The front left wheel velocity PID.
185 * @param rearLeftController The rear left wheel velocity PID.
186 * @param frontRightController The front right wheel velocity PID.
187 * @param rearRightController The rear right wheel velocity PID.
188 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
189 * the current wheel speeds.
190 * @param output The output of the velocity PIDs.
191 * @param requirements The subsystems to require.
192 */
194 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
196 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
197 frc2::PIDController yController,
199 std::function<frc::Rotation2d()> desiredRotation,
200 units::meters_per_second_t maxWheelVelocity,
201 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
202 frc2::PIDController frontLeftController,
203 frc2::PIDController rearLeftController,
204 frc2::PIDController frontRightController,
205 frc2::PIDController rearRightController,
206 std::function<void(units::volt_t, units::volt_t, units::volt_t,
207 units::volt_t)>
208 output,
209 std::span<Subsystem* const> requirements = {});
210
211 /**
212 * Constructs a new MecanumControllerCommand that when executed will follow
213 * the provided trajectory. PID control and feedforward are handled
214 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
215 * motor.
216 *
217 * <p>Note: The controllers will *not* set the outputVolts to zero upon
218 * completion of the path this is left to the user, since it is not
219 * appropriate for paths with nonstationary endstates.
220 *
221 * <p>Note 2: The final rotation of the robot will be set to the rotation of
222 * the final pose in the trajectory. The robot will not follow the rotations
223 * from the poses at each timestep. If alternate rotation behavior is desired,
224 * the other constructor with a supplier for rotation should be used.
225 *
226 * @param trajectory The trajectory to follow.
227 * @param pose A function that supplies the robot pose,
228 * provided by the odometry class.
229 * @param feedforward The feedforward to use for the drivetrain.
230 * @param kinematics The kinematics for the robot drivetrain.
231 * @param xController The Trajectory Tracker PID controller
232 * for the robot's x position.
233 * @param yController The Trajectory Tracker PID controller
234 * for the robot's y position.
235 * @param thetaController The Trajectory Tracker PID controller
236 * for angle for the robot.
237 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
238 * @param frontLeftController The front left wheel velocity PID.
239 * @param rearLeftController The rear left wheel velocity PID.
240 * @param frontRightController The front right wheel velocity PID.
241 * @param rearRightController The rear right wheel velocity PID.
242 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
243 * the current wheel speeds.
244 * @param output The output of the velocity PIDs.
245 * @param requirements The subsystems to require.
246 */
248 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
250 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
251 frc2::PIDController yController,
253 units::meters_per_second_t maxWheelVelocity,
254 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
255 frc2::PIDController frontLeftController,
256 frc2::PIDController rearLeftController,
257 frc2::PIDController frontRightController,
258 frc2::PIDController rearRightController,
259 std::function<void(units::volt_t, units::volt_t, units::volt_t,
260 units::volt_t)>
261 output,
262 std::span<Subsystem* const> requirements = {});
263
264 /**
265 * Constructs a new MecanumControllerCommand that when executed will follow
266 * the provided trajectory. The user should implement a velocity PID on the
267 * desired output wheel velocities.
268 *
269 * <p>Note: The controllers will *not* set the outputVolts to zero upon
270 * completion of the path - this is left to the user, since it is not
271 * appropriate for paths with nonstationary end-states.
272 *
273 * @param trajectory The trajectory to follow.
274 * @param pose A function that supplies the robot pose - use one
275 * of the odometry classes to provide this.
276 * @param kinematics The kinematics for the robot drivetrain.
277 * @param xController The Trajectory Tracker PID controller
278 * for the robot's x position.
279 * @param yController The Trajectory Tracker PID controller
280 * for the robot's y position.
281 * @param thetaController The Trajectory Tracker PID controller
282 * for angle for the robot.
283 * @param desiredRotation The angle that the robot should be facing.
284 * This is sampled at each time step.
285 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
286 * @param output The output of the position PIDs.
287 * @param requirements The subsystems to require.
288 */
290 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
291 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
292 frc2::PIDController yController,
294 std::function<frc::Rotation2d()> desiredRotation,
295 units::meters_per_second_t maxWheelVelocity,
296 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
297 units::meters_per_second_t,
298 units::meters_per_second_t)>
299 output,
300 std::initializer_list<Subsystem*> requirements);
301
302 /**
303 * Constructs a new MecanumControllerCommand that when executed will follow
304 * the provided trajectory. The user should implement a velocity PID on the
305 * desired output wheel velocities.
306 *
307 * <p>Note: The controllers will *not* set the outputVolts to zero upon
308 * completion of the path - this is left to the user, since it is not
309 * appropriate for paths with nonstationary end-states.
310 *
311 * <p>Note 2: The final rotation of the robot will be set to the rotation of
312 * the final pose in the trajectory. The robot will not follow the rotations
313 * from the poses at each timestep. If alternate rotation behavior is desired,
314 * the other constructor with a supplier for rotation should be used.
315 *
316 * @param trajectory The trajectory to follow.
317 * @param pose A function that supplies the robot pose - use one
318 * of the odometry classes to provide this.
319 * @param kinematics The kinematics for the robot drivetrain.
320 * @param xController The Trajectory Tracker PID controller
321 * for the robot's x position.
322 * @param yController The Trajectory Tracker PID controller
323 * for the robot's y position.
324 * @param thetaController The Trajectory Tracker PID controller
325 * for angle for the robot.
326 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
327 * @param output The output of the position PIDs.
328 * @param requirements The subsystems to require.
329 */
331 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
332 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
333 frc2::PIDController yController,
335 units::meters_per_second_t maxWheelVelocity,
336 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
337 units::meters_per_second_t,
338 units::meters_per_second_t)>
339 output,
340 std::initializer_list<Subsystem*> requirements);
341
342 /**
343 * Constructs a new MecanumControllerCommand that when executed will follow
344 * the provided trajectory. The user should implement a velocity PID on the
345 * desired output wheel velocities.
346 *
347 * <p>Note: The controllers will *not* set the outputVolts to zero upon
348 * completion of the path - this is left to the user, since it is not
349 * appropriate for paths with nonstationary end-states.
350 *
351 * @param trajectory The trajectory to follow.
352 * @param pose A function that supplies the robot pose - use one
353 * of the odometry classes to provide this.
354 * @param kinematics The kinematics for the robot drivetrain.
355 * @param xController The Trajectory Tracker PID controller
356 * for the robot's x position.
357 * @param yController The Trajectory Tracker PID controller
358 * for the robot's y position.
359 * @param thetaController The Trajectory Tracker PID controller
360 * for angle for the robot.
361 * @param desiredRotation The angle that the robot should be facing.
362 * This is sampled at every time step.
363 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
364 * @param output The output of the position PIDs.
365 * @param requirements The subsystems to require.
366 */
368 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
369 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
370 frc2::PIDController yController,
372 std::function<frc::Rotation2d()> desiredRotation,
373 units::meters_per_second_t maxWheelVelocity,
374 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
375 units::meters_per_second_t,
376 units::meters_per_second_t)>
377 output,
378 std::span<Subsystem* const> requirements = {});
379
380 /**
381 * Constructs a new MecanumControllerCommand that when executed will follow
382 * the provided trajectory. The user should implement a velocity PID on the
383 * desired output wheel velocities.
384 *
385 * <p>Note: The controllers will *not* set the outputVolts to zero upon
386 * completion of the path - this is left to the user, since it is not
387 * appropriate for paths with nonstationary end-states.
388 *
389 * <p>Note2: The final rotation of the robot will be set to the rotation of
390 * the final pose in the trajectory. The robot will not follow the rotations
391 * from the poses at each timestep. If alternate rotation behavior is desired,
392 * the other constructor with a supplier for rotation should be used.
393 *
394 * @param trajectory The trajectory to follow.
395 * @param pose A function that supplies the robot pose - use one
396 * of the odometry classes to provide this.
397 * @param kinematics The kinematics for the robot drivetrain.
398 * @param xController The Trajectory Tracker PID controller
399 * for the robot's x position.
400 * @param yController The Trajectory Tracker PID controller
401 * for the robot's y position.
402 * @param thetaController The Trajectory Tracker PID controller
403 * for angle for the robot.
404 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
405 * @param output The output of the position PIDs.
406 * @param requirements The subsystems to require.
407 */
409 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
410 frc::MecanumDriveKinematics kinematics, frc2::PIDController xController,
411 frc2::PIDController yController,
413 units::meters_per_second_t maxWheelVelocity,
414 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
415 units::meters_per_second_t,
416 units::meters_per_second_t)>
417 output,
418 std::span<Subsystem* const> requirements = {});
419
420 void Initialize() override;
421
422 void Execute() override;
423
424 void End(bool interrupted) override;
425
426 bool IsFinished() override;
427
428 private:
429 frc::Trajectory m_trajectory;
430 std::function<frc::Pose2d()> m_pose;
432 frc::MecanumDriveKinematics m_kinematics;
434 std::function<frc::Rotation2d()> m_desiredRotation;
435 const units::meters_per_second_t m_maxWheelVelocity;
436 std::unique_ptr<frc2::PIDController> m_frontLeftController;
437 std::unique_ptr<frc2::PIDController> m_rearLeftController;
438 std::unique_ptr<frc2::PIDController> m_frontRightController;
439 std::unique_ptr<frc2::PIDController> m_rearRightController;
440 std::function<frc::MecanumDriveWheelSpeeds()> m_currentWheelSpeeds;
441 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
442 units::meters_per_second_t, units::meters_per_second_t)>
443 m_outputVel;
444 std::function<void(units::volt_t, units::volt_t, units::volt_t,
445 units::volt_t)>
446 m_outputVolts;
447
448 bool m_usePID;
449 frc::Timer m_timer;
450 frc::MecanumDriveWheelSpeeds m_prevSpeeds;
451 units::second_t m_prevTime;
452};
453} // namespace frc2
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:26
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: MecanumControllerCommand.h:54
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
bool IsFinished() override
Whether the command has finished.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< void(units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
void Execute() override
The main body of a command.
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc2::PIDController xController, frc2::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc2::PIDController frontLeftController, frc2::PIDController rearLeftController, frc2::PIDController frontRightController, frc2::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
void Initialize() override
The initial subroutine of a command.
void End(bool interrupted) override
The action to take when the command ends.
Implements a PID control loop.
Definition: PIDController.h:23
This holonomic drive controller can be used to follow trajectories using a holonomic drivetrain (i....
Definition: HolonomicDriveController.h:32
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition: MecanumDriveKinematics.h:42
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
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:28
Definition: InstantCommand.h:14
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15