101 std::function<
void(
double)> rightMotor);
120 void ArcadeDrive(
double xSpeed,
double zRotation,
bool squareInputs =
true);
148 void TankDrive(
double leftSpeed,
double rightSpeed,
bool squareInputs =
true);
164 bool squareInputs =
true);
183 bool allowTurnInPlace);
196 bool squareInputs =
true);
204 std::function<void(
double)> m_leftMotor;
205 std::function<void(
double)> m_rightMotor;
208 double m_leftOutput = 0.0;
209 double m_rightOutput = 0.0;
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:60
void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs=true)
Arcade drive method for differential drive platform.
DifferentialDrive(DifferentialDrive &&)=default
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
std::string GetDescription() const override
Returns a description to print when an error occurs.
DifferentialDrive & operator=(DifferentialDrive &&)=default
WPI_UNIGNORE_DEPRECATED DifferentialDrive(std::function< void(double)> leftMotor, std::function< void(double)> rightMotor)
Construct a DifferentialDrive.
static WheelSpeeds CurvatureDriveIK(double xSpeed, double zRotation, bool allowTurnInPlace)
Curvature drive inverse kinematics for differential drive platform.
~DifferentialDrive() override=default
static WheelSpeeds ArcadeDriveIK(double xSpeed, double zRotation, bool squareInputs=true)
Arcade drive inverse kinematics for differential drive platform.
void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs=true)
Tank 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.
void CurvatureDrive(double xSpeed, double zRotation, bool allowTurnInPlace)
Curvature drive method for differential drive platform.
static WheelSpeeds TankDriveIK(double leftSpeed, double rightSpeed, bool squareInputs=true)
Tank drive inverse kinematics for differential drive platform.
Interface for motor controlling devices.
Definition: MotorController.h:14
Common base class for drive platforms.
Definition: RobotDriveBase.h:20
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
#define WPI_IGNORE_DEPRECATED
Definition: deprecated.h:20
#define WPI_UNIGNORE_DEPRECATED
Definition: deprecated.h:31
Definition: AprilTagPoseEstimator.h:15
Wheel speeds for a differential drive.
Definition: DifferentialDrive.h:67
double left
Left wheel speed.
Definition: DifferentialDrive.h:69
double right
Right wheel speed.
Definition: DifferentialDrive.h:71