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.
Allows multiple
MotorController objects to be linked together.-
Constructor Summary
ConstructorsConstructorDescriptionMotorControllerGroup(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 TypeMethodDescriptionvoidclose()Deprecated, for removal: This API element is subject to removal in a future version.voiddisable()Deprecated, for removal: This API element is subject to removal in a future version.Disable the motor controller.doubleget()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.booleanDeprecated, 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.voidinitSendable(SendableBuilder builder) Deprecated, for removal: This API element is subject to removal in a future version.Initializes thisSendableobject.voidset(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.voidsetInverted(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.voidsetVoltage(double outputVolts) Deprecated, for removal: This API element is subject to removal in a future version.Sets the voltage output of the MotorController.voidDeprecated, 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, waitMethods inherited from interface edu.wpi.first.wpilibj.motorcontrol.MotorController
setVoltage
-
Constructor Details
-
MotorControllerGroup
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 addmotorControllers- The MotorControllers to add
-
MotorControllerGroup
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
Deprecated, for removal: This API element is subject to removal in a future version.- Specified by:
closein interfaceAutoCloseable
-
set
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerCommon interface for setting the speed of a motor controller.- Specified by:
setin interfaceMotorController- Parameters:
speed- The speed to set. Value should be between -1.0 and 1.0.
-
setVoltage
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerSets 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:
setVoltagein interfaceMotorController- Parameters:
outputVolts- The voltage to output, in Volts.
-
get
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerCommon interface for getting the current set speed of a motor controller.- Specified by:
getin interfaceMotorController- Returns:
- The current set speed. Value is between -1.0 and 1.0.
-
setInverted
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerCommon interface for inverting direction of a motor controller.- Specified by:
setInvertedin interfaceMotorController- Parameters:
isInverted- The state of inversion true is inverted.
-
getInverted
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerCommon interface for returning if a motor controller is in the inverted state or not.- Specified by:
getInvertedin interfaceMotorController- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerDisable the motor controller.- Specified by:
disablein interfaceMotorController
-
stopMotor
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:MotorControllerStops motor movement. Motor can be moved again by calling set without having to re-enable the motor.- Specified by:
stopMotorin interfaceMotorController
-
initSendable
Deprecated, for removal: This API element is subject to removal in a future version.Description copied from interface:SendableInitializes thisSendableobject.- Specified by:
initSendablein interfaceSendable- Parameters:
builder- sendable builder
-
PWMMotorController.addFollower(PWMMotorController)or if using CAN motor controllers, use their method of following.