Servo

public final class Servo implements Component

A wrapper for the Servo object in the FTC SDK.

Parameters

servo

the servo for this wrapper to use

range

the range of the servo

Constructors

Link copied to clipboard
public Servo Servo(HardwareMap hMap, String id, Angle range, NanoClock clock)
public Servo Servo(HardwareMap hMap, String id, Angle range)
public Servo Servo(HardwareMap hMap, String id)
public Servo Servo(Servo servo, Angle range, NanoClock clock)
public Servo Servo(Servo servo, Angle range)
public Servo Servo(Servo servo)

Properties

Link copied to clipboard
private Angle angle

Angular representation of the servo's position in the range [0.0, range]. Setting the angle sets position and vice versa. Note that the angle of the servo is independent of scaleRange, but the available angle range is not.

Link copied to clipboard

The currently available movement range of the servo. Affected by scaleRange.

Link copied to clipboard
private final Pair<Double, Double> currentRange

The currently available movement range of the servo. Affected by scaleRange.

Link copied to clipboard
public final Servo internal
Link copied to clipboard
private Double position

The position of this servo in the range [0.0, 1.0].

Link copied to clipboard
public final Angle range
Link copied to clipboard
private Boolean reversed

Whether this servo is reversed.

Functions

Link copied to clipboard
public final Angle getAngle()
Link copied to clipboard

The currently available movement range of the servo. Affected by scaleRange.

Link copied to clipboard
public final Pair<Double, Double> getCurrentRange()

The currently available movement range of the servo. Affected by scaleRange.

Link copied to clipboard
public final Double getPosition()

The position of this servo in the range [0.0, 1.0].

Link copied to clipboard
public final Command goToAngle(Angle angle, Angle speed)

Returns a command that uses range and speed (specified in units per second) to go to the specified angle at the desired speed. Note that since there is no feedback from the servo, it may or may not actually achieve the desired speed.

public final Command goToAngle(Angle angle, Double speed)

Returns a command that goes to the specified angle at the desired speed. Note that since there is no feedback from the servo, it may or may not actually achieve the desired speed.

Link copied to clipboard
public final Command goToPosition(Double position, Angle speed)

Returns a command that uses range and speed (specified in units per second) to go to the specified position at the desired speed by slowly incrementing the position. Note that since there is no feedback from the servo, it may or may not actually achieve the desired speed.

public final Command goToPosition(Double position, Double speed)

Returns a command that goes to the specified position at the desired speed. Note that since there is no feedback from the servo, it may or may not actually achieve the desired speed.

Link copied to clipboard
public final Boolean isReversed()
Link copied to clipboard
public final Unit scaleRange(Angle min, Angle max)

Scales the available movement range of the servo to be a subset of its maximum range. Subsequent positioning calls will operate within that subset range. This is useful if your servo has only a limited useful range of movement due to the physical hardware that it is manipulating (as is often the case) but you don't want to have to manually adjust the input to position each time. For example, if the range of the servo is 180°, and scaleRange(30°, 90°) is set; then servo positions will be clamped to fit in that range:

public final Unit scaleRange(Double min, Double max)

Scales the available movement range of the servo to be a subset of its maximum range. Subsequent positioning calls will operate within that subset range. This is useful if your servo has only a limited useful range of movement due to the physical hardware that it is manipulating (as is often the case) but you don't want to have to manually scale and adjust the input to position each time. For example, if scaleRange(0.2, 0.8) is set; then servo positions will be scaled to fit in that range:

Link copied to clipboard
public final Unit setAngle(Angle angle)
Link copied to clipboard
public final Unit setPosition(Double position)
Link copied to clipboard
public final Servo setReversed(Boolean reversed)
Link copied to clipboard
public final Command waitForAngle(Angle angle, Angle speed)

Returns a command that uses range and speed (specified in units per second) to estimate when the servo will reach the specified angle, and waits until that point.

public final Command waitForAngle(Angle angle, Double speed)

Returns a command that uses speed to estimate when the servo will reach the specified angle, and waits until that point.

Link copied to clipboard
public final Command waitForPosition(Double position, Angle speed)

Returns a command that uses range and speed (specified in units per second) to estimate when the servo will reach the specified position, and waits until that point.

public final Command waitForPosition(Double position, Double speed)

Returns a command that uses speed to estimate when the servo will reach the specified position, and waits until that point.