/
AnalogGyroSim.h
118 lines (99 loc) · 2.81 KB
/
AnalogGyroSim.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <memory>
#include "frc/simulation/CallbackStore.h"
namespace frc {
class AnalogGyro;
namespace sim {
/**
* Class to control a simulated analog gyro.
*/
class AnalogGyroSim {
public:
/**
* Constructs from an AnalogGyro object.
*
* @param gyro AnalogGyro to simulate
*/
explicit AnalogGyroSim(const AnalogGyro& gyro);
/**
* Constructs from an analog input channel number.
*
* @param channel Channel number
*/
explicit AnalogGyroSim(int channel);
/**
* Register a callback on the angle.
*
* @param callback the callback that will be called whenever the angle changes
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterAngleCallback(
NotifyCallback callback, bool initialNotify);
/**
* Get the current angle of the gyro.
*
* @return the angle measured by the gyro
*/
double GetAngle() const;
/**
* Change the angle measured by the gyro.
*
* @param angle the new value
*/
void SetAngle(double angle);
/**
* Register a callback on the rate.
*
* @param callback the callback that will be called whenever the rate changes
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterRateCallback(
NotifyCallback callback, bool initialNotify);
/**
* Get the rate of angle change on this gyro.
*
* @return the rate
*/
double GetRate() const;
/**
* Change the rate of the gyro.
*
* @param rate the new rate
*/
void SetRate(double rate);
/**
* Register a callback on whether the gyro is initialized.
*
* @param callback the callback that will be called whenever the gyro is
* initialized
* @param initialNotify if true, the callback will be run on the initial value
* @return the CallbackStore object associated with this callback
*/
[[nodiscard]] std::unique_ptr<CallbackStore> RegisterInitializedCallback(
NotifyCallback callback, bool initialNotify);
/**
* Check if the gyro is initialized.
*
* @return true if initialized
*/
bool GetInitialized() const;
/**
* Set whether this gyro is initialized.
*
* @param initialized the new value
*/
void SetInitialized(bool initialized);
/**
* Reset all simulation data for this object.
*/
void ResetData();
private:
int m_index;
};
} // namespace sim
} // namespace frc