95 std::function<
void(
double)> rightMotor);
116 bool squareInputs =
true);
134 bool allowTurnInPlace);
146 void TankDrive(
double leftVelocity,
double rightVelocity,
147 bool squareInputs =
true);
164 bool squareInputs =
true);
183 bool allowTurnInPlace);
197 bool squareInputs =
true);
205 std::function<void(
double)> m_leftMotor;
206 std::function<void(
double)> m_rightMotor;
209 double m_leftOutput = 0.0;
210 double m_rightOutput = 0.0;
void ArcadeDrive(double xVelocity, double zRotation, bool squareInputs=true)
Arcade drive method for differential drive platform.
void StopMotor() override
Called to stop the motor when the timeout expires.
static WheelVelocities TankDriveIK(double leftVelocity, double rightVelocity, bool squareInputs=true)
Tank drive inverse kinematics for differential drive platform.
void TankDrive(double leftVelocity, double rightVelocity, bool squareInputs=true)
Tank drive method for differential drive platform.
std::string GetDescription() const override
Returns a description to print when an error occurs.
DifferentialDrive(DifferentialDrive &&)=default
void CurvatureDrive(double xVelocity, double zRotation, bool allowTurnInPlace)
Curvature drive method for differential drive platform.
~DifferentialDrive() override=default
DifferentialDrive & operator=(DifferentialDrive &&)=default
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
DifferentialDrive(MotorController &leftMotor, MotorController &rightMotor)
Construct a DifferentialDrive.
static WheelVelocities ArcadeDriveIK(double xVelocity, double zRotation, bool squareInputs=true)
Arcade drive inverse kinematics for differential drive platform.
static WheelVelocities CurvatureDriveIK(double xVelocity, double zRotation, bool allowTurnInPlace)
Curvature drive inverse kinematics for differential drive platform.
DifferentialDrive(std::function< void(double)> leftMotor, std::function< void(double)> rightMotor)
Construct a DifferentialDrive.
Interface for motor controlling devices.
Definition MotorController.hpp:14
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
Interface for Sendable objects.
Definition Sendable.hpp:16
Definition CvSource.hpp:15
Wheel velocities for a differential drive.
Definition DifferentialDrive.hpp:65
double right
Right wheel velocity.
Definition DifferentialDrive.hpp:69
double left
Left wheel velocity.
Definition DifferentialDrive.hpp:67