Class Servo
- java.lang.Object
-
- edu.wpi.first.wpilibj.MotorSafety
-
- edu.wpi.first.wpilibj.PWM
-
- edu.wpi.first.wpilibj.Servo
-
- All Implemented Interfaces:
Sendable
,AutoCloseable
public class Servo extends PWM
Standard hobby style servo.The range parameters default to the appropriate values for the Hitec HS-322HD servo provided in the FIRST Kit of Parts in 2008.
-
-
Nested Class Summary
-
Nested classes/interfaces inherited from class edu.wpi.first.wpilibj.PWM
PWM.PeriodMultiplier
-
-
Field Summary
Fields Modifier and Type Field Description protected static double
kDefaultMaxServoPWM
protected static double
kDefaultMinServoPWM
-
Constructor Summary
Constructors Constructor Description Servo(int channel)
Constructor.
-
Method Summary
All Methods Instance Methods Concrete Methods Modifier and Type Method Description double
get()
Get the servo position.double
getAngle()
Get the servo angle.void
initSendable(SendableBuilder builder)
Initializes thisSendable
object.void
set(double value)
Set the servo position.void
setAngle(double degrees)
Set the servo angle.-
Methods inherited from class edu.wpi.first.wpilibj.PWM
addChild, close, enableDeadbandElimination, getChannel, getDescription, getName, getPosition, getRaw, getRawBounds, getSpeed, getSubsystem, setBounds, setDisabled, setName, setName, setName, setPeriodMultiplier, setPosition, setRaw, setSpeed, setSubsystem, setZeroLatch, stopMotor
-
Methods inherited from class edu.wpi.first.wpilibj.MotorSafety
check, checkMotors, feed, getExpiration, isAlive, isSafetyEnabled, setExpiration, setSafetyEnabled
-
-
-
-
Field Detail
-
kDefaultMaxServoPWM
protected static final double kDefaultMaxServoPWM
- See Also:
- Constant Field Values
-
kDefaultMinServoPWM
protected static final double kDefaultMinServoPWM
- See Also:
- Constant Field Values
-
-
Method Detail
-
set
public void set(double value)
Set the servo position.Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
- Parameters:
value
- Position from 0.0 to 1.0.
-
get
public double get()
Get the servo position.Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
- Returns:
- Position from 0.0 to 1.0.
-
setAngle
public void setAngle(double degrees)
Set the servo angle.Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
Servo angles that are out of the supported range of the servo simply "saturate" in that direction In other words, if the servo has a range of (X degrees to Y degrees) than angles of less than X result in an angle of X being set and angles of more than Y degrees result in an angle of Y being set.
- Parameters:
degrees
- The angle in degrees to set the servo.
-
getAngle
public double getAngle()
Get the servo angle.Assume that the servo angle is linear with respect to the PWM value (big assumption, need to test).
- Returns:
- The angle in degrees to which the servo is set.
-
initSendable
public void initSendable(SendableBuilder builder)
Description copied from interface:Sendable
Initializes thisSendable
object.- Specified by:
initSendable
in interfaceSendable
- Overrides:
initSendable
in classPWM
- Parameters:
builder
- sendable builder
-
-