Class MotorControllerGroup
java.lang.Object
edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup
- All Implemented Interfaces:
Sendable
,MotorController
,AutoCloseable
public class MotorControllerGroup extends Object implements MotorController, Sendable, AutoCloseable
Allows multiple
MotorController
objects to be linked together.-
Constructor Summary
Constructors Constructor Description MotorControllerGroup(MotorController[] motorControllers)
MotorControllerGroup(MotorController motorController, MotorController... motorControllers)
Create a new MotorControllerGroup with the provided MotorControllers. -
Method Summary
Modifier and Type Method Description void
close()
void
disable()
Disable the motor controller.double
get()
Common interface for getting the current set speed of a motor controller.boolean
getInverted()
Common interface for returning if a motor controller is in the inverted state or not.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.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.void
setVoltage(double outputVolts)
Sets the voltage output of the MotorController.void
stopMotor()
Stops motor movement.
-
Constructor Details
-
MotorControllerGroup
Create a new MotorControllerGroup with the provided MotorControllers.- Parameters:
motorController
- The first MotorController to addmotorControllers
- The MotorControllers to add
-
MotorControllerGroup
-
-
Method Details
-
close
- Specified by:
close
in interfaceAutoCloseable
-
set
Description copied from interface:MotorController
Common interface for setting the speed of a motor controller.- Specified by:
set
in interfaceMotorController
- Parameters:
speed
- The speed to set. Value should be between -1.0 and 1.0.
-
setVoltage
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 interfaceMotorController
- Parameters:
outputVolts
- The voltage to output.
-
get
Description copied from interface:MotorController
Common interface for getting the current set speed of a motor controller.- Specified by:
get
in interfaceMotorController
- Returns:
- The current set speed. Value is between -1.0 and 1.0.
-
setInverted
Description copied from interface:MotorController
Common interface for inverting direction of a motor controller.- Specified by:
setInverted
in interfaceMotorController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
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 interfaceMotorController
- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
Description copied from interface:MotorController
Disable the motor controller.- Specified by:
disable
in interfaceMotorController
-
stopMotor
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 interfaceMotorController
-
initSendable
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-