WPILibC++ 2024.3.2
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 <memory>
9
10#include <frc/Timer.h>
14#include <frc/geometry/Pose2d.h>
17#include <units/length.h>
18#include <units/voltage.h>
19
23
24namespace frc2 {
25/**
26 * A command that uses a RAMSETE controller to follow a trajectory
27 * with a differential drive.
28 *
29 * <p>The command handles trajectory-following, PID calculations, and
30 * feedforwards internally. This is intended to be a more-or-less "complete
31 * solution" that can be used by teams without a great deal of controls
32 * expertise.
33 *
34 * <p>Advanced teams seeking more flexibility (for example, those who wish to
35 * use the onboard PID functionality of a "smart" motor controller) may use the
36 * secondary constructor that omits the PID and feedforward functionality,
37 * returning only the raw wheel speeds from the RAMSETE controller.
38 *
39 * This class is provided by the NewCommands VendorDep
40 *
41 * @see RamseteController
42 * @see Trajectory
43 */
44class RamseteCommand : public CommandHelper<Command, RamseteCommand> {
45 public:
46 /**
47 * Constructs a new RamseteCommand that, when executed, will follow the
48 * provided trajectory. PID control and feedforward are handled internally,
49 * and outputs are scaled -12 to 12 representing units of volts.
50 *
51 * <p>Note: The controller will *not* set the outputVolts to zero upon
52 * completion of the path - this is left to the user, since it is not
53 * appropriate for paths with nonstationary endstates.
54 *
55 * @param trajectory The trajectory to follow.
56 * @param pose A function that supplies the robot pose - use one of
57 * the odometry classes to provide this.
58 * @param controller The RAMSETE controller used to follow the
59 * trajectory.
60 * @param feedforward A component for calculating the feedforward for the
61 * drive.
62 * @param kinematics The kinematics for the robot drivetrain.
63 * @param wheelSpeeds A function that supplies the speeds of the left
64 * and right sides of the robot drive.
65 * @param leftController The PIDController for the left side of the robot
66 * drive.
67 * @param rightController The PIDController for the right side of the robot
68 * drive.
69 * @param output A function that consumes the computed left and right
70 * outputs (in volts) for the robot drive.
71 * @param requirements The subsystems to require.
72 */
73 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
74 frc::RamseteController controller,
77 std::function<frc::DifferentialDriveWheelSpeeds()> wheelSpeeds,
78 frc::PIDController leftController,
79 frc::PIDController rightController,
80 std::function<void(units::volt_t, units::volt_t)> output,
81 Requirements requirements = {});
82
83 /**
84 * Constructs a new RamseteCommand that, when executed, will follow the
85 * provided trajectory. Performs no PID control and calculates no
86 * feedforwards; outputs are the raw wheel speeds from the RAMSETE controller,
87 * and will need to be converted into a usable form by the user.
88 *
89 * @param trajectory The trajectory to follow.
90 * @param pose A function that supplies the robot pose - use one of
91 * the odometry classes to provide this.
92 * @param controller The RAMSETE controller used to follow the
93 * trajectory.
94 * @param kinematics The kinematics for the robot drivetrain.
95 * @param output A function that consumes the computed left and right
96 * wheel speeds.
97 * @param requirements The subsystems to require.
98 */
99 RamseteCommand(frc::Trajectory trajectory, std::function<frc::Pose2d()> pose,
100 frc::RamseteController controller,
102 std::function<void(units::meters_per_second_t,
103 units::meters_per_second_t)>
104 output,
105 Requirements requirements = {});
106
107 void Initialize() override;
108
109 void Execute() override;
110
111 void End(bool interrupted) override;
112
113 bool IsFinished() override;
114
115 void InitSendable(wpi::SendableBuilder& builder) override;
116
117 private:
118 frc::Trajectory m_trajectory;
119 std::function<frc::Pose2d()> m_pose;
120 frc::RamseteController m_controller;
123 std::function<frc::DifferentialDriveWheelSpeeds()> m_speeds;
124 std::unique_ptr<frc::PIDController> m_leftController;
125 std::unique_ptr<frc::PIDController> m_rightController;
126 std::function<void(units::volt_t, units::volt_t)> m_outputVolts;
127 std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
128 m_outputVel;
129
130 frc::Timer m_timer;
131 units::second_t m_prevTime;
133 bool m_usePID;
134};
135} // namespace frc2
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:27
A command that uses a RAMSETE controller to follow a trajectory with a differential drive.
Definition: RamseteCommand.h:44
void Execute() override
void End(bool interrupted) override
void InitSendable(wpi::SendableBuilder &builder) override
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, frc::PIDController leftController, frc::PIDController rightController, std::function< void(units::volt_t, units::volt_t)> output, Requirements requirements={})
Constructs a new RamseteCommand that, when executed, will follow the provided trajectory.
void Initialize() override
bool IsFinished() override
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, Requirements requirements={})
Constructs a new RamseteCommand 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
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:29
Implements a PID control loop.
Definition: PIDController.h:23
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
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:25
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
Definition: TrapezoidProfileSubsystem.h:12
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:15