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 Details

    • m_pwm

      protected PWM m_pwm
      PWM instances for motor controller.
  • Constructor Details

    • PWMMotorController

      protected PWMMotorController(String name, int channel)
      Constructor.
      Parameters:
      name - Name to use for SendableRegistry
      channel - The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are on the MXP port
  • Method Details

    • close

      public void close()
      Free the resource associated with the PWM channel and set the value to 0.
      Specified by:
      close in interface AutoCloseable
    • setDutyCycleInternal

      protected final void setDutyCycleInternal(double dutyCycle)
      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

      protected final double 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 - maximum
      deadbandMaxPwm - deadband max
      centerPwm - center
      deadbandMinPwm - deadmand min
      minPwm - minimum
    • setDutyCycle

      public void setDutyCycle(double dutyCycle)
      Description copied from interface: MotorController
      Sets the duty cycle of the motor controller.
      Specified by:
      setDutyCycle in interface MotorController
      Parameters:
      dutyCycle - The duty cycle between -1 and 1 (sign indicates direction).
    • getDutyCycle

      public double getDutyCycle()
      Description copied from interface: MotorController
      Gets the duty cycle of the motor controller.
      Specified by:
      getDutyCycle in interface MotorController
      Returns:
      The duty cycle between -1 and 1 (sign indicates direction).
    • getVoltage

      public double 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

      public void setInverted(boolean isInverted)
      Description copied from interface: MotorController
      Sets the inversion state of the motor controller.
      Specified by:
      setInverted in interface MotorController
      Parameters:
      isInverted - The inversion state.
    • getInverted

      public boolean getInverted()
      Description copied from interface: MotorController
      Gets the inversion state of the motor controller.
      Specified by:
      getInverted in interface MotorController
      Returns:
      The inversion state.
    • disable

      public void disable()
      Description copied from interface: MotorController
      Disables the motor controller.
      Specified by:
      disable in interface MotorController
    • stopMotor

      public void stopMotor()
      Description copied from class: MotorSafety
      Called to stop the motor when the timeout expires.
      Specified by:
      stopMotor in class MotorSafety
    • getDescription

      Description copied from class: MotorSafety
      Returns a description to print when an error occurs.
      Specified by:
      getDescription in class MotorSafety
      Returns:
      Description to print when an error occurs.
    • 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.
    • addFollower

      public void addFollower(PWMMotorController follower)
      Make the given PWM motor controller follow the output of this one.
      Parameters:
      follower - The motor controller follower.
    • initSendable

      public void initSendable(SendableBuilder builder)
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder