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