WPILibC++ 2023.4.3-108-ge5452e3
frc::DifferentialDrive Class Reference

A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base, "tank drive", or West Coast Drive. More...

#include <frc/drive/DifferentialDrive.h>

Inheritance diagram for frc::DifferentialDrive:
frc::RobotDriveBase wpi::Sendable wpi::SendableHelper< DifferentialDrive > frc::MotorSafety

Classes

struct  WheelSpeeds
 Wheel speeds for a differential drive. More...
 

Public Member Functions

 DifferentialDrive (MotorController &leftMotor, MotorController &rightMotor)
 Construct a DifferentialDrive. More...
 
 ~DifferentialDrive () override=default
 
 DifferentialDrive (DifferentialDrive &&)=default
 
DifferentialDriveoperator= (DifferentialDrive &&)=default
 
void ArcadeDrive (double xSpeed, double zRotation, bool squareInputs=true)
 Arcade drive method for differential drive platform. More...
 
void CurvatureDrive (double xSpeed, double zRotation, bool allowTurnInPlace)
 Curvature drive method for differential drive platform. More...
 
void TankDrive (double leftSpeed, double rightSpeed, bool squareInputs=true)
 Tank drive method for differential drive platform. More...
 
void StopMotor () override
 
std::string GetDescription () const override
 The return value from this method is printed out when an error occurs. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc::RobotDriveBase
 RobotDriveBase ()
 
 ~RobotDriveBase () override=default
 
 RobotDriveBase (RobotDriveBase &&)=default
 
RobotDriveBaseoperator= (RobotDriveBase &&)=default
 
void SetDeadband (double deadband)
 Sets the deadband applied to the drive inputs (e.g., joystick values). More...
 
void SetMaxOutput (double maxOutput)
 Configure the scaling factor for using RobotDrive with motor controllers in a mode other than PercentVbus or to limit the maximum output. More...
 
void FeedWatchdog ()
 Feed the motor safety object. More...
 
void StopMotor () override=0
 
std::string GetDescription () const override=0
 The return value from this method is printed out when an error occurs. More...
 
- Public Member Functions inherited from frc::MotorSafety
 MotorSafety ()
 
virtual ~MotorSafety ()
 
 MotorSafety (MotorSafety &&rhs)
 
MotorSafetyoperator= (MotorSafety &&rhs)
 
void Feed ()
 Feed the motor safety object. More...
 
void SetExpiration (units::second_t expirationTime)
 Set the expiration time for the corresponding motor safety object. More...
 
units::second_t GetExpiration () const
 Retrieve the timeout value for the corresponding motor safety object. More...
 
bool IsAlive () const
 Determine if the motor is still operating or has timed out. More...
 
void SetSafetyEnabled (bool enabled)
 Enable/disable motor safety for this device. More...
 
bool IsSafetyEnabled () const
 Return the state of the motor safety enabled flag. More...
 
void Check ()
 Check if this motor has exceeded its timeout. More...
 
virtual void StopMotor ()=0
 
virtual std::string GetDescription () const =0
 The return value from this method is printed out when an error occurs. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< DifferentialDrive >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Static Public Member Functions

static WheelSpeeds ArcadeDriveIK (double xSpeed, double zRotation, bool squareInputs=true)
 Arcade drive inverse kinematics for differential drive platform. More...
 
static WheelSpeeds CurvatureDriveIK (double xSpeed, double zRotation, bool allowTurnInPlace)
 Curvature drive inverse kinematics for differential drive platform. More...
 
static WheelSpeeds TankDriveIK (double leftSpeed, double rightSpeed, bool squareInputs=true)
 Tank drive inverse kinematics for differential drive platform. More...
 
- Static Public Member Functions inherited from frc::MotorSafety
static void CheckMotors ()
 Check the motors to see if any have timed out. More...
 

Additional Inherited Members

- Public Types inherited from frc::RobotDriveBase
enum  MotorType {
  kFrontLeft = 0 , kFrontRight = 1 , kRearLeft = 2 , kRearRight = 3 ,
  kLeft = 0 , kRight = 1 , kBack = 2
}
 The location of a motor on the robot for the purpose of driving. More...
 
- Protected Member Functions inherited from wpi::SendableHelper< DifferentialDrive >
 SendableHelper ()=default
 
 ~SendableHelper ()
 
- Static Protected Member Functions inherited from frc::RobotDriveBase
static void Desaturate (std::span< double > wheelSpeeds)
 Renormalize all wheel speeds if the magnitude of any wheel is greater than 1.0. More...
 
- Protected Attributes inherited from frc::RobotDriveBase
double m_deadband = 0.02
 
double m_maxOutput = 1.0
 

Detailed Description

A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base, "tank drive", or West Coast Drive.

These drive bases typically have drop-center / skid-steer with two or more wheels per side (e.g., 6WD or 8WD). This class takes a MotorController per side. For four and six motor drivetrains, construct and pass in MotorControllerGroup instances as follows.

Four motor drivetrain:

class Robot {
public:
frc::PWMVictorSPX m_frontLeft{1};
frc::PWMVictorSPX m_rearLeft{2};
frc::MotorControllerGroup m_left{m_frontLeft, m_rearLeft};
frc::PWMVictorSPX m_frontRight{3};
frc::PWMVictorSPX m_rearRight{4};
frc::MotorControllerGroup m_right{m_frontRight, m_rearRight};
frc::DifferentialDrive m_drive{m_left, m_right};
};
A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive base...
Definition: DifferentialDrive.h:92
Allows multiple MotorController objects to be linked together.
Definition: MotorControllerGroup.h:22
Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control.
Definition: PWMVictorSPX.h:28

Six motor drivetrain:

class Robot {
public:
frc::PWMVictorSPX m_frontLeft{1};
frc::PWMVictorSPX m_midLeft{2};
frc::PWMVictorSPX m_rearLeft{3};
frc::MotorControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft};
frc::PWMVictorSPX m_frontRight{4};
frc::PWMVictorSPX m_midRight{5};
frc::PWMVictorSPX m_rearRight{6};
frc::MotorControllerGroup m_right{m_frontRight, m_midRight, m_rearRight};
frc::DifferentialDrive m_drive{m_left, m_right};
};

A differential drive robot has left and right wheels separated by an arbitrary width.

Drive base diagram:

|_______|
| |   | |
  |   |
|_|___|_|
|       |

Each drive function provides different inverse kinematic relations for a differential drive robot.

This library uses the NWU axes convention (North-West-Up as external reference in the world frame). The positive X axis points ahead, the positive Y axis points to the left, and the positive Z axis points up. Rotations follow the right-hand rule, so counterclockwise rotation around the Z axis is positive.

Inputs smaller then 0.02 will be set to 0, and larger values will be scaled so that the full range is still used. This deadband value can be changed with SetDeadband().

MotorSafety is enabled by default. The tankDrive, arcadeDrive, or curvatureDrive methods should be called periodically to avoid Motor Safety timeouts.

Constructor & Destructor Documentation

◆ DifferentialDrive() [1/2]

frc::DifferentialDrive::DifferentialDrive ( MotorController leftMotor,
MotorController rightMotor 
)

Construct a DifferentialDrive.

To pass multiple motors per side, use a MotorControllerGroup. If a motor needs to be inverted, do so before passing it in.

◆ ~DifferentialDrive()

frc::DifferentialDrive::~DifferentialDrive ( )
overridedefault

◆ DifferentialDrive() [2/2]

frc::DifferentialDrive::DifferentialDrive ( DifferentialDrive &&  )
default

Member Function Documentation

◆ ArcadeDrive()

void frc::DifferentialDrive::ArcadeDrive ( double  xSpeed,
double  zRotation,
bool  squareInputs = true 
)

Arcade drive method for differential drive platform.

Note: Some drivers may prefer inverted rotation controls. This can be done by negating the value passed for rotation.

Parameters
xSpeedThe speed at which the robot should drive along the X axis [-1.0..1.0]. Forward is positive.
zRotationThe rotation rate of the robot around the Z axis [-1.0..1.0]. Counterclockwise is positive.
squareInputsIf set, decreases the input sensitivity at low speeds.

◆ ArcadeDriveIK()

static WheelSpeeds frc::DifferentialDrive::ArcadeDriveIK ( double  xSpeed,
double  zRotation,
bool  squareInputs = true 
)
static

Arcade drive inverse kinematics for differential drive platform.

Note: Some drivers may prefer inverted rotation controls. This can be done by negating the value passed for rotation.

Parameters
xSpeedThe speed at which the robot should drive along the X axis [-1.0..1.0]. Forward is positive.
zRotationThe rotation rate of the robot around the Z axis [-1.0..1.0]. Clockwise is positive.
squareInputsIf set, decreases the input sensitivity at low speeds.
Returns
Wheel speeds [-1.0..1.0].

◆ CurvatureDrive()

void frc::DifferentialDrive::CurvatureDrive ( double  xSpeed,
double  zRotation,
bool  allowTurnInPlace 
)

Curvature drive method for differential drive platform.

The rotation argument controls the curvature of the robot's path rather than its rate of heading change. This makes the robot more controllable at high speeds.

Parameters
xSpeedThe robot's speed along the X axis [-1.0..1.0]. Forward is positive.
zRotationThe normalized curvature [-1.0..1.0]. Counterclockwise is positive.
allowTurnInPlaceIf set, overrides constant-curvature turning for turn-in-place maneuvers. zRotation will control turning rate instead of curvature.

◆ CurvatureDriveIK()

static WheelSpeeds frc::DifferentialDrive::CurvatureDriveIK ( double  xSpeed,
double  zRotation,
bool  allowTurnInPlace 
)
static

Curvature drive inverse kinematics for differential drive platform.

The rotation argument controls the curvature of the robot's path rather than its rate of heading change. This makes the robot more controllable at high speeds.

Parameters
xSpeedThe robot's speed along the X axis [-1.0..1.0]. Forward is positive.
zRotationThe normalized curvature [-1.0..1.0]. Clockwise is positive.
allowTurnInPlaceIf set, overrides constant-curvature turning for turn-in-place maneuvers. zRotation will control turning rate instead of curvature.
Returns
Wheel speeds [-1.0..1.0].

◆ GetDescription()

std::string frc::DifferentialDrive::GetDescription ( ) const
overridevirtual

The return value from this method is printed out when an error occurs.

This method must not throw!

Implements frc::RobotDriveBase.

◆ InitSendable()

void frc::DifferentialDrive::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ operator=()

DifferentialDrive & frc::DifferentialDrive::operator= ( DifferentialDrive &&  )
default

◆ StopMotor()

void frc::DifferentialDrive::StopMotor ( )
overridevirtual

Implements frc::RobotDriveBase.

◆ TankDrive()

void frc::DifferentialDrive::TankDrive ( double  leftSpeed,
double  rightSpeed,
bool  squareInputs = true 
)

Tank drive method for differential drive platform.

Parameters
leftSpeedThe robot left side's speed along the X axis [-1.0..1.0]. Forward is positive.
rightSpeedThe robot right side's speed along the X axis [-1.0..1.0]. Forward is positive.
squareInputsIf set, decreases the input sensitivity at low speeds.

◆ TankDriveIK()

static WheelSpeeds frc::DifferentialDrive::TankDriveIK ( double  leftSpeed,
double  rightSpeed,
bool  squareInputs = true 
)
static

Tank drive inverse kinematics for differential drive platform.

Parameters
leftSpeedThe robot left side's speed along the X axis [-1.0..1.0]. Forward is positive.
rightSpeedThe robot right side's speed along the X axis [-1.0..1.0]. Forward is positive.
squareInputsIf set, decreases the input sensitivity at low speeds.
Returns
Wheel speeds [-1.0..1.0].

The documentation for this class was generated from the following file: