public class ServoImplEx extends ServoImpl implements ServoEx
ServoEx.ServoPwmRangeServo.DirectionHardwareDevice.Manufacturer| Modifier and Type | Field and Description |
|---|---|
protected ServoControllerEx |
controllerEx |
controller, direction, limitPositionMax, limitPositionMin, portNumberMAX_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, setPositionprotected ServoControllerEx controllerEx
public ServoImplEx(ServoController controller, int portNumber)
public ServoImplEx(ServoController controller, int portNumber, Servo.Direction direction)
public void setPwmRange(ServoEx.ServoPwmRange range)
ServoExsetPwmRange in interface ServoExrange - the new PWM range limits for the servoServoEx.getPwmRange()public ServoEx.ServoPwmRange getPwmRange()
ServoExgetPwmRange in interface ServoExServoEx.setPwmRange(ServoPwmRange)public void setPwmEnable()
ServoExsetPwmEnable in interface ServoExServoEx.setPwmDisable(),
ServoEx.isPwmEnabled()public void setPwmDisable()
ServoExsetPwmDisable in interface ServoExServoEx.setPwmEnable()public boolean isPwmEnabled()
ServoExisPwmEnabled in interface ServoExServoEx.setPwmEnable()