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 <string>
26 #include <thread>
27 #include "IVMXTimestampedAHRSDataSubscriber.h"
28 
29 class IIOProviderRpi;
30 class ContinuousAngleTrackerVMX;
31 
32 class SPIClient;
33 class PIGPIOClient;
34 class VMXPi;
35 class VMXZero;
36 
37 using namespace std;
38 
39 enum BoardAxis {
40  kBoardAxisX = 0,
41  kBoardAxisY = 1,
42  kBoardAxisZ = 2,
43 };
44 
47 {
48  /* Identifies one of the board axes */
49  BoardAxis board_axis;
50  /* true if axis is pointing up (with respect to gravity); false if pointing down. */
51  bool up;
52 };
53 
54 namespace vmx {
55 
56 class AHRSInternal;
57 
59 class AHRS {
60  friend class ::VMXPi;
61  friend class ::VMXZero;
62 
63  AHRS(SPIClient& client, PIGPIOClient& pigpio, uint8_t update_rate_hz);
64  virtual ~AHRS();
65 public:
66 
71  kProcessedData = 0,
75  kRawData = 1
76  };
77 
78 private:
79  friend class AHRSInternal;
80  AHRSInternal * ahrs_internal;
81 
82  volatile float yaw;
83  volatile float pitch;
84  volatile float roll;
85  volatile float compass_heading;
86  volatile float world_linear_accel_x;
87  volatile float world_linear_accel_y;
88  volatile float world_linear_accel_z;
89  volatile float mpu_temp_c;
90  volatile float fused_heading;
91  volatile float altitude;
92  volatile float baro_pressure;
93  volatile bool is_moving;
94  volatile bool is_rotating;
95  volatile float baro_sensor_temp_c;
96  volatile bool altitude_valid;
97  volatile bool is_magnetometer_calibrated;
98  volatile bool magnetic_disturbance;
99  volatile float quaternionW;
100  volatile float quaternionX;
101  volatile float quaternionY;
102  volatile float quaternionZ;
103 
104  /* Integrated Data */
105  float velocity[3];
106  float displacement[3];
107 
108 
109  /* Raw Data */
110  volatile int16_t raw_gyro_x;
111  volatile int16_t raw_gyro_y;
112  volatile int16_t raw_gyro_z;
113  volatile int16_t raw_accel_x;
114  volatile int16_t raw_accel_y;
115  volatile int16_t raw_accel_z;
116  volatile int16_t cal_mag_x;
117  volatile int16_t cal_mag_y;
118  volatile int16_t cal_mag_z;
119 
120  /* Configuration/Status */
121  volatile uint8_t update_rate_hz;
122  volatile int16_t accel_fsr_g;
123  volatile int16_t gyro_fsr_dps;
124  volatile int16_t capability_flags;
125  volatile uint8_t op_status;
126  volatile int16_t sensor_status;
127  volatile uint8_t cal_status;
128  volatile uint8_t selftest_status;
129 
130  /* Board ID */
131  volatile uint8_t board_type;
132  volatile uint8_t hw_rev;
133  volatile uint8_t fw_ver_major;
134  volatile uint8_t fw_ver_minor;
135 
136  long last_sensor_timestamp;
137  double last_update_time;
138 
139  ContinuousAngleTrackerVMX *yaw_angle_tracker;
140  IIOProviderRpi * io;
141 
142  thread * task;
143 
144 #define MAX_NUM_CALLBACKS 3
145  IVMXTimestampedAHRSDataSubscriber *callbacks[MAX_NUM_CALLBACKS];
146  void *callback_contexts[MAX_NUM_CALLBACKS];
147 
148 public:
149 
150  float GetPitch();
151  float GetRoll();
152  float GetYaw();
153  float GetCompassHeading();
154  void ZeroYaw();
155  bool IsCalibrating();
156  bool IsConnected();
157  double GetByteCount();
158  double GetUpdateCount();
159  long GetLastSensorTimestamp();
160  float GetWorldLinearAccelX();
161  float GetWorldLinearAccelY();
162  float GetWorldLinearAccelZ();
163  bool IsMoving();
164  bool IsRotating();
165  float GetBarometricPressure();
166  float GetAltitude();
167  bool IsAltitudeValid();
168  float GetFusedHeading();
169  bool IsMagneticDisturbance();
170  bool IsMagnetometerCalibrated();
171  float GetQuaternionW();
172  float GetQuaternionX();
173  float GetQuaternionY();
174  float GetQuaternionZ();
175  void ResetDisplacement();
176  void UpdateDisplacement( float accel_x_g, float accel_y_g,
177  int update_rate_hz, bool is_moving );
178  float GetVelocityX();
179  float GetVelocityY();
180  float GetVelocityZ();
181  float GetDisplacementX();
182  float GetDisplacementY();
183  float GetDisplacementZ();
184  double GetAngle();
185  double GetRate();
186  void Reset();
187  float GetRawGyroX();
188  float GetRawGyroY();
189  float GetRawGyroZ();
190  float GetRawAccelX();
191  float GetRawAccelY();
192  float GetRawAccelZ();
193  float GetRawMagX();
194  float GetRawMagY();
195  float GetRawMagZ();
196  float GetPressure();
197  float GetTempC();
198  BoardYawAxis GetBoardYawAxis();
199  std::string GetFirmwareVersion();
200 
201  bool RegisterCallback( IVMXTimestampedAHRSDataSubscriber *callback, void *callback_context);
202  bool DeregisterCallback( IVMXTimestampedAHRSDataSubscriber *callback );
203  bool BlockOnNewCurrentRegisterData(uint32_t timeout_ms, uint8_t *first_reg_addr_out, uint8_t *p_data_out, uint8_t requested_len, uint8_t *p_len_out);
204  bool ReadConfigurationData(uint8_t first_reg_addr, uint8_t *p_data_out, uint8_t requested_len);
205 
206  int GetActualUpdateRate();
207  int GetRequestedUpdateRate();
208 
209  void Stop();
210 
211 private:
212  void commonInit( uint8_t update_rate_hz );
213  static int ThreadFunc(IIOProviderRpi *io_provider);
214 
215  uint8_t GetActualUpdateRateInternal(uint8_t update_rate);
216 };
217 
218 } // namespace vmx
219 
220 #endif /* SRC_AHRS_H_ */
Top-level Library Class providing access to all VMX-pi functionality.
Definition: VMXPi.h:40
Definition: AHRS.h:54
Describes the currently-configured Omnimount IMU configuration.
Definition: AHRS.h:46
The AHRS class provides accesst to the VMX-pi IMU and Attitude/Heading Reference System functionality...
Definition: AHRS.h:59
SerialDataType
Definition: AHRS.h:67
Top-level Library Class providing access to all VMXzero functionality.
Definition: VMXZero.h:40
The IVMXTimestampedAHRSDataSubscriber interface provides a method for consumers of navX-Model device ...
Definition: IVMXTimestampedAHRSDataSubscriber.h:50