26 #include "ITimestampedDataSubscriber.h" 29 class ContinuousAngleTracker;
68 friend class AHRSInternal;
69 AHRSInternal * ahrs_internal;
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;
95 float displacement[3];
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;
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;
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;
125 long last_sensor_timestamp;
126 double last_update_time;
128 ContinuousAngleTracker *yaw_angle_tracker;
133 #define MAX_NUM_CALLBACKS 3 135 void *callback_contexts[MAX_NUM_CALLBACKS];
138 AHRS(SPIClient& client, PIGPIOClient& pigpio, uint8_t update_rate_hz);
144 float GetCompassHeading();
146 bool IsCalibrating();
148 double GetByteCount();
149 double GetUpdateCount();
150 long GetLastSensorTimestamp();
151 float GetWorldLinearAccelX();
152 float GetWorldLinearAccelY();
153 float GetWorldLinearAccelZ();
156 float GetBarometricPressure();
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();
181 float GetRawAccelX();
182 float GetRawAccelY();
183 float GetRawAccelZ();
190 std::string GetFirmwareVersion();
195 int GetActualUpdateRate();
196 int GetRequestedUpdateRate();
201 void commonInit( uint8_t update_rate_hz );
202 static int ThreadFunc(IIOProvider *io_provider);
204 uint8_t GetActualUpdateRateInternal(uint8_t update_rate);
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