public abstract class PWMSpeedController extends SafePWM implements SpeedController
PWM.PeriodMultiplier
DEFAULT_SAFETY_EXPIRATION
Modifier | Constructor and Description |
---|---|
protected |
PWMSpeedController(int channel)
Constructor.
|
Modifier and Type | Method and Description |
---|---|
double |
get()
Get the recently set value of the PWM.
|
java.lang.String |
getDescription() |
boolean |
getInverted()
Common interface for returning if a speed controller is in the inverted state or not.
|
void |
initSendable(SendableBuilder builder)
Initializes this
Sendable object. |
void |
pidWrite(double output)
Write out the PID value as seen in the PIDOutput base object.
|
void |
set(double speed)
Set the PWM value.
|
void |
setInverted(boolean isInverted)
Common interface for inverting direction of a speed controller.
|
disable, feed, Feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled, stopMotor
close, enableDeadbandElimination, getChannel, getPosition, getRaw, getRawBounds, getSpeed, setBounds, setDisabled, setPeriodMultiplier, setPosition, setRaw, setSpeed, setZeroLatch
addChild, free, getName, getSubsystem, setName, setName, setName, setSubsystem
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
disable, stopMotor
protected PWMSpeedController(int channel)
channel
- The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are
on the MXP portpublic java.lang.String getDescription()
getDescription
in interface MotorSafety
getDescription
in class SafePWM
public void set(double speed)
The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the FPGA.
set
in interface SpeedController
speed
- The speed value between -1.0 and 1.0 to set.public double get()
get
in interface SpeedController
public void setInverted(boolean isInverted)
SpeedController
setInverted
in interface SpeedController
isInverted
- The state of inversion true is inverted.public boolean getInverted()
SpeedController
getInverted
in interface SpeedController
public void pidWrite(double output)
public void initSendable(SendableBuilder builder)
Sendable
Sendable
object.initSendable
in interface Sendable
initSendable
in class PWM
builder
- sendable builder