11 #include <initializer_list>
14 #include <frc/controller/PIDController.h>
15 #include <frc/controller/RamseteController.h>
16 #include <frc/controller/SimpleMotorFeedforward.h>
17 #include <frc/geometry/Pose2d.h>
18 #include <frc/kinematics/DifferentialDriveKinematics.h>
19 #include <frc/trajectory/Trajectory.h>
20 #include <units/units.h>
21 #include <wpi/ArrayRef.h>
23 #include "frc2/Timer.h"
24 #include "frc2/command/CommandBase.h"
25 #include "frc2/command/CommandHelper.h"
81 std::function<
void(units::volt_t, units::volt_t)> output,
82 std::initializer_list<Subsystem*> requirements);
118 std::function<
void(units::volt_t, units::volt_t)> output,
140 std::function<
void(units::meters_per_second_t,
141 units::meters_per_second_t)>
143 std::initializer_list<Subsystem*> requirements);
164 std::function<
void(units::meters_per_second_t,
165 units::meters_per_second_t)>
173 void End(
bool interrupted)
override;
184 std::unique_ptr<frc2::PIDController> m_leftController;
185 std::unique_ptr<frc2::PIDController> m_rightController;
186 std::function<void(units::volt_t, units::volt_t)> m_outputVolts;
187 std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
191 units::second_t m_prevTime;
ArrayRef - Represent a constant reference to an array (0 or more elements consecutively in memory),...
Definition: ArrayRef.h:42
A wrapper for the frc::Timer class that returns unit-typed values.
Definition: Timer.h:40
void End(bool interrupted) override
The action to take when the command ends.
Represents a 2d pose containing translational and rotational elements.
Definition: Pose2d.h:23
Represents the wheel speeds for a differential drive drivetrain.
Definition: DifferentialDriveWheelSpeeds.h:16
bool IsFinished() override
Whether the command has finished.
Helper class that converts a chassis velocity (dx and dtheta components) to left and right wheel velo...
Definition: DifferentialDriveKinematics.h:25
CRTP implementation to allow polymorphic decorator functions in Command.
Definition: CommandHelper.h:26
Represents a time-parameterized trajectory.
Definition: Trajectory.h:34
void Initialize() override
The initial subroutine of a command.
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.
A command that uses a RAMSETE controller to follow a trajectory with a differential drive.
Definition: RamseteCommand.h:45
Implements a PID control loop.
Definition: PIDController.h:23
void Execute() override
The main body of a command.
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition: RamseteController.h:45