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,Koors40,PWMSparkFlex,PWMSparkMax,PWMTalonFX,PWMTalonSRX,PWMVenom,PWMVictorSPX,RomiMotor,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
Fields -
Constructor Summary
ConstructorsModifierConstructorDescriptionprotectedPWMMotorController(String name, int channel) Constructor. -
Method Summary
Modifier and TypeMethodDescriptionvoidaddFollower(PWMMotorController follower) Make the given PWM motor controller follow the output of this one.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.intGets the PWM channel number.Returns a description to print when an error occurs.booleanCommon interface for returning if a motor controller is in the inverted state or not.intGets the backing PWM handle.doubleGets the voltage output of the motor controller, nominally between -12 V and 12 V.voidinitSendable(SendableBuilder builder) Initializes thisSendableobject.voidset(double speed) Set the PWM value.voidsetInverted(boolean isInverted) Common interface for inverting direction of a motor controller.voidCalled to stop the motor when the timeout expires.Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabledMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj.motorcontrol.MotorController
setVoltage, setVoltage
-
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:
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- 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- Returns:
- The most recently set value for the PWM between -1.0 and 1.0.
-
getVoltage
Gets the voltage output of the motor controller, nominally between -12 V and 12 V.- Returns:
- The voltage of the motor controller, nominally between -12 V and 12 V.
-
setInverted
Description copied from interface:MotorControllerCommon interface for inverting direction of a motor controller.- Specified by:
setInvertedin interfaceMotorController- 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- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
Description copied from interface:MotorControllerDisable the motor controller.- Specified by:
disablein interfaceMotorController
-
stopMotor
Description copied from class:MotorSafetyCalled to stop the motor when the timeout expires.- Specified by:
stopMotorin interfaceMotorController- Specified by:
stopMotorin classMotorSafety
-
getDescription
Description copied from class:MotorSafetyReturns a description to print when an error occurs.- Specified by:
getDescriptionin 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:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-