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 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
    • 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 interface MotorController
      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, use PWM.getSpeed() instead.
      Specified by:
      get in interface MotorController
      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 interface MotorController
      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 interface MotorController
      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 interface MotorController
    • stopMotor

      public void stopMotor()
      Description copied from class: MotorSafety
      Called to stop the motor when the timeout expires.
      Specified by:
      stopMotor in interface MotorController
      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