Package edu.wpi.first.wpilibj
Class SpeedControllerGroup
- java.lang.Object
-
- edu.wpi.first.wpilibj.SpeedControllerGroup
-
- All Implemented Interfaces:
Sendable
,MotorController
,SpeedController
,AutoCloseable
@Deprecated(since="2022", forRemoval=true) public class SpeedControllerGroup extends Object implements MotorController, Sendable, AutoCloseable
Deprecated, for removal: This API element is subject to removal in a future version.UseMotorControllerGroup
.Allows multipleSpeedController
objects to be linked together.
-
-
Constructor Summary
Constructors Constructor Description SpeedControllerGroup(SpeedController[] speedControllers)
Deprecated, for removal: This API element is subject to removal in a future version.SpeedControllerGroup(SpeedController speedController, SpeedController... speedControllers)
Deprecated, for removal: This API element is subject to removal in a future version.Create a new SpeedControllerGroup with the provided SpeedControllers.
-
Method Summary
All Methods Instance Methods Concrete Methods Deprecated Methods 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 thisSendable
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
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
-
Methods inherited from interface edu.wpi.first.wpilibj.motorcontrol.MotorController
setVoltage
-
-
-
-
Constructor Detail
-
SpeedControllerGroup
public SpeedControllerGroup(SpeedController speedController, SpeedController... speedControllers)
Deprecated, for removal: This API element is subject to removal in a future version.Create a new SpeedControllerGroup with the provided SpeedControllers.- Parameters:
speedController
- The first SpeedController to add.speedControllers
- The SpeedControllers to add
-
SpeedControllerGroup
public SpeedControllerGroup(SpeedController[] speedControllers)
Deprecated, for removal: This API element is subject to removal in a future version.
-
-
Method Detail
-
close
public void close()
Deprecated, for removal: This API element is subject to removal in a future version.- Specified by:
close
in interfaceAutoCloseable
-
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 interfaceMotorController
- Specified by:
set
in interfaceSpeedController
- Parameters:
speed
- The speed to set. Value should be between -1.0 and 1.0.
-
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 interfaceMotorController
- Specified by:
get
in interfaceSpeedController
- 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 interfaceMotorController
- Specified by:
setInverted
in interfaceSpeedController
- 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 interfaceMotorController
- Specified by:
getInverted
in interfaceSpeedController
- 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 interfaceMotorController
- Specified by:
disable
in interfaceSpeedController
-
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 interfaceMotorController
- Specified by:
stopMotor
in interfaceSpeedController
-
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 thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Parameters:
builder
- sendable builder
-
-