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.
-
-
Constructor Summary
Constructors Modifier Constructor Description protected
PWMMotorController(String name, int channel)
Constructor.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description 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()
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()
Stops motor movement.-
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.motorcontrol.MotorController
setVoltage
-
-
-
-
Constructor Detail
-
PWMMotorController
protected PWMMotorController(String name, int channel)
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 Detail
-
close
public void close()
Free the resource associated with the PWM channel and set the value to 0.- Specified by:
close
in interfaceAutoCloseable
-
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 interfaceMotorController
- 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. 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
- 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:MotorController
Common interface for inverting direction of a motor controller.- Specified by:
setInverted
in interfaceMotorController
- Specified by:
setInverted
in interfaceSpeedController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
getInverted
public boolean 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
- Specified by:
getInverted
in interfaceSpeedController
- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
public void disable()
Description copied from interface:MotorController
Disable the motor controller.- Specified by:
disable
in interfaceMotorController
- Specified by:
disable
in interfaceSpeedController
-
stopMotor
public void stopMotor()
Description copied from interface:MotorController
Stops motor movement. Motor can be moved again by calling set without having to re-enable the motor.- Specified by:
stopMotor
in interfaceMotorController
- Specified by:
stopMotor
in interfaceSpeedController
- Specified by:
stopMotor
in classMotorSafety
-
getDescription
public String getDescription()
- Specified by:
getDescription
in classMotorSafety
-
getPwmHandle
public int getPwmHandle()
Gets the backing PWM handle.- Returns:
- The pwm handle.
-
getChannel
public int getChannel()
Gets the PWM channel number.- Returns:
- The channel number.
-
enableDeadbandElimination
public void enableDeadbandElimination(boolean eliminateDeadband)
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
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-