public interface PwmControl
PwmControl
interface provides control of the width of pulses used and whether
the PWM is enabled or disabled.
PWM is commonly used to control servos. PwmControl
is thus found as a second
interface on servo objects whose primary interface is Servo
or CRServo
when the underlying servo controller hardware supports this fine-grained control (not all
servo controllers provide such control). To access the PwmControl
interface,
cast your Servo
or CRServo
object to PwmControl
; however, it is
usually prudent to first test whether the cast will succeed by testing using
instanceof.
DcMotorEx
,
Pulse-width modulationModifier and Type | Interface and Description |
---|---|
static class |
PwmControl.PwmRange
PwmRange instances are used to specify the upper and lower pulse widths
and overall framing rate for a servo.
|
Modifier and Type | Method and Description |
---|---|
PwmControl.PwmRange |
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(PwmControl.PwmRange range)
Sets the PWM range limits for the servo
|
void setPwmRange(PwmControl.PwmRange range)
range
- the new PWM range limits for the servogetPwmRange()
PwmControl.PwmRange getPwmRange()
setPwmRange(PwmRange)
void setPwmEnable()
setPwmDisable()
,
isPwmEnabled()
void setPwmDisable()
setPwmEnable()
boolean isPwmEnabled()
setPwmEnable()