VMX-pi C++ HAL Library for Raspberry Pi
VMX-pi Robotics Controller & Vision/Motion Processor
AHRS.h
1 /* ============================================
2 VMX-pi HAL source code is placed under the MIT license
3 Copyright (c) 2017 Kauai Labs
4 Permission is hereby granted, free of charge, to any person obtaining a copy
5 of this software and associated documentation files (the "Software"), to deal
6 in the Software without restriction, including without limitation the rights
7 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
8 copies of the Software, and to permit persons to whom the Software is
9 furnished to do so, subject to the following conditions:
10 The above copyright notice and this permission notice shall be included in
11 all copies or substantial portions of the Software.
12 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
13 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
14 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
15 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
16 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
17 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
18 THE SOFTWARE.
19 ===============================================
20 */
21 
22 #ifndef SRC_AHRS_H_
23 #define SRC_AHRS_H_
24 
25 #include <thread>
26 #include "ITimestampedDataSubscriber.h"
27 
28 class IIOProvider;
29 class ContinuousAngleTracker;
30 class AHRSInternal;
31 
32 class SPIClient;
33 class PIGPIOClient;
34 
35 using namespace std;
36 
38 class AHRS {
39 public:
40 
41  enum BoardAxis {
42  kBoardAxisX = 0,
43  kBoardAxisY = 1,
44  kBoardAxisZ = 2,
45  };
46 
48  struct BoardYawAxis
49  {
50  /* Identifies one of the board axes */
51  BoardAxis board_axis;
52  /* true if axis is pointing up (with respect to gravity); false if pointing down. */
53  bool up;
54  };
55 
60  kProcessedData = 0,
64  kRawData = 1
65  };
66 
67 private:
68  friend class AHRSInternal;
69  AHRSInternal * ahrs_internal;
70 
71  volatile float yaw;
72  volatile float pitch;
73  volatile float roll;
74  volatile float compass_heading;
75  volatile float world_linear_accel_x;
76  volatile float world_linear_accel_y;
77  volatile float world_linear_accel_z;
78  volatile float mpu_temp_c;
79  volatile float fused_heading;
80  volatile float altitude;
81  volatile float baro_pressure;
82  volatile bool is_moving;
83  volatile bool is_rotating;
84  volatile float baro_sensor_temp_c;
85  volatile bool altitude_valid;
86  volatile bool is_magnetometer_calibrated;
87  volatile bool magnetic_disturbance;
88  volatile float quaternionW;
89  volatile float quaternionX;
90  volatile float quaternionY;
91  volatile float quaternionZ;
92 
93  /* Integrated Data */
94  float velocity[3];
95  float displacement[3];
96 
97 
98  /* Raw Data */
99  volatile int16_t raw_gyro_x;
100  volatile int16_t raw_gyro_y;
101  volatile int16_t raw_gyro_z;
102  volatile int16_t raw_accel_x;
103  volatile int16_t raw_accel_y;
104  volatile int16_t raw_accel_z;
105  volatile int16_t cal_mag_x;
106  volatile int16_t cal_mag_y;
107  volatile int16_t cal_mag_z;
108 
109  /* Configuration/Status */
110  volatile uint8_t update_rate_hz;
111  volatile int16_t accel_fsr_g;
112  volatile int16_t gyro_fsr_dps;
113  volatile int16_t capability_flags;
114  volatile uint8_t op_status;
115  volatile int16_t sensor_status;
116  volatile uint8_t cal_status;
117  volatile uint8_t selftest_status;
118 
119  /* Board ID */
120  volatile uint8_t board_type;
121  volatile uint8_t hw_rev;
122  volatile uint8_t fw_ver_major;
123  volatile uint8_t fw_ver_minor;
124 
125  long last_sensor_timestamp;
126  double last_update_time;
127 
128  ContinuousAngleTracker *yaw_angle_tracker;
129  IIOProvider * io;
130 
131  thread * task;
132 
133 #define MAX_NUM_CALLBACKS 3
134  ITimestampedDataSubscriber *callbacks[MAX_NUM_CALLBACKS];
135  void *callback_contexts[MAX_NUM_CALLBACKS];
136 
137 public:
138  AHRS(SPIClient& client, PIGPIOClient& pigpio, uint8_t update_rate_hz);
139  virtual ~AHRS();
140 
141  float GetPitch();
142  float GetRoll();
143  float GetYaw();
144  float GetCompassHeading();
145  void ZeroYaw();
146  bool IsCalibrating();
147  bool IsConnected();
148  double GetByteCount();
149  double GetUpdateCount();
150  long GetLastSensorTimestamp();
151  float GetWorldLinearAccelX();
152  float GetWorldLinearAccelY();
153  float GetWorldLinearAccelZ();
154  bool IsMoving();
155  bool IsRotating();
156  float GetBarometricPressure();
157  float GetAltitude();
158  bool IsAltitudeValid();
159  float GetFusedHeading();
160  bool IsMagneticDisturbance();
161  bool IsMagnetometerCalibrated();
162  float GetQuaternionW();
163  float GetQuaternionX();
164  float GetQuaternionY();
165  float GetQuaternionZ();
166  void ResetDisplacement();
167  void UpdateDisplacement( float accel_x_g, float accel_y_g,
168  int update_rate_hz, bool is_moving );
169  float GetVelocityX();
170  float GetVelocityY();
171  float GetVelocityZ();
172  float GetDisplacementX();
173  float GetDisplacementY();
174  float GetDisplacementZ();
175  double GetAngle();
176  double GetRate();
177  void Reset();
178  float GetRawGyroX();
179  float GetRawGyroY();
180  float GetRawGyroZ();
181  float GetRawAccelX();
182  float GetRawAccelY();
183  float GetRawAccelZ();
184  float GetRawMagX();
185  float GetRawMagY();
186  float GetRawMagZ();
187  float GetPressure();
188  float GetTempC();
189  AHRS::BoardYawAxis GetBoardYawAxis();
190  std::string GetFirmwareVersion();
191 
192  bool RegisterCallback( ITimestampedDataSubscriber *callback, void *callback_context);
193  bool DeregisterCallback( ITimestampedDataSubscriber *callback );
194 
195  int GetActualUpdateRate();
196  int GetRequestedUpdateRate();
197 
198  void Stop();
199 
200 private:
201  void commonInit( uint8_t update_rate_hz );
202  static int ThreadFunc(IIOProvider *io_provider);
203 
204  uint8_t GetActualUpdateRateInternal(uint8_t update_rate);
205 };
206 
207 #endif /* SRC_AHRS_H_ */
SerialDataType
Definition: AHRS.h:56
Describes the currently-configured Omnimount IMU configuration.
Definition: AHRS.h:48
The AHRS class provides accesst to the VMX-pi IMU and Attitude/Heading Reference System functionality...
Definition: AHRS.h:38
The ITimestampedDataSubscriber interface provides a method for consumers of navX-Model device data to...
Definition: ITimestampedDataSubscriber.h:46