Class MotorControllerGroup

java.lang.Object
edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup
All Implemented Interfaces:
Sendable, MotorController, AutoCloseable

@Deprecated(forRemoval=true,
            since="2024")
public class MotorControllerGroup
extends Object
implements MotorController, Sendable, AutoCloseable
Deprecated, for removal: This API element is subject to removal in a future version.
Use PWMMotorController.addFollower(PWMMotorController) or if using CAN motor controllers, use their method of following.
Allows multiple MotorController objects to be linked together.
  • Constructor Summary

    Constructors 
    Constructor Description
    MotorControllerGroup​(MotorController[] motorControllers)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Create a new MotorControllerGroup with the provided MotorControllers.
    MotorControllerGroup​(MotorController motorController, MotorController... motorControllers)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Create a new MotorControllerGroup with the provided MotorControllers.
  • Method Summary

    Modifier and Type Method Description
    void close()
    Deprecated, for removal: This API element is subject to removal in a future version.
     
    void disable()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Disable the motor controller.
    double get()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Common interface for getting the current set speed of a motor controller.
    boolean getInverted()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Common interface for returning if a motor controller is in the inverted state or not.
    void initSendable​(SendableBuilder builder)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Initializes this Sendable object.
    void set​(double speed)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Common interface for setting the speed of a motor controller.
    void setInverted​(boolean isInverted)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Common interface for inverting direction of a motor controller.
    void setVoltage​(double outputVolts)
    Deprecated, for removal: This API element is subject to removal in a future version.
    Sets the voltage output of the MotorController.
    void stopMotor()
    Deprecated, for removal: This API element is subject to removal in a future version.
    Stops motor movement.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • MotorControllerGroup

      public MotorControllerGroup​(MotorController motorController, MotorController... motorControllers)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create a new MotorControllerGroup with the provided MotorControllers.
      Parameters:
      motorController - The first MotorController to add
      motorControllers - The MotorControllers to add
    • MotorControllerGroup

      public MotorControllerGroup​(MotorController[] motorControllers)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Create a new MotorControllerGroup with the provided MotorControllers.
      Parameters:
      motorControllers - The MotorControllers to add.
  • Method Details

    • close

      public void close()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Specified by:
      close in interface AutoCloseable
    • set

      public void set​(double speed)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: MotorController
      Common interface for setting the speed of a motor controller.
      Specified by:
      set in interface MotorController
      Parameters:
      speed - The speed to set. Value should be between -1.0 and 1.0.
    • setVoltage

      public void setVoltage​(double outputVolts)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: MotorController
      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."

      Specified by:
      setVoltage in interface MotorController
      Parameters:
      outputVolts - The voltage to output.
    • get

      public double get()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: MotorController
      Common interface for getting the current set speed of a motor controller.
      Specified by:
      get in interface MotorController
      Returns:
      The current set speed. Value is between -1.0 and 1.0.
    • setInverted

      public void setInverted​(boolean isInverted)
      Deprecated, for removal: This API element is subject to removal in a future version.
      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()
      Deprecated, for removal: This API element is subject to removal in a future version.
      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()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: MotorController
      Disable the motor controller.
      Specified by:
      disable in interface MotorController
    • stopMotor

      public void stopMotor()
      Deprecated, for removal: This API element is subject to removal in a future version.
      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 interface MotorController
    • initSendable

      public void initSendable​(SendableBuilder builder)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Description copied from interface: Sendable
      Initializes this Sendable object.
      Specified by:
      initSendable in interface Sendable
      Parameters:
      builder - sendable builder