WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
frc::Servo Class Reference

Standard hobby style servo. More...

#include <frc/Servo.h>

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

Public Member Functions

 Servo (int channel)
 Constructor.
 
 Servo (Servo &&)=default
 
Servooperator= (Servo &&)=default
 
void Set (double value)
 Set the servo position.
 
double Get () const
 Get the servo position.
 
void SetAngle (double angle)
 Set the servo angle.
 
double GetAngle () const
 Get the servo angle.
 
int GetChannel () const
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object.
 
- Public Member Functions inherited from wpi::Sendable
virtual constexpr ~Sendable ()=default
 
- Public Member Functions inherited from wpi::SendableHelper< Servo >
constexpr SendableHelper (const SendableHelper &rhs)=default
 
constexpr SendableHelper (SendableHelper &&rhs)
 
constexpr SendableHelperoperator= (const SendableHelper &rhs)=default
 
constexpr SendableHelperoperator= (SendableHelper &&rhs)
 

Friends

class frc::sim::ServoSim
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< Servo >
constexpr SendableHelper ()=default
 
constexpr ~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

Constructor.

By default, 2.4 ms is used as the max PWM value and 0.6 ms is used as the min PWM value.

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.

◆ GetChannel()

int frc::Servo::GetChannel ( ) const

◆ InitSendable()

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

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ 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.

Friends And Related Symbol Documentation

◆ frc::sim::ServoSim

friend class frc::sim::ServoSim
friend

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