WPILibC++ 2024.1.1-beta-4
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 <memory>
8
9#include <frc/Timer.h>
13#include <frc/geometry/Pose2d.h>
18#include <units/length.h>
19#include <units/time.h>
20#include <units/voltage.h>
21
25
26#pragma once
27
28namespace frc2 {
29
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 * swerve drive.
34 *
35 * <p>The command handles trajectory-following, Velocity PID calculations, and
36 * feedforwards internally. This is intended to be a more-or-less "complete
37 * solution" that can be used by teams without a great deal of controls
38 * 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 module states from the position 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 */
51template <size_t NumModules>
53 : public CommandHelper<Command, SwerveControllerCommand<NumModules>> {
54 using voltsecondspermeter =
55 units::compound_unit<units::voltage::volt, units::second,
57 using voltsecondssquaredpermeter =
60
61 public:
62 /**
63 * Constructs a new SwerveControllerCommand that when executed will follow the
64 * provided trajectory. This command will not return output voltages but
65 * rather raw module states from the position controllers which need to be put
66 * into a velocity PID.
67 *
68 * <p>Note: The controllers will *not* set the outputVolts to zero upon
69 * completion of the path- this is left to the user, since it is not
70 * appropriate for paths with nonstationary endstates.
71 *
72 * @param trajectory The trajectory to follow.
73 * @param pose A function that supplies the robot pose,
74 * provided by the odometry class.
75 * @param kinematics The kinematics for the robot drivetrain.
76 * @param xController The Trajectory Tracker PID controller
77 * for the robot's x position.
78 * @param yController The Trajectory Tracker PID controller
79 * for the robot's y position.
80 * @param thetaController The Trajectory Tracker PID controller
81 * for angle for the robot.
82 * @param desiredRotation The angle that the drivetrain should be
83 * facing. This is sampled at each time step.
84 * @param output The raw output module states from the
85 * position controllers.
86 * @param requirements The subsystems to require.
87 */
89 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
91 frc::PIDController xController, frc::PIDController yController,
93 std::function<frc::Rotation2d()> desiredRotation,
94 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
95 output,
96 Requirements requirements = {});
97
98 /**
99 * Constructs a new SwerveControllerCommand that when executed will follow the
100 * provided trajectory. This command will not return output voltages but
101 * rather raw module states from the position controllers which need to be put
102 * into a velocity PID.
103 *
104 * <p>Note: The controllers will *not* set the outputVolts to zero upon
105 * completion of the path- this is left to the user, since it is not
106 * appropriate for paths with nonstationary endstates.
107 *
108 * <p>Note 2: The final rotation of the robot will be set to the rotation of
109 * the final pose in the trajectory. The robot will not follow the rotations
110 * from the poses at each timestep. If alternate rotation behavior is desired,
111 * the other constructor with a supplier for rotation should be used.
112 *
113 * @param trajectory The trajectory to follow.
114 * @param pose A function that supplies the robot pose,
115 * provided by the odometry class.
116 * @param kinematics The kinematics for the robot drivetrain.
117 * @param xController The Trajectory Tracker PID controller
118 * for the robot's x position.
119 * @param yController The Trajectory Tracker PID controller
120 * for the robot's y position.
121 * @param thetaController The Trajectory Tracker PID controller
122 * for angle for the robot.
123 * @param output The raw output module states from the
124 * position controllers.
125 * @param requirements The subsystems to require.
126 */
128 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
130 frc::PIDController xController, frc::PIDController yController,
132 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
133 output,
134 Requirements requirements = {});
135
136 /**
137 * Constructs a new SwerveControllerCommand that when executed will follow the
138 * provided trajectory. This command will not return output voltages but
139 * rather raw module states from the position controllers which need to be put
140 * into a velocity PID.
141 *
142 * <p>Note: The controllers will *not* set the outputVolts to zero upon
143 * completion of the path- this is left to the user, since it is not
144 * appropriate for paths with nonstationary endstates.
145 *
146 * @param trajectory The trajectory to follow.
147 * @param pose A function that supplies the robot pose,
148 * provided by the odometry class.
149 * @param kinematics The kinematics for the robot drivetrain.
150 * @param controller The HolonomicDriveController for the drivetrain.
151 * @param desiredRotation The angle that the drivetrain should be
152 * facing. This is sampled at each time step.
153 * @param output The raw output module states from the
154 * position controllers.
155 * @param requirements The subsystems to require.
156 */
158 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
161 std::function<frc::Rotation2d()> desiredRotation,
162 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
163 output,
164 Requirements requirements = {});
165
166 /**
167 * Constructs a new SwerveControllerCommand that when executed will follow the
168 * provided trajectory. This command will not return output voltages but
169 * rather raw module states from the position controllers which need to be put
170 * into a velocity PID.
171 *
172 * <p>Note: The controllers will *not* set the outputVolts to zero upon
173 * completion of the path- this is left to the user, since it is not
174 * appropriate for paths with nonstationary endstates.
175 *
176 * <p>Note 2: The final rotation of the robot will be set to the rotation of
177 * the final pose in the trajectory. The robot will not follow the rotations
178 * from the poses at each timestep. If alternate rotation behavior is desired,
179 * the other constructor with a supplier for rotation should be used.
180 *
181 * @param trajectory The trajectory to follow.
182 * @param pose A function that supplies the robot pose,
183 * provided by the odometry class.
184 * @param kinematics The kinematics for the robot drivetrain.
185 * @param controller The HolonomicDriveController for the drivetrain.
186 * @param output The raw output module states from the
187 * position controllers.
188 * @param requirements The subsystems to require.
189 */
191 frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
194 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
195 output,
196 Requirements requirements = {});
197
198 void Initialize() override;
199
200 void Execute() override;
201
202 void End(bool interrupted) override;
203
204 bool IsFinished() override;
205
206 private:
207 frc::Trajectory m_trajectory;
208 std::function<frc::Pose2d()> m_pose;
211 std::function<void(std::array<frc::SwerveModuleState, NumModules>)>
212 m_outputStates;
213
214 std::function<frc::Rotation2d()> m_desiredRotation;
215
216 frc::Timer m_timer;
217 units::second_t m_prevTime;
218 frc::Rotation2d m_finalRotation;
219};
220} // namespace frc2
221
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:25
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:53
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:1146
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1446
Definition: TrapezoidProfileSubsystem.h:12
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13