Package edu.wpi.first.wpilibj
Class PWMSpeedController
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- edu.wpi.first.wpilibj.PWM
-
- edu.wpi.first.wpilibj.PWMSpeedController
-
- All Implemented Interfaces:
PIDOutput
,Sendable
,SpeedController
,AutoCloseable
- Direct Known Subclasses:
DMC60
,Jaguar
,PWMTalonSRX
,PWMVictorSPX
,SD540
,Spark
,Talon
,Victor
,VictorSP
public abstract class PWMSpeedController extends PWM implements SpeedController
Common base class for all PWM Speed Controllers.
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj.PWM
PWM.PeriodMultiplier
-
-
Constructor Summary
Constructors Modifier Constructor Description protected
PWMSpeedController(int channel)
Constructor.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
disable()
Disable the speed controller.double
get()
Get the recently set value of the PWM.String
getDescription()
boolean
getInverted()
Common interface for returning if a speed controller is in the inverted state or not.void
initSendable(SendableBuilder builder)
Initializes thisSendable
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.-
Methods inherited from class edu.wpi.first.wpilibj.PWM
addChild, close, enableDeadbandElimination, getChannel, getName, getPosition, getRaw, getRawBounds, getSpeed, getSubsystem, setBounds, setDisabled, setName, setName, setName, setPeriodMultiplier, setPosition, setRaw, setSpeed, setSubsystem, setZeroLatch, stopMotor
-
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.SpeedController
stopMotor
-
-
-
-
Method Detail
-
getDescription
public String getDescription()
- Overrides:
getDescription
in classPWM
-
set
public void set(double speed)
Set the PWM value.The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the FPGA.
- Specified by:
set
in interfaceSpeedController
- Parameters:
speed
- The speed value between -1.0 and 1.0 to set.
-
get
public double get()
Get the recently set value of the PWM.- Specified by:
get
in interfaceSpeedController
- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
setInverted
public void setInverted(boolean isInverted)
Description copied from interface:SpeedController
Common interface for inverting direction of a speed controller.- Specified by:
setInverted
in interfaceSpeedController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
getInverted
public boolean getInverted()
Description copied from interface:SpeedController
Common interface for returning if a speed controller is in the inverted state or not.- Specified by:
getInverted
in interfaceSpeedController
- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
public void disable()
Description copied from interface:SpeedController
Disable the speed controller.- Specified by:
disable
in interfaceSpeedController
-
pidWrite
public void pidWrite(double output)
Write out the PID value as seen in the PIDOutput base object.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Overrides:
initSendable
in classPWM
- Parameters:
builder
- sendable builder
-
-