129 void ArcadeDrive(
double xSpeed,
double zRotation,
bool squareInputs =
true);
157 void TankDrive(
double leftSpeed,
double rightSpeed,
bool squareInputs =
true);
173 bool squareInputs =
true);
192 bool allowTurnInPlace);
205 bool squareInputs =
true);
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:92
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
The return value from this method is printed out when an error occurs.
DifferentialDrive & operator=(DifferentialDrive &&)=default
static WheelSpeeds CurvatureDriveIK(double xSpeed, double zRotation, bool allowTurnInPlace)
Curvature drive inverse kinematics for differential drive platform.
~DifferentialDrive() override=default
DifferentialDrive(MotorController &leftMotor, MotorController &rightMotor)
Construct a DifferentialDrive.
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.
void StopMotor() override
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
Definition: SendableBuilder.h:18
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: AprilTagPoseEstimator.h:15
Wheel speeds for a differential drive.
Definition: DifferentialDrive.h:99
double left
Definition: DifferentialDrive.h:100
double right
Definition: DifferentialDrive.h:101