Package edu.wpi.first.wpilibj.drive
Class RobotDriveBase
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.drive.RobotDriveBase
-
- All Implemented Interfaces:
MotorSafety
,Sendable
,AutoCloseable
- Direct Known Subclasses:
DifferentialDrive
,KilloughDrive
,MecanumDrive
public abstract class RobotDriveBase extends SendableBase implements 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
protected MotorSafetyHelper
m_safetyHelper
-
Fields inherited from interface edu.wpi.first.wpilibj.MotorSafety
DEFAULT_SAFETY_EXPIRATION
-
-
Constructor Summary
Constructors Constructor Description RobotDriveBase()
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description protected double
applyDeadband(double value, double deadband)
Returns 0.0 if the given value is within the specified range around zero.void
feedWatchdog()
Feed the motor safety object.abstract String
getDescription()
double
getExpiration()
boolean
isAlive()
boolean
isSafetyEnabled()
protected double
limit(double value)
Limit motor values to the -1.0 to +1.0 range.protected 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
setExpiration(double timeout)
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.void
setSafetyEnabled(boolean enabled)
abstract void
stopMotor()
-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, close, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
-
Methods inherited from interface edu.wpi.first.wpilibj.Sendable
initSendable, setName
-
-
-
-
Field Detail
-
kDefaultDeadband
public static final double kDefaultDeadband
- See Also:
- Constant Field Values
-
kDefaultMaxOutput
public static final double kDefaultMaxOutput
- See Also:
- Constant Field Values
-
m_deadband
protected double m_deadband
-
m_maxOutput
protected double m_maxOutput
-
m_safetyHelper
protected MotorSafetyHelper m_safetyHelper
-
-
Method Detail
-
setDeadband
public void 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
applyDeadband(double, double)
.- Parameters:
deadband
- The deadband to set.
-
setMaxOutput
public 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.The default value is 1.0.
- Parameters:
maxOutput
- Multiplied with the output percentage computed by the drive functions.
-
feedWatchdog
public void feedWatchdog()
Feed the motor safety object. Resets the timer that will stop the motors if it completes.- See Also:
MotorSafetyHelper.feed()
-
setExpiration
public void setExpiration(double timeout)
- Specified by:
setExpiration
in interfaceMotorSafety
-
getExpiration
public double getExpiration()
- Specified by:
getExpiration
in interfaceMotorSafety
-
isAlive
public boolean isAlive()
- Specified by:
isAlive
in interfaceMotorSafety
-
stopMotor
public abstract void stopMotor()
- Specified by:
stopMotor
in interfaceMotorSafety
-
isSafetyEnabled
public boolean isSafetyEnabled()
- Specified by:
isSafetyEnabled
in interfaceMotorSafety
-
setSafetyEnabled
public void setSafetyEnabled(boolean enabled)
- Specified by:
setSafetyEnabled
in interfaceMotorSafety
-
getDescription
public abstract String getDescription()
- Specified by:
getDescription
in interfaceMotorSafety
-
limit
protected double limit(double value)
Limit motor values to the -1.0 to +1.0 range.
-
applyDeadband
protected double applyDeadband(double value, double deadband)
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
-
normalize
protected void normalize(double[] wheelSpeeds)
Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
-
-