WPILibC++ 2023.4.3-108-ge5452e3
Servo.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <units/angle.h>
8
9#include "frc/PWM.h"
10
11namespace frc {
12
13/**
14 * Standard hobby style servo.
15 *
16 * The range parameters default to the appropriate values for the Hitec HS-322HD
17 * servo provided in the FIRST Kit of Parts in 2008.
18 */
19class Servo : public PWM {
20 public:
21 /**
22 * @param channel The PWM channel to which the servo is attached. 0-9 are
23 * on-board, 10-19 are on the MXP port
24 */
25 explicit Servo(int channel);
26
27 Servo(Servo&&) = default;
28 Servo& operator=(Servo&&) = default;
29
30 /**
31 * Set the servo position.
32 *
33 * Servo values range from 0.0 to 1.0 corresponding to the range of full left
34 * to full right.
35 *
36 * @param value Position from 0.0 to 1.0.
37 */
38 void Set(double value);
39
40 /**
41 * Set the servo to offline.
42 *
43 * Set the servo raw value to 0 (undriven)
44 */
45 void SetOffline();
46
47 /**
48 * Get the servo position.
49 *
50 * Servo values range from 0.0 to 1.0 corresponding to the range of full left
51 * to full right. This returns the commanded position, not the position that
52 * the servo is actually at, as the servo does not report its own position.
53 *
54 * @return Position from 0.0 to 1.0.
55 */
56 double Get() const;
57
58 /**
59 * Set the servo angle.
60 *
61 * The angles are based on the HS-322HD Servo, and have a range of 0 to 180
62 * degrees.
63 *
64 * Servo angles that are out of the supported range of the servo simply
65 * "saturate" in that direction. In other words, if the servo has a range of
66 * (X degrees to Y degrees) than angles of less than X result in an angle of
67 * X being set and angles of more than Y degrees result in an angle of Y being
68 * set.
69 *
70 * @param angle The angle in degrees to set the servo.
71 */
72 void SetAngle(double angle);
73
74 /**
75 * Get the servo angle.
76 *
77 * This returns the commanded angle, not the angle that the servo is actually
78 * at, as the servo does not report its own angle.
79 *
80 * @return The angle in degrees to which the servo is set.
81 */
82 double GetAngle() const;
83
84 /**
85 * Get the maximum angle of the servo.
86 *
87 * @return The maximum angle of the servo in degrees.
88 */
89 double GetMaxAngle() const;
90
91 /**
92 * Get the minimum angle of the servo.
93 *
94 * @return The minimum angle of the servo in degrees.
95 */
96 double GetMinAngle() const;
97
98 void InitSendable(wpi::SendableBuilder& builder) override;
99
100 private:
101 double GetServoAngleRange() const;
102
103 static constexpr double kMaxServoAngle = 180.;
104 static constexpr double kMinServoAngle = 0.0;
105
106 static constexpr units::millisecond_t kDefaultMaxServoPWM = 2.4_ms;
107 static constexpr units::millisecond_t kDefaultMinServoPWM = 0.6_ms;
108};
109
110} // namespace frc
Class implements the PWM generation in the FPGA.
Definition: PWM.h:26
Standard hobby style servo.
Definition: Servo.h:19
Servo(int channel)
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
double Get() const
Get the servo position.
double GetMaxAngle() const
Get the maximum angle of the servo.
Servo & operator=(Servo &&)=default
void SetOffline()
Set the servo to offline.
double GetMinAngle() const
Get the minimum angle of the servo.
double GetAngle() const
Get the servo angle.
void Set(double value)
Set the servo position.
void SetAngle(double angle)
Set the servo angle.
Servo(Servo &&)=default
Definition: core.h:1240
Definition: SendableBuilder.h:18
Definition: AprilTagPoseEstimator.h:15