Package edu.wpi.first.wpilibj.drive
Class RobotDriveBase
java.lang.Object
edu.wpi.first.wpilibj.MotorSafety
edu.wpi.first.wpilibj.drive.RobotDriveBase
- Direct Known Subclasses:
DifferentialDrive
,KilloughDrive
,MecanumDrive
public abstract class RobotDriveBase extends MotorSafety
Common base class for drive platforms.
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static class
RobotDriveBase.MotorType
The location of a motor on the robot for the purpose of driving. -
Field Summary
Fields Modifier and Type Field Description static double
kDefaultDeadband
static double
kDefaultMaxOutput
protected double
m_deadband
protected double
m_maxOutput
-
Constructor Summary
Constructors Constructor Description RobotDriveBase()
RobotDriveBase constructor. -
Method Summary
Modifier and Type Method Description protected static double
applyDeadband(double value, double deadband)
Deprecated, for removal: This API element is subject to removal in a future version.Use MathUtil.applyDeadband(double,double).void
feedWatchdog()
Feed the motor safety object.abstract String
getDescription()
protected static void
normalize(double[] wheelSpeeds)
Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.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 drive methods with motor controllers in a mode other than PercentVbus or to limit the maximum output.abstract void
stopMotor()
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Field Details
-
kDefaultDeadband
- See Also:
- Constant Field Values
-
kDefaultMaxOutput
- See Also:
- Constant Field Values
-
m_deadband
-
m_maxOutput
-
-
Constructor Details
-
RobotDriveBase
public RobotDriveBase()RobotDriveBase constructor.
-
-
Method Details
-
setDeadband
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
MathUtil.applyDeadband(double, double)
.- Parameters:
deadband
- The deadband to set.
-
setMaxOutput
Configure the scaling factor for using drive methods with motor controllers in a mode other than PercentVbus or to limit the maximum output.The default value is 1.0.
- Parameters:
maxOutput
- Multiplied with the output percentage computed by the drive functions.
-
feedWatchdog
Feed the motor safety object. Resets the timer that will stop the motors if it completes.- See Also:
MotorSafety.feed()
-
stopMotor
- Specified by:
stopMotor
in classMotorSafety
-
getDescription
- Specified by:
getDescription
in classMotorSafety
-
applyDeadband
@Deprecated(since="2021", forRemoval=true) protected static double applyDeadband(double value, double deadband)Deprecated, for removal: This API element is subject to removal in a future version.Use MathUtil.applyDeadband(double,double).Returns 0.0 if the given value is within the specified range around zero. The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.- Parameters:
value
- value to clipdeadband
- range around zero- Returns:
- The value after the deadband is applied.
-
normalize
Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.- Parameters:
wheelSpeeds
- List of wheel speeds to normalize.
-