100 std::function<
void(
double)> rightMotor);
121 bool squareInputs =
true);
139 bool allowTurnInPlace);
151 void TankDrive(
double leftVelocity,
double rightVelocity,
152 bool squareInputs =
true);
169 bool squareInputs =
true);
188 bool allowTurnInPlace);
202 bool squareInputs =
true);
210 std::function<void(
double)> m_leftMotor;
211 std::function<void(
double)> m_rightMotor;
214 double m_leftOutput = 0.0;
215 double m_rightOutput = 0.0;
void ArcadeDrive(double xVelocity, double zRotation, bool squareInputs=true)
Arcade drive method for differential drive platform.
WPI_IGNORE_DEPRECATED DifferentialDrive(MotorController &leftMotor, MotorController &rightMotor)
Construct a DifferentialDrive.
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.
WPI_UNIGNORE_DEPRECATED DifferentialDrive(std::function< void(double)> leftMotor, std::function< void(double)> rightMotor)
Construct a DifferentialDrive.
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.
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.
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
#define WPI_IGNORE_DEPRECATED
Definition deprecated.hpp:15
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.hpp:26
Definition CvSource.hpp:15
Wheel velocities for a differential drive.
Definition DifferentialDrive.hpp:66
double right
Right wheel velocity.
Definition DifferentialDrive.hpp:70
double left
Left wheel velocity.
Definition DifferentialDrive.hpp:68