Interface MotorController

All Known Implementing Classes:
DMC60, Jaguar, MotorControllerGroup, NidecBrushless, PWMMotorController, PWMSparkFlex, PWMSparkMax, PWMTalonFX, PWMTalonSRX, PWMVenom, PWMVictorSPX, SD540, Spark, Talon, Victor, VictorSP

public interface MotorController
Interface for motor controlling devices.
  • Method Summary

    Modifier and Type
    Method
    Description
    void
    Disable the motor controller.
    double
    get()
    Common interface for getting the current set speed of a motor controller.
    boolean
    Common interface for returning if a motor controller is in the inverted state or not.
    void
    set(double speed)
    Common interface for setting the speed of a motor controller.
    void
    setInverted(boolean isInverted)
    Common interface for inverting direction of a motor controller.
    default void
    setVoltage(double outputVolts)
    Sets the voltage output of the MotorController.
    void
    Stops motor movement.
  • Method Details

    • set

      void set(double speed)
      Common interface for setting the speed of a motor controller.
      Parameters:
      speed - The speed to set. Value should be between -1.0 and 1.0.
    • setVoltage

      default void setVoltage(double outputVolts)
      Sets the voltage output of the MotorController. Compensates for the current bus voltage to ensure that the desired voltage is output even if the battery voltage is below 12V - highly useful when the voltage outputs are "meaningful" (e.g. they come from a feedforward calculation).

      NOTE: This function *must* be called regularly in order for voltage compensation to work properly - unlike the ordinary set function, it is not "set it and forget it."

      Parameters:
      outputVolts - The voltage to output.
    • get

      double get()
      Common interface for getting the current set speed of a motor controller.
      Returns:
      The current set speed. Value is between -1.0 and 1.0.
    • setInverted

      void setInverted(boolean isInverted)
      Common interface for inverting direction of a motor controller.
      Parameters:
      isInverted - The state of inversion true is inverted.
    • getInverted

      boolean getInverted()
      Common interface for returning if a motor controller is in the inverted state or not.
      Returns:
      isInverted The state of the inversion true is inverted.
    • disable

      void disable()
      Disable the motor controller.
    • stopMotor

      void stopMotor()
      Stops motor movement. Motor can be moved again by calling set without having to re-enable the motor.