-
Notifications
You must be signed in to change notification settings - Fork 9
/
Copy pathAHRS.h
201 lines (171 loc) · 5.36 KB
/
AHRS.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
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
/*
* AHRS.h
*
* Created on: Jul 30, 2015
* Author: Scott
*/
#ifndef SRC_AHRS_H_
#define SRC_AHRS_H_
#include "ITimestampedDataSubscriber.h"
#include <memory>
#include <string>
class IIOProvider;
class ContinuousAngleTracker;
class InertialDataIntegrator;
class OffsetTracker;
class AHRSInternal;
class AHRS{
public:
enum BoardAxis {
kBoardAxisX = 0,
kBoardAxisY = 1,
kBoardAxisZ = 2,
};
struct BoardYawAxis
{
/* Identifies one of the board axes */
BoardAxis board_axis;
/* true if axis is pointing up (with respect to gravity); false if pointing down. */
bool up;
};
enum SerialDataType {
/**
* (default): 6 and 9-axis processed data
*/
kProcessedData = 0,
/**
* unprocessed data from each individual sensor
*/
kRawData = 1
};
private:
friend class AHRSInternal;
AHRSInternal * ahrs_internal;
volatile float yaw;
volatile float pitch;
volatile float roll;
volatile float compass_heading;
volatile float world_linear_accel_x;
volatile float world_linear_accel_y;
volatile float world_linear_accel_z;
volatile float mpu_temp_c;
volatile float fused_heading;
volatile float altitude;
volatile float baro_pressure;
volatile bool is_moving;
volatile bool is_rotating;
volatile float baro_sensor_temp_c;
volatile bool altitude_valid;
volatile bool is_magnetometer_calibrated;
volatile bool magnetic_disturbance;
volatile float quaternionW;
volatile float quaternionX;
volatile float quaternionY;
volatile float quaternionZ;
/* Integrated Data */
float velocity[3];
float displacement[3];
/* Raw Data */
volatile int16_t raw_gyro_x;
volatile int16_t raw_gyro_y;
volatile int16_t raw_gyro_z;
volatile int16_t raw_accel_x;
volatile int16_t raw_accel_y;
volatile int16_t raw_accel_z;
volatile int16_t cal_mag_x;
volatile int16_t cal_mag_y;
volatile int16_t cal_mag_z;
/* Configuration/Status */
volatile uint8_t update_rate_hz;
volatile int16_t accel_fsr_g;
volatile int16_t gyro_fsr_dps;
volatile int16_t capability_flags;
volatile uint8_t op_status;
volatile int16_t sensor_status;
volatile uint8_t cal_status;
volatile uint8_t selftest_status;
/* Board ID */
volatile uint8_t board_type;
volatile uint8_t hw_rev;
volatile uint8_t fw_ver_major;
volatile uint8_t fw_ver_minor;
long last_sensor_timestamp;
double last_update_time;
InertialDataIntegrator *integrator;
ContinuousAngleTracker *yaw_angle_tracker;
OffsetTracker * yaw_offset_tracker;
IIOProvider * io;
#define MAX_NUM_CALLBACKS 3
ITimestampedDataSubscriber *callbacks[MAX_NUM_CALLBACKS];
void *callback_contexts[MAX_NUM_CALLBACKS];
public:
AHRS(std::string serial_port_id);
AHRS(std::string serial_port_id, AHRS::SerialDataType data_type, uint8_t update_rate_hz);
float GetPitch();
float GetRoll();
float GetYaw();
float GetCompassHeading();
void ZeroYaw();
bool IsCalibrating();
bool IsConnected();
double GetByteCount();
double GetUpdateCount();
long GetLastSensorTimestamp();
float GetWorldLinearAccelX();
float GetWorldLinearAccelY();
float GetWorldLinearAccelZ();
bool IsMoving();
bool IsRotating();
float GetBarometricPressure();
float GetAltitude();
bool IsAltitudeValid();
float GetFusedHeading();
bool IsMagneticDisturbance();
bool IsMagnetometerCalibrated();
float GetQuaternionW();
float GetQuaternionX();
float GetQuaternionY();
float GetQuaternionZ();
void ResetDisplacement();
void UpdateDisplacement( float accel_x_g, float accel_y_g,
int update_rate_hz, bool is_moving );
float GetVelocityX();
float GetVelocityY();
float GetVelocityZ();
float GetDisplacementX();
float GetDisplacementY();
float GetDisplacementZ();
double GetAngle();
double GetRate();
void Reset();
float GetRawGyroX();
float GetRawGyroY();
float GetRawGyroZ();
float GetRawAccelX();
float GetRawAccelY();
float GetRawAccelZ();
float GetRawMagX();
float GetRawMagY();
float GetRawMagZ();
float GetPressure();
float GetTempC();
AHRS::BoardYawAxis GetBoardYawAxis();
std::string GetFirmwareVersion();
bool RegisterCallback( ITimestampedDataSubscriber *callback, void *callback_context);
bool DeregisterCallback( ITimestampedDataSubscriber *callback );
int GetActualUpdateRate();
int GetRequestedUpdateRate();
void Close();
private:
void SerialInit(std::string serial_port_id, AHRS::SerialDataType data_type, uint8_t update_rate_hz);
void commonInit( uint8_t update_rate_hz );
static void *ThreadFunc(void *threadarg);
/* LiveWindowSendable implementation */
std::string GetSmartDashboardType() const;
void StartLiveWindowMode();
void StopLiveWindowMode();
/* PIDSource implementation */
double PIDGet();
uint8_t GetActualUpdateRateInternal(uint8_t update_rate);
};
#endif /* SRC_AHRS_H_ */