74 [[deprecated(
"Use LTVUnicycleController instead.")]]
82 std::function<
void(units::volt_t, units::volt_t)> output,
102 [[deprecated(
"Use LTVUnicycleController instead.")]]
106 std::function<
void(units::meters_per_second_t,
107 units::meters_per_second_t)> output,
114 void End(
bool interrupted)
override;
127 std::unique_ptr<frc::PIDController> m_leftController;
128 std::unique_ptr<frc::PIDController> m_rightController;
129 std::function<void(units::volt_t, units::volt_t)> m_outputVolts;
130 std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
134 units::second_t m_prevTime;
CRTP implementation to allow polymorphic decorator functions in Command.
Definition CommandHelper.h:25
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:31
Implements a PID control loop.
Definition PIDController.h:29
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition RamseteController.h:48
A helper class that computes feedforward voltages for a simple permanent-magnet DC motor.
Definition SimpleMotorFeedforward.h:24
A timer class.
Definition Timer.h:36
Represents a time-parameterized trajectory.
Definition Trajectory.h:29
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.h:21
Definition FunctionalCommand.h:13
Represents the wheel speeds for a differential drive drivetrain.
Definition DifferentialDriveWheelSpeeds.h:16