WPILibC++ 2023.4.3-108-ge5452e3
|
Standard hobby style servo. More...
#include <frc/Servo.h>
Public Member Functions | |
Servo (int channel) | |
Servo (Servo &&)=default | |
Servo & | operator= (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 | |
PWM & | operator= (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) | |
SendableHelper & | operator= (const SendableHelper &rhs)=default |
SendableHelper & | operator= (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 () | |
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.
|
explicit |
channel | The PWM channel to which the servo is attached. 0-9 are on-board, 10-19 are on the MXP port |
|
default |
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.
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.
double frc::Servo::GetMaxAngle | ( | ) | const |
Get the maximum angle of the servo.
double frc::Servo::GetMinAngle | ( | ) | const |
Get the minimum angle of the servo.
|
overridevirtual |
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.
value | Position from 0.0 to 1.0. |
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.
angle | The angle in degrees to set the servo. |
void frc::Servo::SetOffline | ( | ) |
Set the servo to offline.
Set the servo raw value to 0 (undriven)