WPILibC++ 2023.4.3
AnalogGyroSim.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 <memory>
8
10
11namespace frc {
12
13class AnalogGyro;
14
15namespace sim {
16
17/**
18 * Class to control a simulated analog gyro.
19 */
21 public:
22 /**
23 * Constructs from an AnalogGyro object.
24 *
25 * @param gyro AnalogGyro to simulate
26 */
27 explicit AnalogGyroSim(const AnalogGyro& gyro);
28
29 /**
30 * Constructs from an analog input channel number.
31 *
32 * @param channel Channel number
33 */
34 explicit AnalogGyroSim(int channel);
35
36 /**
37 * Register a callback on the angle.
38 *
39 * @param callback the callback that will be called whenever the angle changes
40 * @param initialNotify if true, the callback will be run on the initial value
41 * @return the CallbackStore object associated with this callback
42 */
43 [[nodiscard]] std::unique_ptr<CallbackStore> RegisterAngleCallback(
44 NotifyCallback callback, bool initialNotify);
45
46 /**
47 * Get the current angle of the gyro.
48 *
49 * @return the angle measured by the gyro
50 */
51 double GetAngle() const;
52
53 /**
54 * Change the angle measured by the gyro.
55 *
56 * @param angle the new value
57 */
58 void SetAngle(double angle);
59
60 /**
61 * Register a callback on the rate.
62 *
63 * @param callback the callback that will be called whenever the rate changes
64 * @param initialNotify if true, the callback will be run on the initial value
65 * @return the CallbackStore object associated with this callback
66 */
67 [[nodiscard]] std::unique_ptr<CallbackStore> RegisterRateCallback(
68 NotifyCallback callback, bool initialNotify);
69
70 /**
71 * Get the rate of angle change on this gyro.
72 *
73 * @return the rate
74 */
75 double GetRate() const;
76
77 /**
78 * Change the rate of the gyro.
79 *
80 * @param rate the new rate
81 */
82 void SetRate(double rate);
83
84 /**
85 * Register a callback on whether the gyro is initialized.
86 *
87 * @param callback the callback that will be called whenever the gyro is
88 * initialized
89 * @param initialNotify if true, the callback will be run on the initial value
90 * @return the CallbackStore object associated with this callback
91 */
92 [[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
93 NotifyCallback callback, bool initialNotify);
94
95 /**
96 * Check if the gyro is initialized.
97 *
98 * @return true if initialized
99 */
100 bool GetInitialized() const;
101
102 /**
103 * Set whether this gyro is initialized.
104 *
105 * @param initialized the new value
106 */
107 void SetInitialized(bool initialized);
108
109 /**
110 * Reset all simulation data for this object.
111 */
112 void ResetData();
113
114 private:
115 int m_index;
116};
117} // namespace sim
118} // namespace frc
Use a rate gyro to return the robots heading relative to a starting position.
Definition: AnalogGyro.h:34
Class to control a simulated analog gyro.
Definition: AnalogGyroSim.h:20
bool GetInitialized() const
Check if the gyro is initialized.
void SetInitialized(bool initialized)
Set whether this gyro is initialized.
void SetRate(double rate)
Change the rate of the gyro.
void SetAngle(double angle)
Change the angle measured by the gyro.
void ResetData()
Reset all simulation data for this object.
double GetAngle() const
Get the current angle of the gyro.
std::unique_ptr< CallbackStore > RegisterRateCallback(NotifyCallback callback, bool initialNotify)
Register a callback on the rate.
double GetRate() const
Get the rate of angle change on this gyro.
AnalogGyroSim(const AnalogGyro &gyro)
Constructs from an AnalogGyro object.
std::unique_ptr< CallbackStore > RegisterInitializedCallback(NotifyCallback callback, bool initialNotify)
Register a callback on whether the gyro is initialized.
AnalogGyroSim(int channel)
Constructs from an analog input channel number.
std::unique_ptr< CallbackStore > RegisterAngleCallback(NotifyCallback callback, bool initialNotify)
Register a callback on the angle.
std::function< void(std::string_view, const HAL_Value *)> NotifyCallback
Definition: CallbackStore.h:14
Definition: AprilTagFieldLayout.h:22