8#include <initializer_list>
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,
119 std::span<Subsystem* const> requirements = {});
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)>
167 std::span<Subsystem* const> requirements = {});
173 void End(
bool interrupted)
override;
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)>
193 units::second_t m_prevTime;
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