Class TetrixServo
- java.lang.Object
-
- lejos.hardware.device.tetrix.TetrixServo
-
- All Implemented Interfaces:
Servo
public class TetrixServo extends java.lang.Object implements Servo
Basic servo motor abstraction. Servos are driven by a PWM signal from the controller with varying pulse widths controlling the rotational position of the servo actuator shaft.The HiTechnic Servo Controller allows setting of the PWM output from 0.75 - 2.25ms. Note that some servos may hit their internal mechanical limits at each end of this range causing them to consume excessive current and potentially be damaged.
- Author:
- Kirk P. Thompson
-
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description floatgetAngle()Returns the current servo angle as reverse calculated by the last call tosetAngle().intgetpulseWidth()Get the current PWM pulse width for the servo.voidsetAngle(float angle)Sets the angle target of the servo.voidsetpulseWidth(int microSeconds)Set the PWM pulse width for the servo.voidsetRange(int microsecLOW, int microsecHIGH, int travelRange)Set the allowable pulse width operating range of this servo in microseconds and the total travel range.
-
-
-
Method Detail
-
setRange
public void setRange(int microsecLOW, int microsecHIGH, int travelRange) throws java.lang.IllegalArgumentExceptionSet the allowable pulse width operating range of this servo in microseconds and the total travel range. Default for pulse width at instantiation is 750 & 2250 microseconds. Default for travel is 200 degrees.The midpoint of the pulse width operating range should normally be 1500 microseconds so the range extents should reflect this.
This information must reflect the appropriate specifications and/or empirical characterization data of the specific servo used for the
setAngle()method to be able to position the servo accurately.- Specified by:
setRangein interfaceServo- Parameters:
microsecLOW- The low end of the servos response/operating range in microsecondsmicrosecHIGH- The high end of the servos response/operating range in microsecondstravelRange- The total mechanical travel range of the servo in degrees- Throws:
java.lang.IllegalArgumentException- if the range isn't within 750 and 2250- See Also:
setAngle(float)
-
setAngle
public void setAngle(float angle)
Sets the angle target of the servo. The positional accuracy of this method requires thatsetRange()be called with the correct parameters to establish proper ranging conversion to internal controller representation of servo position.- Specified by:
setAnglein interfaceServo- Parameters:
angle- Set servo angle in degrees.- See Also:
setRange(int, int, int),getAngle()
-
getAngle
public float getAngle()
Returns the current servo angle as reverse calculated by the last call tosetAngle(). This is calculated from the internal byte representation used (calculated bysetAngle()) to control the servo so the resolution will be affected by ranging factors set withsetRange()The actual physical servo position may or may not be at the reported angle if mechanical limits have been reached.
- Specified by:
getAnglein interfaceServo- Returns:
- Current servo angle
- See Also:
setRange(int, int, int),setAngle(float)
-
setpulseWidth
public void setpulseWidth(int microSeconds) throws java.lang.IllegalArgumentExceptionSet the PWM pulse width for the servo. This must be in the range defined for the servo. This method allows manipulation of the servo position based on absolute pulse widths in microseconds.A servo pulse of 1500 microseconds (1.5 ms) width will typically set the servo to its "neutral" position. This is the "standard pulse servo mode" used by all hobby analog servos.
The HiTechic Servo Controller allows setting of the PWM output from 750 to 2250 microseconds with a step resolution of 5.88 microseconds (1 byte is used to control the pulse width output) and this method will calculate and use the stepped value closest to value passed in
microSeconds.Note that some servos may hit their internal mechanical limits at each end of this range causing them to consume excessive current and potentially be damaged.
- Specified by:
setpulseWidthin interfaceServo- Parameters:
microSeconds- The pulse width time in microseconds- Throws:
java.lang.IllegalArgumentException- if the range isn't within 750 and 2250- See Also:
setRange(int, int, int)
-
getpulseWidth
public int getpulseWidth()
Description copied from interface:ServoGet the current PWM pulse width for the servo.- Specified by:
getpulseWidthin interfaceServo- Returns:
- The pulse width time in microseconds
-
-