WPILibC++ 2027.0.0-alpha-5
Loading...
Searching...
No Matches
wpi::RobotDriveBase Class Referenceabstract

Common base class for drive platforms. More...

#include <wpi/drive/RobotDriveBase.hpp>

Inheritance diagram for wpi::RobotDriveBase:
wpi::MotorSafety wpi::DifferentialDrive wpi::MecanumDrive

Public Types

enum class  MotorType {
  FRONT_LEFT = 0 , FRONT_RIGHT = 1 , REAR_LEFT = 2 , REAR_RIGHT = 3 ,
  LEFT = 0 , RIGHT = 1 , BACK = 2
}
 The location of a motor on the robot for the purpose of driving. More...

Public Member Functions

 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).
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.
void FeedWatchdog ()
 Feed the motor safety object.
void StopMotor () override=0
 Called to stop the motor when the timeout expires.
std::string GetDescription () const override=0
 Returns a description to print when an error occurs.
Public Member Functions inherited from wpi::MotorSafety
 MotorSafety ()
virtual ~MotorSafety ()
 MotorSafety (MotorSafety &&rhs)
MotorSafetyoperator= (MotorSafety &&rhs)
void Feed ()
 Feed the motor safety object.
void SetExpiration (wpi::units::second_t expirationTime)
 Set the expiration time for the corresponding motor safety object.
wpi::units::second_t GetExpiration () const
 Retrieve the timeout value for the corresponding motor safety object.
bool IsAlive () const
 Determine if the motor is still operating or has timed out.
void SetSafetyEnabled (bool enabled)
 Enable/disable motor safety for this device.
bool IsSafetyEnabled () const
 Return the state of the motor safety enabled flag.
void Check ()
 Check if this motor has exceeded its timeout.

Static Protected Member Functions

static void Desaturate (std::span< double > wheelVelocities)
 Renormalize all wheel velocities if the magnitude of any wheel is greater than 1.0.

Protected Attributes

double m_deadband = DEFAULT_DEADBAND
 Input deadband.
double m_maxOutput = DEFAULT_MAX_OUTPUT
 Maximum output.

Static Protected Attributes

static constexpr double DEFAULT_DEADBAND = 0.02
 Default input deadband.
static constexpr double DEFAULT_MAX_OUTPUT = 1.0
 Default maximum output.

Additional Inherited Members

Static Public Member Functions inherited from wpi::MotorSafety
static void CheckMotors ()
 Check the motors to see if any have timed out.

Detailed Description

Common base class for drive platforms.

MotorSafety is enabled by default.

Member Enumeration Documentation

◆ MotorType

enum class wpi::RobotDriveBase::MotorType
strong

The location of a motor on the robot for the purpose of driving.

Enumerator
FRONT_LEFT 

Front-left motor.

FRONT_RIGHT 

Front-right motor.

REAR_LEFT 

Rear-left motor.

REAR_RIGHT 

Rear-right motor.

LEFT 

Left motor.

RIGHT 

Right motor.

BACK 

Back motor.

Constructor & Destructor Documentation

◆ RobotDriveBase() [1/2]

wpi::RobotDriveBase::RobotDriveBase ( )

◆ ~RobotDriveBase()

wpi::RobotDriveBase::~RobotDriveBase ( )
overridedefault

◆ RobotDriveBase() [2/2]

wpi::RobotDriveBase::RobotDriveBase ( RobotDriveBase && )
default

Member Function Documentation

◆ Desaturate()

void wpi::RobotDriveBase::Desaturate ( std::span< double > wheelVelocities)
staticprotected

Renormalize all wheel velocities if the magnitude of any wheel is greater than 1.0.

◆ FeedWatchdog()

void wpi::RobotDriveBase::FeedWatchdog ( )

Feed the motor safety object.

Resets the timer that will stop the motors if it completes.

See also
MotorSafetyHelper::Feed()

◆ GetDescription()

std::string wpi::RobotDriveBase::GetDescription ( ) const
overridepure virtual

Returns a description to print when an error occurs.

Returns
Description to print when an error occurs.

Implements wpi::MotorSafety.

Implemented in wpi::DifferentialDrive, and wpi::MecanumDrive.

◆ operator=()

RobotDriveBase & wpi::RobotDriveBase::operator= ( RobotDriveBase && )
default

◆ SetDeadband()

void wpi::RobotDriveBase::SetDeadband ( double deadband)

Sets the deadband applied to the drive inputs (e.g., joystick values).

The default value is 0.02. Inputs smaller than the deadband are set to 0.0 while inputs larger than the deadband are scaled from 0.0 to 1.0. See wpi::math::ApplyDeadband().

Parameters
deadbandThe deadband to set.

◆ SetMaxOutput()

void wpi::RobotDriveBase::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.

Parameters
maxOutputMultiplied with the output percentage computed by the drive functions.

◆ StopMotor()

void wpi::RobotDriveBase::StopMotor ( )
overridepure virtual

Called to stop the motor when the timeout expires.

Implements wpi::MotorSafety.

Implemented in wpi::DifferentialDrive, and wpi::MecanumDrive.

Member Data Documentation

◆ DEFAULT_DEADBAND

double wpi::RobotDriveBase::DEFAULT_DEADBAND = 0.02
staticconstexprprotected

Default input deadband.

◆ DEFAULT_MAX_OUTPUT

double wpi::RobotDriveBase::DEFAULT_MAX_OUTPUT = 1.0
staticconstexprprotected

Default maximum output.

◆ m_deadband

double wpi::RobotDriveBase::m_deadband = DEFAULT_DEADBAND
protected

Input deadband.

◆ m_maxOutput

double wpi::RobotDriveBase::m_maxOutput = DEFAULT_MAX_OUTPUT
protected

Maximum output.


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