Class PWMMotorController
java.lang.Object
edu.wpi.first.wpilibj.MotorSafety
edu.wpi.first.wpilibj.motorcontrol.PWMMotorController
- All Implemented Interfaces:
Sendable
,MotorController
,AutoCloseable
- Direct Known Subclasses:
DMC60
,Jaguar
,PWMSparkFlex
,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 protected
PWMMotorController(String name, int channel)
Constructor. -
Method Summary
Modifier and Type Method Description void
addFollower(PWMMotorController follower)
Make the given PWM motor controller follow the output of this one.void
close()
Free the resource associated with the PWM channel and set the value to 0.void
disable()
Disable the motor controller.void
enableDeadbandElimination(boolean eliminateDeadband)
Optionally eliminate the deadband from a motor controller.double
get()
Get the recently set value of the PWM.int
getChannel()
Gets the PWM channel number.String
getDescription()
Returns a description to print when an error occurs.boolean
getInverted()
Common interface for returning if a motor controller is in the inverted state or not.int
getPwmHandle()
Gets the backing PWM handle.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
set(double speed)
Set the PWM value.void
setInverted(boolean isInverted)
Common interface for inverting direction of a motor controller.void
stopMotor()
Called to stop the motor when the timeout expires.Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
Field Details
-
m_pwm
PWM instances for motor controller.
-
-
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:
close
in 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:
set
in interfaceMotorController
- 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:
get
in interfaceMotorController
- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
setInverted
Description copied from interface:MotorController
Common interface for inverting direction of a motor controller.- Specified by:
setInverted
in interfaceMotorController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
getInverted
Description copied from interface:MotorController
Common interface for returning if a motor controller is in the inverted state or not.- Specified by:
getInverted
in interfaceMotorController
- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
Description copied from interface:MotorController
Disable the motor controller.- Specified by:
disable
in interfaceMotorController
-
stopMotor
Description copied from class:MotorSafety
Called to stop the motor when the timeout expires.- Specified by:
stopMotor
in interfaceMotorController
- Specified by:
stopMotor
in classMotorSafety
-
getDescription
Description copied from class:MotorSafety
Returns a description to print when an error occurs.- Specified by:
getDescription
in classMotorSafety
- Returns:
- Description to print when an error occurs.
-
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.
-
addFollower
Make the given PWM motor controller follow the output of this one.- Parameters:
follower
- The motor controller follower.
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-