WPILibC++ 2023.4.3
RamseteCommand.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#pragma once
6
7#include <functional>
8#include <initializer_list>
9#include <memory>
10#include <span>
11
12#include <frc/Timer.h>
16#include <frc/geometry/Pose2d.h>
19#include <units/length.h>
20#include <units/voltage.h>
21
24
25namespace frc2 {
26/**
27 * A command that uses a RAMSETE controller to follow a trajectory
28 * with a differential drive.
29 *
30 * <p>The command handles trajectory-following, PID calculations, and
31 * feedforwards internally. This is intended to be a more-or-less "complete
32 * solution" that can be used by teams without a great deal of controls
33 * expertise.
34 *
35 * <p>Advanced teams seeking more flexibility (for example, those who wish to
36 * use the onboard PID functionality of a "smart" motor controller) may use the
37 * secondary constructor that omits the PID and feedforward functionality,
38 * returning only the raw wheel speeds from the RAMSETE controller.
39 *
40 * This class is provided by the NewCommands VendorDep
41 *
42 * @see RamseteController
43 * @see Trajectory
44 */
45class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
46 public:
47 /**
48 * Constructs a new RamseteCommand that, when executed, will follow the
49 * provided trajectory. PID control and feedforward are handled internally,
50 * and outputs are scaled -12 to 12 representing units of volts.
51 *
52 * <p>Note: The controller will *not* set the outputVolts to zero upon
53 * completion of the path - this is left to the user, since it is not
54 * appropriate for paths with nonstationary endstates.
55 *
56 * @param trajectory The trajectory to follow.
57 * @param pose A function that supplies the robot pose - use one of
58 * the odometry classes to provide this.
59 * @param controller The RAMSETE controller used to follow the
60 * trajectory.
61 * @param feedforward A component for calculating the feedforward for the
62 * drive.
63 * @param kinematics The kinematics for the robot drivetrain.
64 * @param wheelSpeeds A function that supplies the speeds of the left
65 * and right sides of the robot drive.
66 * @param leftController The PIDController for the left side of the robot
67 * drive.
68 * @param rightController The PIDController for the right side of the robot
69 * drive.
70 * @param output A function that consumes the computed left and right
71 * outputs (in volts) for the robot drive.
72 * @param requirements The subsystems to require.
73 */
74 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
75 frc::RamseteController controller,
78 std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
79 frc2::PIDController leftController,
80 frc2::PIDController rightController,
81 std::function<void(units::volt_t, units::volt_t)> output,
82 std::initializer_list<Subsystem*> requirements);
83
84 /**
85 * Constructs a new RamseteCommand that, when executed, will follow the
86 * provided trajectory. PID control and feedforward are handled internally,
87 * and outputs are scaled -12 to 12 representing units of volts.
88 *
89 * <p>Note: The controller will *not* set the outputVolts to zero upon
90 * completion of the path - this is left to the user, since it is not
91 * appropriate for paths with nonstationary endstates.
92 *
93 * @param trajectory The trajectory to follow.
94 * @param pose A function that supplies the robot pose - use one of
95 * the odometry classes to provide this.
96 * @param controller The RAMSETE controller used to follow the
97 * trajectory.
98 * @param feedforward A component for calculating the feedforward for the
99 * drive.
100 * @param kinematics The kinematics for the robot drivetrain.
101 * @param wheelSpeeds A function that supplies the speeds of the left
102 * and right sides of the robot drive.
103 * @param leftController The PIDController for the left side of the robot
104 * drive.
105 * @param rightController The PIDController for the right side of the robot
106 * drive.
107 * @param output A function that consumes the computed left and right
108 * outputs (in volts) for the robot drive.
109 * @param requirements The subsystems to require.
110 */
111 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
112 frc::RamseteController controller,
115 std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
116 frc2::PIDController leftController,
117 frc2::PIDController rightController,
118 std::function<void(units::volt_t, units::volt_t)> output,
119 std::span<Subsystem* const> requirements = {});
120
121 /**
122 * Constructs a new RamseteCommand that, when executed, will follow the
123 * provided trajectory. Performs no PID control and calculates no
124 * feedforwards; outputs are the raw wheel speeds from the RAMSETE controller,
125 * and will need to be converted into a usable form by the user.
126 *
127 * @param trajectory The trajectory to follow.
128 * @param pose A function that supplies the robot pose - use one of
129 * the odometry classes to provide this.
130 * @param controller The RAMSETE controller used to follow the
131 * trajectory.
132 * @param kinematics The kinematics for the robot drivetrain.
133 * @param output A function that consumes the computed left and right
134 * wheel speeds.
135 * @param requirements The subsystems to require.
136 */
137 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
138 frc::RamseteController controller,
140 std::function<void(units::meters_per_second_t,
141 units::meters_per_second_t)>
142 output,
143 std::initializer_list<Subsystem*> requirements);
144
145 /**
146 * Constructs a new RamseteCommand that, when executed, will follow the
147 * provided trajectory. Performs no PID control and calculates no
148 * feedforwards; outputs are the raw wheel speeds from the RAMSETE controller,
149 * and will need to be converted into a usable form by the user.
150 *
151 * @param trajectory The trajectory to follow.
152 * @param pose A function that supplies the robot pose - use one of
153 * the odometry classes to provide this.
154 * @param controller The RAMSETE controller used to follow the
155 * trajectory.
156 * @param kinematics The kinematics for the robot drivetrain.
157 * @param output A function that consumes the computed left and right
158 * wheel speeds.
159 * @param requirements The subsystems to require.
160 */
161 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
162 frc::RamseteController controller,
164 std::function<void(units::meters_per_second_t,
165 units::meters_per_second_t)>
166 output,
167 std::span<Subsystem* const> requirements = {});
168
169 void Initialize() override;
170
171 void Execute() override;
172
173 void End(bool interrupted) override;
174
175 bool IsFinished() override;
176
177 void InitSendable(wpi::SendableBuilder& builder) override;
178
179 private:
180 frc::Trajectory m_trajectory;
181 std::function<frc::Pose2d()> m_pose;
182 frc::RamseteController m_controller;
185 std::function<frc::DifferentialDriveWheelSpeeds()> m_speeds;
186 std::unique_ptr<frc2::PIDController> m_leftController;
187 std::unique_ptr<frc2::PIDController> m_rightController;
188 std::function<void(units::volt_t, units::volt_t)> m_outputVolts;
189 std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
190 m_outputVel;
191
192 frc::Timer m_timer;
193 units::second_t m_prevTime;
195 bool m_usePID;
196};
197} // namespace frc2
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:26
Implements a PID control loop.
Definition: PIDController.h:23
A command that uses a RAMSETE controller to follow a trajectory with a differential drive.
Definition: RamseteCommand.h:45
void Execute() override
The main body of a command.
void End(bool interrupted) override
The action to take when the command ends.
RamseteCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::DifferentialDriveKinematics kinematics, std::function< frc::DifferentialDriveWheelSpeeds()> wheelSpeeds, frc2::PIDController leftController, frc2::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
RamseteCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::DifferentialDriveKinematics kinematics, std::function< void(units::meters_per_second_t, units::meters_per_second_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void Initialize() override
The initial subroutine of a command.
bool IsFinished() override
Whether the command has finished.
RamseteCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::DifferentialDriveKinematics kinematics, std::function< void(units::meters_per_second_t, units::meters_per_second_t)> output, std::initializer_list< Subsystem * > requirements)
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
RamseteCommand(frc::Trajectory trajectory, std::function< frc::Pose2d()> pose, frc::RamseteController controller, frc::SimpleMotorFeedforward< units::meters > feedforward, frc::DifferentialDriveKinematics kinematics, std::function< frc::DifferentialDriveWheelSpeeds()> wheelSpeeds, frc2::PIDController leftController, frc2::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, std::span< Subsystem *const > requirements={})
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:25
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition: RamseteController.h:45
A timer class.
Definition: Timer.h:36
Represents a time-parameterized trajectory.
Definition: Trajectory.h:28
Definition: SendableBuilder.h:18
Definition: InstantCommand.h:14
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15