Class PWMMotorController
java.lang.Object
org.wpilib.hardware.motor.MotorSafety
org.wpilib.hardware.motor.PWMMotorController
- All Implemented Interfaces:
AutoCloseable, MotorController, Sendable
- Direct Known Subclasses:
Koors40, PWMSparkFlex, PWMSparkMax, PWMTalonFX, PWMTalonSRX, PWMVenom, PWMVictorSPX, RomiMotor, Spark, SparkMini, Talon, 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()Disables the motor controller.voidenableDeadbandElimination(boolean eliminateDeadband) Optionally eliminate the deadband from a motor controller.intGets the PWM channel number.Returns a description to print when an error occurs.protected final doubleGets the duty cycle from -1 to 1 (the sign indicates direction), from the currently set pulse time.booleanGets the inversion state of the motor controller.intGets the backing PWM handle.doubleGets the throttle of the motor controller.doubleGets the voltage output of the motor controller, nominally between -12 V and 12 V.voidinitSendable(SendableBuilder builder) Initializes thisSendableobject.protected final voidsetBoundsMicroseconds(int maxPwm, int deadbandMaxPwm, int centerPwm, int deadbandMinPwm, int minPwm) Sets the bounds in microseconds for the controller.protected final voidsetDutyCycleInternal(double dutyCycle) Takes a duty cycle from -1 to 1 (the sign indicates direction), and outputs it in the microsecond format.voidsetInverted(boolean isInverted) Sets the inversion state of the motor controller.voidsetThrottle(double throttle) Sets the throttle of the motor controller.voidCalled to stop the motor when the timeout expires.Methods inherited from class MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabledMethods inherited from class Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface MotorController
setVoltage, setVoltage
-
Field Details
-
m_pwm
-
-
Constructor Details
-
PWMMotorController
Constructor.- Parameters:
name- Name to use for SendableRegistrychannel- The SmartIO channel that the controller is attached to.
-
-
Method Details
-
close
Free the resource associated with the PWM channel and set the value to 0.- Specified by:
closein interfaceAutoCloseable
-
setDutyCycleInternal
Takes a duty cycle from -1 to 1 (the sign indicates direction), and outputs it in the microsecond format.- Parameters:
dutyCycle- The duty cycle between -1 and 1 (sign indicates direction).
-
getDutyCycleInternal
Gets the duty cycle from -1 to 1 (the sign indicates direction), from the currently set pulse time.- Returns:
- motor controller duty cycle
-
setBoundsMicroseconds
protected final void setBoundsMicroseconds(int maxPwm, int deadbandMaxPwm, int centerPwm, int deadbandMinPwm, int minPwm) Sets the bounds in microseconds for the controller.- Parameters:
maxPwm- maximumdeadbandMaxPwm- deadband maxcenterPwm- centerdeadbandMinPwm- deadband minminPwm- minimum
-
setThrottle
Description copied from interface:MotorControllerSets the throttle of the motor controller.- Specified by:
setThrottlein interfaceMotorController- Parameters:
throttle- The throttle where -1 indicates full reverse and 1 indicates full forward.
-
getThrottle
Description copied from interface:MotorControllerGets the throttle of the motor controller.- Specified by:
getThrottlein interfaceMotorController- Returns:
- The throttle where -1 represents full reverse and 1 represents full forward.
-
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:MotorControllerSets the inversion state of the motor controller.- Specified by:
setInvertedin interfaceMotorController- Parameters:
isInverted- The inversion state.
-
getInverted
Description copied from interface:MotorControllerGets the inversion state of the motor controller.- Specified by:
getInvertedin interfaceMotorController- Returns:
- The inversion state.
-
disable
Description copied from interface:MotorControllerDisables the motor controller.- Specified by:
disablein interfaceMotorController
-
stopMotor
Description copied from class:MotorSafetyCalled to stop the motor when the timeout expires.- 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
-
getChannel
-
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
-