80 std::function<
void(units::volt_t, units::volt_t)> output,
102 std::function<
void(units::meters_per_second_t,
103 units::meters_per_second_t)>
111 void End(
bool interrupted)
override;
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)>
131 units::second_t m_prevTime;
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 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