Package edu.wpi.first.wpilibj.drive
Class RobotDriveBase
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- edu.wpi.first.wpilibj.drive.RobotDriveBase
-
- All Implemented Interfaces:
Sendable,AutoCloseable
- Direct Known Subclasses:
DifferentialDrive,KilloughDrive,MecanumDrive
public abstract class RobotDriveBase extends MotorSafety implements Sendable, AutoCloseable
Common base class for drive platforms.
-
-
Nested Class Summary
Nested Classes Modifier and Type Class Description static classRobotDriveBase.MotorTypeThe location of a motor on the robot for the purpose of driving.
-
Field Summary
Fields Modifier and Type Field Description static doublekDefaultDeadbandstatic doublekDefaultMaxOutputprotected doublem_deadbandprotected doublem_maxOutput
-
Constructor Summary
Constructors Constructor Description RobotDriveBase()RobotDriveBase constructor.
-
Method Summary
All Methods Instance Methods Abstract Methods Concrete Methods Modifier and Type Method Description protected voidaddChild(Object child)Add a child component.protected doubleapplyDeadband(double value, double deadband)Returns 0.0 if the given value is within the specified range around zero.voidclose()voidfeedWatchdog()Feed the motor safety object.abstract StringgetDescription()StringgetName()Gets the name of thisSendableobject.StringgetSubsystem()Gets the subsystem name of thisSendableobject.protected doublelimit(double value)Limit motor values to the -1.0 to +1.0 range.protected voidnormalize(double[] wheelSpeeds)Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.voidsetDeadband(double deadband)Sets the deadband applied to the drive inputs (e.g., joystick values).voidsetMaxOutput(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.voidsetName(String name)Sets the name of thisSendableobject.protected voidsetName(String moduleType, int channel)Sets the name of the sensor with a channel number.protected voidsetName(String moduleType, int moduleNumber, int channel)Sets the name of the sensor with a module and channel number.voidsetSubsystem(String subsystem)Sets the subsystem name of thisSendableobject.abstract voidstopMotor()-
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
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
-
-
Method Detail
-
close
public void close()
- Specified by:
closein interfaceAutoCloseable
-
getName
public final String getName()
Description copied from interface:SendableGets the name of thisSendableobject.
-
setName
public final void setName(String name)
Description copied from interface:SendableSets the name of thisSendableobject.
-
setName
protected final void setName(String moduleType, int channel)
Sets the name of the sensor with a channel number.- Parameters:
moduleType- A string that defines the module name in the label for the valuechannel- The channel number the device is plugged into
-
setName
protected final void setName(String moduleType, int moduleNumber, int channel)
Sets the name of the sensor with a module and channel number.- Parameters:
moduleType- A string that defines the module name in the label for the valuemoduleNumber- The number of the particular module typechannel- The channel number the device is plugged into (usually PWM)
-
getSubsystem
public final String getSubsystem()
Description copied from interface:SendableGets the subsystem name of thisSendableobject.- Specified by:
getSubsystemin interfaceSendable- Returns:
- Subsystem name
-
setSubsystem
public final void setSubsystem(String subsystem)
Description copied from interface:SendableSets the subsystem name of thisSendableobject.- Specified by:
setSubsystemin interfaceSendable- Parameters:
subsystem- subsystem name
-
addChild
protected final void addChild(Object child)
Add a child component.- Parameters:
child- child component
-
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:
MotorSafety.feed()
-
stopMotor
public abstract void stopMotor()
- Specified by:
stopMotorin classMotorSafety
-
getDescription
public abstract String getDescription()
- Specified by:
getDescriptionin classMotorSafety
-
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.
-
-