WPILibC++ 2024.3.2
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 <functional>
6#include <memory>
7
8#include <frc/Timer.h>
13#include <frc/geometry/Pose2d.h>
18#include <units/angle.h>
19#include <units/length.h>
20#include <units/velocity.h>
21#include <units/voltage.h>
22
26
27#pragma once
28
29namespace frc2 {
30/**
31 * A command that uses two PID controllers (PIDController) and a profiled PID
32 * controller (ProfiledPIDController) to follow a trajectory (Trajectory) with a
33 * mecanum drive.
34 *
35 * <p>The command handles trajectory-following,
36 * Velocity PID calculations, and feedforwards internally. This
37 * is intended to be a more-or-less "complete solution" that can be used by
38 * teams without a great deal of controls expertise.
39 *
40 * <p>Advanced teams seeking more flexibility (for example, those who wish to
41 * use the onboard PID functionality of a "smart" motor controller) may use the
42 * secondary constructor that omits the PID and feedforward functionality,
43 * returning only the raw wheel speeds from the PID controllers.
44 *
45 * <p>The robot angle controller does not follow the angle given by
46 * the trajectory but rather goes to the angle given in the final state of the
47 * trajectory.
48 *
49 * This class is provided by the NewCommands VendorDep
50 */
52 : public CommandHelper<Command, MecanumControllerCommand> {
53 public:
54 /**
55 * Constructs a new MecanumControllerCommand that when executed will follow
56 * the provided trajectory. PID control and feedforward are handled
57 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
58 * motor.
59 *
60 * <p>Note: The controllers will *not* set the outputVolts to zero upon
61 * completion of the path this is left to the user, since it is not
62 * appropriate for paths with nonstationary endstates.
63 *
64 * @param trajectory The trajectory to follow.
65 * @param pose A function that supplies the robot pose,
66 * provided by the odometry class.
67 * @param feedforward The feedforward to use for the drivetrain.
68 * @param kinematics The kinematics for the robot drivetrain.
69 * @param xController The Trajectory Tracker PID controller
70 * for the robot's x position.
71 * @param yController The Trajectory Tracker PID controller
72 * for the robot's y position.
73 * @param thetaController The Trajectory Tracker PID controller
74 * for angle for the robot.
75 * @param desiredRotation The angle that the robot should be facing.
76 * This is sampled at each time step.
77 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
78 * @param frontLeftController The front left wheel velocity PID.
79 * @param rearLeftController The rear left wheel velocity PID.
80 * @param frontRightController The front right wheel velocity PID.
81 * @param rearRightController The rear right wheel velocity PID.
82 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
83 * the current wheel speeds.
84 * @param output The output of the velocity PIDs.
85 * @param requirements The subsystems to require.
86 */
88 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
90 frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
91 frc::PIDController yController,
93 std::function<frc::Rotation2d()> desiredRotation,
94 units::meters_per_second_t maxWheelVelocity,
95 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
96 frc::PIDController frontLeftController,
97 frc::PIDController rearLeftController,
98 frc::PIDController frontRightController,
99 frc::PIDController rearRightController,
100 std::function<void(units::volt_t, units::volt_t, units::volt_t,
101 units::volt_t)>
102 output,
103 Requirements requirements = {});
104
105 /**
106 * Constructs a new MecanumControllerCommand that when executed will follow
107 * the provided trajectory. PID control and feedforward are handled
108 * internally. Outputs are scaled from -12 to 12 as a voltage output to the
109 * motor.
110 *
111 * <p>Note: The controllers will *not* set the outputVolts to zero upon
112 * completion of the path this is left to the user, since it is not
113 * appropriate for paths with nonstationary endstates.
114 *
115 * <p>Note 2: The final rotation of the robot will be set to the rotation of
116 * the final pose in the trajectory. The robot will not follow the rotations
117 * from the poses at each timestep. If alternate rotation behavior is desired,
118 * the other constructor with a supplier for rotation should be used.
119 *
120 * @param trajectory The trajectory to follow.
121 * @param pose A function that supplies the robot pose,
122 * provided by the odometry class.
123 * @param feedforward The feedforward to use for the drivetrain.
124 * @param kinematics The kinematics for the robot drivetrain.
125 * @param xController The Trajectory Tracker PID controller
126 * for the robot's x position.
127 * @param yController The Trajectory Tracker PID controller
128 * for the robot's y position.
129 * @param thetaController The Trajectory Tracker PID controller
130 * for angle for the robot.
131 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
132 * @param frontLeftController The front left wheel velocity PID.
133 * @param rearLeftController The rear left wheel velocity PID.
134 * @param frontRightController The front right wheel velocity PID.
135 * @param rearRightController The rear right wheel velocity PID.
136 * @param currentWheelSpeeds A MecanumDriveWheelSpeeds object containing
137 * the current wheel speeds.
138 * @param output The output of the velocity PIDs.
139 * @param requirements The subsystems to require.
140 */
142 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
144 frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
145 frc::PIDController yController,
147 units::meters_per_second_t maxWheelVelocity,
148 std::function<frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds,
149 frc::PIDController frontLeftController,
150 frc::PIDController rearLeftController,
151 frc::PIDController frontRightController,
152 frc::PIDController rearRightController,
153 std::function<void(units::volt_t, units::volt_t, units::volt_t,
154 units::volt_t)>
155 output,
156 Requirements requirements = {});
157
158 /**
159 * Constructs a new MecanumControllerCommand that when executed will follow
160 * the provided trajectory. The user should implement a velocity PID on the
161 * desired output wheel velocities.
162 *
163 * <p>Note: The controllers will *not* set the outputVolts to zero upon
164 * completion of the path - this is left to the user, since it is not
165 * appropriate for paths with nonstationary end-states.
166 *
167 * @param trajectory The trajectory to follow.
168 * @param pose A function that supplies the robot pose - use one
169 * of the odometry classes to provide this.
170 * @param kinematics The kinematics for the robot drivetrain.
171 * @param xController The Trajectory Tracker PID controller
172 * for the robot's x position.
173 * @param yController The Trajectory Tracker PID controller
174 * for the robot's y position.
175 * @param thetaController The Trajectory Tracker PID controller
176 * for angle for the robot.
177 * @param desiredRotation The angle that the robot should be facing.
178 * This is sampled at each time step.
179 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
180 * @param output The output of the position PIDs.
181 * @param requirements The subsystems to require.
182 */
184 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
185 frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
186 frc::PIDController yController,
188 std::function<frc::Rotation2d()> desiredRotation,
189 units::meters_per_second_t maxWheelVelocity,
190 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
191 units::meters_per_second_t,
192 units::meters_per_second_t)>
193 output,
194 Requirements requirements);
195
196 /**
197 * Constructs a new MecanumControllerCommand that when executed will follow
198 * the provided trajectory. The user should implement a velocity PID on the
199 * desired output wheel velocities.
200 *
201 * <p>Note: The controllers will *not* set the outputVolts to zero upon
202 * completion of the path - this is left to the user, since it is not
203 * appropriate for paths with nonstationary end-states.
204 *
205 * <p>Note 2: The final rotation of the robot will be set to the rotation of
206 * the final pose in the trajectory. The robot will not follow the rotations
207 * from the poses at each timestep. If alternate rotation behavior is desired,
208 * the other constructor with a supplier for rotation should be used.
209 *
210 * @param trajectory The trajectory to follow.
211 * @param pose A function that supplies the robot pose - use one
212 * of the odometry classes to provide this.
213 * @param kinematics The kinematics for the robot drivetrain.
214 * @param xController The Trajectory Tracker PID controller
215 * for the robot's x position.
216 * @param yController The Trajectory Tracker PID controller
217 * for the robot's y position.
218 * @param thetaController The Trajectory Tracker PID controller
219 * for angle for the robot.
220 * @param maxWheelVelocity The maximum velocity of a drivetrain wheel.
221 * @param output The output of the position PIDs.
222 * @param requirements The subsystems to require.
223 */
225 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
226 frc::MecanumDriveKinematics kinematics, frc::PIDController xController,
227 frc::PIDController yController,
229 units::meters_per_second_t maxWheelVelocity,
230 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
231 units::meters_per_second_t,
232 units::meters_per_second_t)>
233 output,
234 Requirements requirements = {});
235
236 void Initialize() override;
237
238 void Execute() override;
239
240 void End(bool interrupted) override;
241
242 bool IsFinished() override;
243
244 private:
245 frc::Trajectory m_trajectory;
246 std::function<frc::Pose2d()> m_pose;
248 frc::MecanumDriveKinematics m_kinematics;
250 std::function<frc::Rotation2d()> m_desiredRotation;
251 const units::meters_per_second_t m_maxWheelVelocity;
252 std::unique_ptr<frc::PIDController> m_frontLeftController;
253 std::unique_ptr<frc::PIDController> m_rearLeftController;
254 std::unique_ptr<frc::PIDController> m_frontRightController;
255 std::unique_ptr<frc::PIDController> m_rearRightController;
256 std::function<frc::MecanumDriveWheelSpeeds()> m_currentWheelSpeeds;
257 std::function<void(units::meters_per_second_t, units::meters_per_second_t,
258 units::meters_per_second_t, units::meters_per_second_t)>
259 m_outputVel;
260 std::function<void(units::volt_t, units::volt_t, units::volt_t,
261 units::volt_t)>
262 m_outputVolts;
263
264 bool m_usePID;
265 frc::Timer m_timer;
266 frc::MecanumDriveWheelSpeeds m_prevSpeeds;
267 units::second_t m_prevTime;
268};
269} // namespace frc2
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:27
A command that uses two PID controllers (PIDController) and a profiled PID controller (ProfiledPIDCon...
Definition: MecanumControllerCommand.h:52
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::MecanumDriveKinematics kinematics, frc::PIDController xController, frc::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc::PIDController frontLeftController, frc::PIDController rearLeftController, frc::PIDController frontRightController, frc::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, Requirements 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, frc::PIDController xController, frc::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, Requirements 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, frc::PIDController xController, frc::PIDController yController, frc::ProfiledPIDController< units::radians > thetaController, std::function< frc::Rotation2d()> desiredRotation, units::meters_per_second_t maxWheelVelocity, std::function< frc::MecanumDriveWheelSpeeds()> currentWheelSpeeds, frc::PIDController frontLeftController, frc::PIDController rearLeftController, frc::PIDController frontRightController, frc::PIDController rearRightController, std::function< void(units::volt_t, units::volt_t, units::volt_t, units::volt_t)> output, Requirements requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
void End(bool interrupted) override
MecanumControllerCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::MecanumDriveKinematics kinematics, frc::PIDController xController, frc::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, Requirements requirements={})
Constructs a new MecanumControllerCommand that when executed will follow the provided trajectory.
Represents requirements for a command, which is a set of (pointers to) subsystems.
Definition: Requirements.h:20
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:44
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
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:25
Definition: TrapezoidProfileSubsystem.h:12
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
Represents the wheel speeds for a mecanum drive drivetrain.
Definition: MecanumDriveWheelSpeeds.h:15