Package edu.wpi.first.wpilibj
Class SpeedControllerGroup
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.SpeedControllerGroup
-
- All Implemented Interfaces:
PIDOutput
,Sendable
,SpeedController
,AutoCloseable
public class SpeedControllerGroup extends SendableBase implements SpeedController
Allows multipleSpeedController
objects to be linked together.
-
-
Constructor Summary
Constructors Constructor Description SpeedControllerGroup(SpeedController speedController, SpeedController... speedControllers)
Create a new SpeedControllerGroup with the provided SpeedControllers.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description void
disable()
Disable the speed controller.double
get()
Common interface for getting the current set speed of a speed controller.boolean
getInverted()
Common interface for returning if a speed controller is in the inverted state or not.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
pidWrite(double output)
Set the output to the value calculated by PIDController.void
set(double speed)
Common interface for setting the speed of a speed controller.void
setInverted(boolean isInverted)
Common interface for inverting direction of a speed controller.void
stopMotor()
Stops motor movement.-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, close, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
SpeedControllerGroup
public SpeedControllerGroup(SpeedController speedController, SpeedController... speedControllers)
Create a new SpeedControllerGroup with the provided SpeedControllers.- Parameters:
speedControllers
- The SpeedControllers to add
-
-
Method Detail
-
set
public void set(double speed)
Description copied from interface:SpeedController
Common interface for setting the speed of a speed controller.- Specified by:
set
in interfaceSpeedController
- Parameters:
speed
- The speed to set. Value should be between -1.0 and 1.0.
-
get
public double get()
Description copied from interface:SpeedController
Common interface for getting the current set speed of a speed controller.- Specified by:
get
in interfaceSpeedController
- Returns:
- The current set speed. Value is between -1.0 and 1.0.
-
setInverted
public void setInverted(boolean isInverted)
Description copied from interface:SpeedController
Common interface for inverting direction of a speed controller.- Specified by:
setInverted
in interfaceSpeedController
- Parameters:
isInverted
- The state of inversion true is inverted.
-
getInverted
public boolean getInverted()
Description copied from interface:SpeedController
Common interface for returning if a speed controller is in the inverted state or not.- Specified by:
getInverted
in interfaceSpeedController
- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
public void disable()
Description copied from interface:SpeedController
Disable the speed controller.- Specified by:
disable
in interfaceSpeedController
-
stopMotor
public void stopMotor()
Description copied from interface:SpeedController
Stops motor movement. Motor can be moved again by calling set without having to re-enable the motor.- Specified by:
stopMotor
in interfaceSpeedController
-
pidWrite
public void pidWrite(double output)
Description copied from interface:PIDOutput
Set the output to the value calculated by PIDController.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-