WPILibC++ 2023.4.3-108-ge5452e3
frc::Servo Class Reference

Standard hobby style servo. More...

#include <frc/Servo.h>

Inheritance diagram for frc::Servo:
frc::PWM wpi::Sendable wpi::SendableHelper< PWM >

Public Member Functions

 Servo (int channel)
 
 Servo (Servo &&)=default
 
Servooperator= (Servo &&)=default
 
void Set (double value)
 Set the servo position. More...
 
void SetOffline ()
 Set the servo to offline. More...
 
double Get () const
 Get the servo position. More...
 
void SetAngle (double angle)
 Set the servo angle. More...
 
double GetAngle () const
 Get the servo angle. More...
 
double GetMaxAngle () const
 Get the maximum angle of the servo. More...
 
double GetMinAngle () const
 Get the minimum angle of the servo. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from frc::PWM
 PWM (int channel, bool registerSendable=true)
 Allocate a PWM given a channel number. More...
 
 ~PWM () override
 Free the PWM channel. More...
 
 PWM (PWM &&)=default
 
PWMoperator= (PWM &&)=default
 
virtual void SetPulseTime (units::microsecond_t time)
 Set the PWM pulse time directly to the hardware. More...
 
virtual units::microsecond_t GetPulseTime () const
 Get the PWM pulse time directly from the hardware. More...
 
virtual void SetPosition (double pos)
 Set the PWM value based on a position. More...
 
virtual double GetPosition () const
 Get the PWM value in terms of a position. More...
 
virtual void SetSpeed (double speed)
 Set the PWM value based on a speed. More...
 
virtual double GetSpeed () const
 Get the PWM value in terms of speed. More...
 
virtual void SetDisabled ()
 Temporarily disables the PWM output. More...
 
void SetPeriodMultiplier (PeriodMultiplier mult)
 Slow down the PWM signal for old devices. More...
 
void SetZeroLatch ()
 
void EnableDeadbandElimination (bool eliminateDeadband)
 Optionally eliminate the deadband from a motor controller. More...
 
void SetBounds (units::microsecond_t max, units::microsecond_t deadbandMax, units::microsecond_t center, units::microsecond_t deadbandMin, units::microsecond_t min)
 Set the bounds on the PWM pulse widths. More...
 
void GetBounds (units::microsecond_t *max, units::microsecond_t *deadbandMax, units::microsecond_t *center, units::microsecond_t *deadbandMin, units::microsecond_t *min)
 Get the bounds on the PWM values. More...
 
void SetAlwaysHighMode ()
 Sets the PWM output to be a continuous high signal while enabled. More...
 
int GetChannel () const
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< PWM >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Public Types inherited from frc::PWM
enum  PeriodMultiplier { kPeriodMultiplier_1X = 1 , kPeriodMultiplier_2X = 2 , kPeriodMultiplier_4X = 4 }
 Represents the amount to multiply the minimum servo-pulse pwm period by. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Protected Member Functions inherited from wpi::SendableHelper< PWM >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ Servo() [1/2]

frc::Servo::Servo ( int  channel)
explicit
Parameters
channelThe PWM channel to which the servo is attached. 0-9 are on-board, 10-19 are on the MXP port

◆ Servo() [2/2]

frc::Servo::Servo ( Servo &&  )
default

Member Function Documentation

◆ Get()

double frc::Servo::Get ( ) const

Get the servo position.

Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right. This returns the commanded position, not the position that the servo is actually at, as the servo does not report its own position.

Returns
Position from 0.0 to 1.0.

◆ GetAngle()

double frc::Servo::GetAngle ( ) const

Get the servo angle.

This returns the commanded angle, not the angle that the servo is actually at, as the servo does not report its own angle.

Returns
The angle in degrees to which the servo is set.

◆ GetMaxAngle()

double frc::Servo::GetMaxAngle ( ) const

Get the maximum angle of the servo.

Returns
The maximum angle of the servo in degrees.

◆ GetMinAngle()

double frc::Servo::GetMinAngle ( ) const

Get the minimum angle of the servo.

Returns
The minimum angle of the servo in degrees.

◆ InitSendable()

void frc::Servo::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Reimplemented from frc::PWM.

◆ operator=()

Servo & frc::Servo::operator= ( Servo &&  )
default

◆ Set()

void frc::Servo::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
valuePosition from 0.0 to 1.0.

◆ SetAngle()

void frc::Servo::SetAngle ( double  angle)

Set the servo angle.

The angles are based on the HS-322HD Servo, and have a range of 0 to 180 degrees.

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
angleThe angle in degrees to set the servo.

◆ SetOffline()

void frc::Servo::SetOffline ( )

Set the servo to offline.

Set the servo raw value to 0 (undriven)


The documentation for this class was generated from the following file: