Class PWMMotorController
java.lang.Object
edu.wpi.first.wpilibj.MotorSafety
edu.wpi.first.wpilibj.motorcontrol.PWMMotorController
- All Implemented Interfaces:
Sendable,MotorController,SpeedController,AutoCloseable
- Direct Known Subclasses:
DMC60,Jaguar,PWMSparkMax,PWMTalonFX,PWMTalonSRX,PWMVenom,PWMVictorSPX,SD540,Spark,Talon,Victor,VictorSP
public abstract class PWMMotorController extends MotorSafety implements MotorController, Sendable, AutoCloseable
Common base class for all PWM Motor Controllers.
-
Field Summary
-
Constructor Summary
Constructors Modifier Constructor Description protectedPWMMotorController(String name, int channel)Constructor. -
Method Summary
Modifier and Type Method Description voidclose()Free the resource associated with the PWM channel and set the value to 0.voiddisable()Disable the motor controller.voidenableDeadbandElimination(boolean eliminateDeadband)Optionally eliminate the deadband from a motor controller.doubleget()Get the recently set value of the PWM.intgetChannel()Gets the PWM channel number.StringgetDescription()booleangetInverted()Common interface for returning if a motor controller is in the inverted state or not.intgetPwmHandle()Gets the backing PWM handle.voidinitSendable(SendableBuilder builder)Initializes thisSendableobject.voidset(double speed)Set the PWM value.voidsetInverted(boolean isInverted)Common interface for inverting direction of a motor controller.voidstopMotor()Stops motor movement.Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Field Details
-
Constructor Details
-
PWMMotorController
Constructor.- Parameters:
name- Name to use for SendableRegistrychannel- The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are on the MXP port
-
-
Method Details
-
close
Free the resource associated with the PWM channel and set the value to 0.- Specified by:
closein interfaceAutoCloseable
-
set
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:
setin interfaceMotorController- Specified by:
setin interfaceSpeedController- Parameters:
speed- The speed value between -1.0 and 1.0 to set.
-
get
Get the recently set value of the PWM. This value is affected by the inversion property. If you want the value that is sent directly to the MotorController, usePWM.getSpeed()instead.- Specified by:
getin interfaceMotorController- Specified by:
getin interfaceSpeedController- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
setInverted
Description copied from interface:MotorControllerCommon interface for inverting direction of a motor controller.- Specified by:
setInvertedin interfaceMotorController- Specified by:
setInvertedin interfaceSpeedController- Parameters:
isInverted- The state of inversion true is inverted.
-
getInverted
Description copied from interface:MotorControllerCommon interface for returning if a motor controller is in the inverted state or not.- Specified by:
getInvertedin interfaceMotorController- Specified by:
getInvertedin interfaceSpeedController- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
Description copied from interface:MotorControllerDisable the motor controller.- Specified by:
disablein interfaceMotorController- Specified by:
disablein interfaceSpeedController
-
stopMotor
Description copied from interface:MotorControllerStops motor movement. Motor can be moved again by calling set without having to re-enable the motor.- Specified by:
stopMotorin interfaceMotorController- Specified by:
stopMotorin interfaceSpeedController- Specified by:
stopMotorin classMotorSafety
-
getDescription
- Specified by:
getDescriptionin classMotorSafety
-
getPwmHandle
Gets the backing PWM handle.- Returns:
- The pwm handle.
-
getChannel
Gets the PWM channel number.- Returns:
- The channel number.
-
enableDeadbandElimination
Optionally eliminate the deadband from a motor controller.- Parameters:
eliminateDeadband- If true, set the motor curve for the motor controller to eliminate the deadband in the middle of the range. Otherwise, keep the full range without modifying any values.
-
initSendable
Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-