Package edu.wpi.first.wpilibj
Interface SpeedController
-
- All Superinterfaces:
PIDOutput
- All Known Implementing Classes:
DMC60,Jaguar,NidecBrushless,PWMSpeedController,PWMTalonSRX,PWMVictorSPX,SD540,Spark,SpeedControllerGroup,Talon,Victor,VictorSP
public interface SpeedController extends PIDOutput
Interface for speed controlling devices.
-
-
Method Summary
All Methods Instance Methods Abstract Methods Modifier and Type Method Description voiddisable()Disable the speed controller.doubleget()Common interface for getting the current set speed of a speed controller.booleangetInverted()Common interface for returning if a speed controller is in the inverted state or not.voidset(double speed)Common interface for setting the speed of a speed controller.voidsetInverted(boolean isInverted)Common interface for inverting direction of a speed controller.voidstopMotor()Stops motor movement.
-
-
-
Method Detail
-
set
void set(double speed)
Common interface for setting the speed of a speed controller.- Parameters:
speed- The speed to set. Value should be between -1.0 and 1.0.
-
get
double get()
Common interface for getting the current set speed of a speed controller.- Returns:
- The current set speed. Value is between -1.0 and 1.0.
-
setInverted
void setInverted(boolean isInverted)
Common interface for inverting direction of a speed controller.- Parameters:
isInverted- The state of inversion true is inverted.
-
getInverted
boolean getInverted()
Common interface for returning if a speed controller is in the inverted state or not.- Returns:
- isInverted The state of the inversion true is inverted.
-
disable
void disable()
Disable the speed controller.
-
stopMotor
void stopMotor()
Stops motor movement. Motor can be moved again by calling set without having to re-enable the motor.
-
-