WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
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 <hal/SimDevice.h>
8#include <units/angle.h>
9
10#include "frc/PWM.h"
11
12namespace frc {
13
14namespace sim {
15class ServoSim;
16} // namespace sim
17
18/**
19 * Standard hobby style servo.
20 *
21 * The range parameters default to the appropriate values for the Hitec HS-322HD
22 * servo provided in the FIRST Kit of Parts in 2008.
23 */
24class Servo : public wpi::Sendable, public wpi::SendableHelper<Servo> {
25 public:
26 friend class frc::sim::ServoSim;
27
28 /**
29 * Constructor.
30 *
31 * By default, 2.4 ms is used as the max PWM value and 0.6 ms is used as the
32 * min PWM value.
33 *
34 * @param channel The PWM channel to which the servo is attached. 0-9 are
35 * on-board, 10-19 are on the MXP port
36 */
37 explicit Servo(int channel);
38
39 Servo(Servo&&) = default;
40 Servo& operator=(Servo&&) = default;
41
42 /**
43 * Set the servo position.
44 *
45 * Servo values range from 0.0 to 1.0 corresponding to the range of full left
46 * to full right.
47 *
48 * @param value Position from 0.0 to 1.0.
49 */
50 void Set(double value);
51
52 /**
53 * Get the servo position.
54 *
55 * Servo values range from 0.0 to 1.0 corresponding to the range of full left
56 * to full right. This returns the commanded position, not the position that
57 * the servo is actually at, as the servo does not report its own position.
58 *
59 * @return Position from 0.0 to 1.0.
60 */
61 double Get() const;
62
63 /**
64 * Set the servo angle.
65 *
66 * The angles are based on the HS-322HD Servo, and have a range of 0 to 180
67 * degrees.
68 *
69 * Servo angles that are out of the supported range of the servo simply
70 * "saturate" in that direction. In other words, if the servo has a range of
71 * (X degrees to Y degrees) than angles of less than X result in an angle of
72 * X being set and angles of more than Y degrees result in an angle of Y being
73 * set.
74 *
75 * @param angle The angle in degrees to set the servo.
76 */
77 void SetAngle(double angle);
78
79 /**
80 * Get the servo angle.
81 *
82 * This returns the commanded angle, not the angle that the servo is actually
83 * at, as the servo does not report its own angle.
84 *
85 * @return The angle in degrees to which the servo is set.
86 */
87 double GetAngle() const;
88
89 int GetChannel() const;
90
91 void InitSendable(wpi::SendableBuilder& builder) override;
92
93 private:
94 static double GetServoAngleRange();
95 units::microsecond_t GetFullRangeScaleFactor() const;
96
97 static constexpr double kMaxServoAngle = 180.0;
98 static constexpr double kMinServoAngle = 0.0;
99
100 static constexpr units::millisecond_t kDefaultMaxServoPWM = 2.4_ms;
101 static constexpr units::millisecond_t kDefaultMinServoPWM = 0.6_ms;
102
103 units::millisecond_t m_maxPwm = kDefaultMaxServoPWM;
104 units::millisecond_t m_minPwm = kDefaultMinServoPWM;
105
106 hal::SimDevice m_simDevice;
107 hal::SimDouble m_simPosition;
108
109 PWM m_pwm;
110};
111
112} // namespace frc
Class implements the PWM generation in the FPGA.
Definition PWM.h:26
Standard hobby style servo.
Definition Servo.h:24
int GetChannel() const
Servo(int channel)
Constructor.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
double Get() const
Get the servo position.
Servo & operator=(Servo &&)=default
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 ServoSim.h:17
A move-only C++ wrapper around a HAL simulator device handle.
Definition SimDevice.h:645
C++ wrapper around a HAL simulator double value handle.
Definition SimDevice.h:536
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.h:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.h:21
Interface for Sendable objects.
Definition Sendable.h:16
Definition SystemServer.h:9