public class ServoImplEx extends ServoImpl implements ServoEx
ServoEx.ServoPwmRange
Servo.Direction
HardwareDevice.Manufacturer
Modifier and Type | Field and Description |
---|---|
protected ServoControllerEx |
controllerEx |
controller, direction, limitPositionMax, limitPositionMin, portNumber
MAX_POSITION, MIN_POSITION
Constructor and Description |
---|
ServoImplEx(ServoController controller,
int portNumber) |
ServoImplEx(ServoController controller,
int portNumber,
Servo.Direction direction) |
Modifier and Type | Method and Description |
---|---|
ServoEx.ServoPwmRange |
getPwmRange()
Returns the current PWM range limits for the servo
|
boolean |
isPwmEnabled()
Returns whether the PWM is energized for this particular servo
|
void |
setPwmDisable()
Individually denergizes the PWM for this particular servo
|
void |
setPwmEnable()
Individually energizes the PWM for this particular servo.
|
void |
setPwmRange(ServoEx.ServoPwmRange range)
Sets the PWM range limits for the servo
|
close, getConnectionInfo, getController, getDeviceName, getDirection, getManufacturer, getPortNumber, getPosition, getVersion, internalSetPosition, resetDeviceConfigurationForOpMode, scaleRange, setDirection, setPosition
protected ServoControllerEx controllerEx
public ServoImplEx(ServoController controller, int portNumber)
public ServoImplEx(ServoController controller, int portNumber, Servo.Direction direction)
public void setPwmRange(ServoEx.ServoPwmRange range)
ServoEx
setPwmRange
in interface ServoEx
range
- the new PWM range limits for the servoServoEx.getPwmRange()
public ServoEx.ServoPwmRange getPwmRange()
ServoEx
getPwmRange
in interface ServoEx
ServoEx.setPwmRange(ServoPwmRange)
public void setPwmEnable()
ServoEx
setPwmEnable
in interface ServoEx
ServoEx.setPwmDisable()
,
ServoEx.isPwmEnabled()
public void setPwmDisable()
ServoEx
setPwmDisable
in interface ServoEx
ServoEx.setPwmEnable()
public boolean isPwmEnabled()
ServoEx
isPwmEnabled
in interface ServoEx
ServoEx.setPwmEnable()