edu.wpi.first.wpilibj
Class SafePWM
java.lang.Object
edu.wpi.first.wpilibj.SensorBase
edu.wpi.first.wpilibj.PWM
edu.wpi.first.wpilibj.SafePWM
- All Implemented Interfaces:
- LiveWindowSendable, MotorSafety, Sendable
- Direct Known Subclasses:
- Jaguar, Talon, Victor
public class SafePWM
- extends PWM
- implements MotorSafety
Constructor Summary |
SafePWM(int channel)
Constructor for a SafePWM object taking a channel number |
SafePWM(int slot,
int channel)
Constructor for a SafePWM object taking channel and slot numbers. |
Methods inherited from class edu.wpi.first.wpilibj.PWM |
enableDeadbandElimination, free, getChannel, getModuleNumber, getPosition, getRaw, getSmartDashboardType, getSpeed, getTable, initTable, setBounds, setPeriodMultiplier, setPosition, setRaw, startLiveWindowMode, stopLiveWindowMode, updateTable |
Methods inherited from class edu.wpi.first.wpilibj.SensorBase |
checkAnalogChannel, checkAnalogModule, checkDigitalChannel, checkDigitalModule, checkPWMChannel, checkPWMModule, checkRelayChannel, checkRelayModule, checkSolenoidChannel, checkSolenoidModule, getDefaultAnalogModule, getDefaultDigitalModule, getDefaultSolenoidModule, setDefaultAnalogModule, setDefaultDigitalModule, setDefaultSolenoidModule |
Methods inherited from class java.lang.Object |
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
SafePWM
public SafePWM(int channel)
- Constructor for a SafePWM object taking a channel number
- Parameters:
channel
- The channel number to be used for the underlying PWM object
SafePWM
public SafePWM(int slot,
int channel)
- Constructor for a SafePWM object taking channel and slot numbers.
- Parameters:
slot
- The slot number of the digital module for this PWM objectchannel
- The channel number in the module for this PWM object
setExpiration
public void setExpiration(double timeout)
- Specified by:
setExpiration
in interface MotorSafety
getExpiration
public double getExpiration()
- Return the expiration time for the PWM object.
- Specified by:
getExpiration
in interface MotorSafety
- Returns:
- The expiration time value.
isAlive
public boolean isAlive()
- Check if the PWM object is currently alive or stopped due to a timeout.
- Specified by:
isAlive
in interface MotorSafety
- Returns:
- a bool value that is true if the motor has NOT timed out and should still
be running.
stopMotor
public void stopMotor()
- Stop the motor associated with this PWM object.
This is called by the MotorSafetyHelper object when it has a timeout for this PWM and needs to
stop it from running.
- Specified by:
stopMotor
in interface MotorSafety
isSafetyEnabled
public boolean isSafetyEnabled()
- Check if motor safety is enabled for this object
- Specified by:
isSafetyEnabled
in interface MotorSafety
- Returns:
- True if motor safety is enforced for this object
Feed
public void Feed()
- Feed the MotorSafety timer.
This method is called by the subclass motor whenever it updates its speed, thereby reseting
the timeout value.
setSafetyEnabled
public void setSafetyEnabled(boolean enabled)
- Specified by:
setSafetyEnabled
in interface MotorSafety
getDescription
public java.lang.String getDescription()
- Specified by:
getDescription
in interface MotorSafety
disable
public void disable()