Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS_SBG_structs.h
6351 views
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
support for serial connected SBG INS system
17
*/
18
19
#pragma once
20
21
#include "AP_ExternalAHRS_config.h"
22
23
#if AP_EXTERNAL_AHRS_SBG_ENABLED
24
25
/*!
26
* Clock status and UTC time status definitions.
27
*/
28
#define SBG_ECOM_CLOCK_STATUS_SHIFT (1u) /*!< Shift used to extract the clock status part. */
29
#define SBG_ECOM_CLOCK_STATUS_MASK (0x000Fu) /*!< Mask used to keep only the clock status part. */
30
#define SBG_ECOM_CLOCK_UTC_STATUS_SHIFT (6u) /*!< Shift used to extract the clock UTC status part. */
31
#define SBG_ECOM_CLOCK_UTC_STATUS_MASK (0x000Fu) /*!< Mask used to keep only the clock UTC status part. */
32
33
/*!
34
* Clock status enum.
35
*/
36
typedef enum _SbgEComClockStatus
37
{
38
SBG_ECOM_CLOCK_ERROR = 0, /*!< An error has occurred on the clock estimation. */
39
SBG_ECOM_CLOCK_FREE_RUNNING = 1, /*!< The clock is only based on the internal crystal. */
40
SBG_ECOM_CLOCK_STEERING = 2, /*!< A PPS has been detected and the clock is converging to it. */
41
SBG_ECOM_CLOCK_VALID = 3 /*!< The clock has converged to the PPS and is within 500ns. */
42
} SbgEComClockStatus;
43
44
/*!
45
* Status for the UTC time data.
46
*/
47
typedef enum _SbgEComClockUtcStatus
48
{
49
SBG_ECOM_UTC_INVALID = 0, /*!< The UTC time is not known, we are just propagating the UTC time internally. */
50
SBG_ECOM_UTC_NO_LEAP_SEC = 1, /*!< We have received valid UTC time information but we don't have the leap seconds information. */
51
SBG_ECOM_UTC_VALID = 2 /*!< We have received valid UTC time data with valid leap seconds. */
52
} SbgEComClockUtcStatus;
53
54
static inline SbgEComClockStatus sbgEComLogUtcGetClockStatus(uint16_t status) {
55
return (SbgEComClockStatus)((status >> SBG_ECOM_CLOCK_STATUS_SHIFT) & SBG_ECOM_CLOCK_STATUS_MASK);
56
}
57
static inline SbgEComClockUtcStatus sbgEComLogUtcGetClockUtcStatus(uint16_t status) {
58
return (SbgEComClockUtcStatus)((status >> SBG_ECOM_CLOCK_UTC_STATUS_SHIFT) & SBG_ECOM_CLOCK_UTC_STATUS_MASK);
59
}
60
61
62
typedef struct PACKED _SbgLogUtcData
63
{
64
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
65
uint16_t status; /*!< UTC time and clock status information */
66
uint16_t year; /*!< Year for example: 2013. */
67
int8_t month; /*!< Month in year [1 .. 12]. */
68
int8_t day; /*!< Day in month [1 .. 31]. */
69
int8_t hour; /*!< Hour in day [0 .. 23]. */
70
int8_t minute; /*!< Minute in hour [0 .. 59]. */
71
int8_t second; /*!< Second in minute [0 .. 60]. (60 is used only when a leap second is added) */
72
int32_t nanoSecond; /*!< Nanosecond of current second in ns. */
73
uint32_t gpsTimeOfWeek; /*!< GPS time of week in ms. */
74
} SbgLogUtcData;
75
76
77
78
/*!
79
* Structure that stores data for the SBG_ECOM_LOG_GPS#_VEL message.
80
*/
81
typedef struct PACKED _SbgLogGpsVel
82
{
83
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
84
uint32_t status; /*!< GPS velocity status, type and bitmask. */
85
uint32_t timeOfWeek; /*!< GPS time of week in ms. */
86
float velocity[3]; /*!< GPS North, East, Down velocity in m.s^-1. */
87
float velocityAcc[3]; /*!< GPS North, East, Down velocity 1 sigma accuracy in m.s^-1. */
88
float course; /*!< Track ground course in degrees. */
89
float courseAcc; /*!< Course accuracy in degrees. */
90
} SbgLogGpsVel;
91
92
/*!
93
* Structure that stores data for the SBG_ECOM_LOG_GPS#_POS message.
94
*/
95
typedef struct PACKED _SbgLogGpsPos
96
{
97
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
98
uint32_t status; /*!< GPS position status, type and bitmask. */
99
uint32_t timeOfWeek; /*!< GPS time of week in ms. */
100
double latitude; /*!< Latitude in degrees, positive north. */
101
double longitude; /*!< Longitude in degrees, positive east. */
102
double altitude; /*!< Altitude above Mean Sea Level in meters. */
103
float undulation; /*!< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation). */
104
float latitudeAccuracy; /*!< 1 sigma latitude accuracy in meters. */
105
float longitudeAccuracy; /*!< 1 sigma longitude accuracy in meters. */
106
float altitudeAccuracy; /*!< 1 sigma altitude accuracy in meters. */
107
uint8_t numSvUsed; /*!< Number of space vehicles used to compute the solution (since version 1.4). */
108
uint16_t baseStationId; /*!< Base station id for differential corrections (0-4095). Set to 0xFFFF if differential corrections are not used (since version 1.4). */
109
uint16_t differentialAge; /*!< Differential correction age in 0.01 seconds. Set to 0XFFFF if differential corrections are not used (since version 1.4). */
110
} SbgLogGpsPos;
111
112
/*!
113
* Structure that stores data for the SBG_ECOM_LOG_GPS#_HDT message.
114
*/
115
typedef struct PACKED _SbgLogGpsHdt
116
{
117
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
118
uint16_t status; /*!< GPS HDT status, type and bitmask. */
119
uint32_t timeOfWeek; /*!< GPS time of week in ms. */
120
float heading; /*!< GPS true heading in degrees. */
121
float headingAccuracy; /*!< 1 sigma GPS true heading accuracy in degrees. */
122
float pitch; /*!< GPS pitch angle measured from the master to the rover in degrees. */
123
float pitchAccuracy; /*!< 1 signa GPS pitch angle accuarcy in degrees. */
124
} SbgLogGpsHdt;
125
126
127
128
/*!
129
* Structure that stores data for the SBG_ECOM_LOG_IMU_DATA message.
130
*/
131
typedef struct PACKED _SbgLogImuData
132
{
133
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
134
uint16_t status; /*!< IMU status bitmask. */
135
float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */
136
float gyroscopes[3]; /*!< X, Y, Z gyroscopes in rad.s^-1. */
137
float temperature; /*!< Internal temperature in C. */
138
float deltaVelocity[3]; /*!< X, Y, Z delta velocity in m.s^-2. */
139
float deltaAngle[3]; /*!< X, Y, Z delta angle in rad.s^-1. */
140
} SbgLogImuData;
141
142
/*!
143
* Structure that stores the data for SBG_ECOM_LOG_FAST_IMU_DATA message
144
*/
145
typedef struct PACKED _SbgLogFastImuData
146
{
147
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
148
uint16_t status; /*!< IMU status bitmask. */
149
float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */
150
float gyroscopes[3]; /*!< X, Y, Z gyroscopes in rad.s^-1. */
151
} SbgLogFastImuData;
152
153
/*!
154
* Log inertial data status mask definitions
155
*/
156
#define SBG_ECOM_IMU_COM_OK (0x00000001u << 0) /*!< Set to 1 if the communication with the IMU is ok. */
157
#define SBG_ECOM_IMU_STATUS_BIT (0x00000001u << 1) /*!< Set to 1 if the IMU passes general Built in Tests (calibration, CPU, ...). */
158
159
#define SBG_ECOM_IMU_ACCEL_X_BIT (0x00000001u << 2) /*!< Set to 1 if the accelerometer X passes Built In Test. */
160
#define SBG_ECOM_IMU_ACCEL_Y_BIT (0x00000001u << 3) /*!< Set to 1 if the accelerometer Y passes Built In Test. */
161
#define SBG_ECOM_IMU_ACCEL_Z_BIT (0x00000001u << 4) /*!< Set to 1 if the accelerometer Z passes Built In Test. */
162
163
#define SBG_ECOM_IMU_GYRO_X_BIT (0x00000001u << 5) /*!< Set to 1 if the gyroscope X passes Built In Test. */
164
#define SBG_ECOM_IMU_GYRO_Y_BIT (0x00000001u << 6) /*!< Set to 1 if the gyroscope Y passes Built In Test. */
165
#define SBG_ECOM_IMU_GYRO_Z_BIT (0x00000001u << 7) /*!< Set to 1 if the gyroscope Z passes Built In Test. */
166
167
#define SBG_ECOM_IMU_ACCELS_IN_RANGE (0x00000001u << 8) /*!< Set to 1 if all accelerometers are within operating range. */
168
#define SBG_ECOM_IMU_GYROS_IN_RANGE (0x00000001u << 9) /*!< Set to 1 if all gyroscopes are within operating range. */
169
#define SBG_ECOM_IMU_GYROS_USE_HIGH_SCALE (0x00000001u << 10) /*!< Set if the gyroscope scale factor range is high. Applicable only for SBG_ECOM_LOG_IMU_SHORT logs. */
170
171
/*!
172
* Standard gyroscope scale factor.
173
*/
174
#define SBG_ECOM_LOG_IMU_GYRO_SCALE_STD (67108864.0f)
175
176
/*!
177
* High range gyroscope scale factor derived from 10000 degrees per second maximum range.
178
*
179
* Calculation: (2^31 - 1) / (10000 * π / 180)
180
*/
181
#define SBG_ECOM_LOG_IMU_GYRO_SCALE_HIGH (12304174.0f)
182
183
/*!
184
* Maximum value for the standard scale factor, in radians per second.
185
*
186
* Approximately equivalent to 1833 °/s.
187
*/
188
#define SBG_ECOM_LOG_IMU_GYRO_SCALE_STD_MAX_RAD ((float)INT32_MAX / SBG_ECOM_LOG_IMU_GYRO_SCALE_STD)
189
190
/*!
191
* Standard accelerometer scale factor.
192
*/
193
#define SBG_ECOM_LOG_IMU_ACCEL_SCALE_STD (1048576.0f)
194
195
/*!
196
* Standard temperature scale factor.
197
*/
198
#define SBG_ECOM_LOG_IMU_TEMP_SCALE_STD (256.0f)
199
200
/*!
201
* Structure that stores data for the SBG_ECOM_LOG_IMU_SHORT message.
202
*
203
* This message is sent asynchronously and must be used for post processing.
204
*
205
* The delta angle values are scaled based on the gyroscopes output. If any output exceeds
206
* a predefined limit, the scale factor switches from standard to high range to prevent saturation.
207
*/
208
typedef struct PACKED _SbgEComLogImuShort
209
{
210
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
211
uint16_t status; /*!< IMU status bitmask. */
212
int32_t deltaVelocity[3]; /*!< X, Y, Z delta velocity. Unit is 1048576 LSB for 1 m.s^-2. */
213
int32_t deltaAngle[3]; /*!< X, Y, Z delta angle. Unit is either 67108864 LSB for 1 rad.s^-1 (standard) or 12304174 LSB for 1 rad.s^-1 (high range), managed automatically. */
214
int16_t temperature; /*!< IMU average temperature. Unit is 256 LSB for 1°C. */
215
} SbgEComLogImuShort;
216
217
218
219
#define SBG_ECOM_LOG_EKF_SOLUTION_MODE_MASK (0x0000000Fu) /*!< Mask used to keep only the clock status part. */
220
221
/*!
222
* Solution filter mode enum.
223
*/
224
typedef enum _SbgEComSolutionMode
225
{
226
SBG_ECOM_SOL_MODE_UNINITIALIZED = 0, /*!< The Kalman filter is not initialized and the returned data are all invalid. */
227
SBG_ECOM_SOL_MODE_VERTICAL_GYRO = 1, /*!< The Kalman filter only rely on a vertical reference to compute roll and pitch angles. Heading and navigation data drift freely. */
228
SBG_ECOM_SOL_MODE_AHRS = 2, /*!< A heading reference is available, the Kalman filter provides full orientation but navigation data drift freely. */
229
SBG_ECOM_SOL_MODE_NAV_VELOCITY = 3, /*!< The Kalman filter computes orientation and velocity. Position is freely integrated from velocity estimation. */
230
SBG_ECOM_SOL_MODE_NAV_POSITION = 4 /*!< Nominal mode, the Kalman filter computes all parameters (attitude, velocity, position). Absolute position is provided. */
231
} SbgEComSolutionMode;
232
233
/*!
234
* EKF computed orientation using euler angles.
235
*/
236
typedef struct PACKED _SbgLogEkfEulerData
237
{
238
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
239
float euler[3]; /*!< Roll, Pitch and Yaw angles in rad. */
240
float eulerStdDev[3]; /*!< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad. */
241
uint32_t status; /*!< EKF solution status bitmask and enum. */
242
} SbgLogEkfEulerData;
243
244
/*!
245
* EFK computed orientation using quaternion.
246
*/
247
typedef struct PACKED _SbgLogEkfQuatData
248
{
249
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
250
float quaternion[4]; /*!< Orientation quaternion stored in W, X, Y, Z form. */
251
float eulerStdDev[3]; /*!< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad. */
252
uint32_t status; /*!< EKF solution status bitmask and enum. */
253
} SbgLogEkfQuatData;
254
255
/*!
256
* EFK computed navigation data.
257
*/
258
typedef struct PACKED _SbgLogEkfNavData
259
{
260
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
261
float velocity[3]; /*!< North, East, Down velocity in m.s^-1. */
262
float velocityStdDev[3]; /*!< North, East, Down velocity 1 sigma standard deviation in m.s^-1. */
263
double position[3]; /*!< Latitude, Longitude in degrees positive North and East.
264
Altitude above Mean Sea Level in meters. */
265
float undulation; /*!< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation). */
266
float positionStdDev[3]; /*!< Latitude, longitude and altitude 1 sigma standard deviation in meters. */
267
uint32_t status; /*!< EKF solution status bitmask and enum. */
268
} SbgLogEkfNavData;
269
270
//----------------------------------------------------------------------//
271
//- Log Air Data status definitions -//
272
//----------------------------------------------------------------------//
273
274
/*!
275
* Air Data sensor status mask definitions
276
*/
277
#define SBG_ECOM_AIR_DATA_TIME_IS_DELAY (0x0001u << 0) /*!< Set to 1 if the timeStamp field represents a delay instead of an absolute timestamp. */
278
#define SBG_ECOM_AIR_DATA_PRESSURE_ABS_VALID (0x0001u << 1) /*!< Set to 1 if the pressure field is filled and valid. */
279
#define SBG_ECOM_AIR_DATA_ALTITUDE_VALID (0x0001u << 2) /*!< Set to 1 if the barometric altitude field is filled and valid. */
280
#define SBG_ECOM_AIR_DATA_PRESSURE_DIFF_VALID (0x0001u << 3) /*!< Set to 1 if the differential pressure field is filled and valid. */
281
#define SBG_ECOM_AIR_DATA_AIRPSEED_VALID (0x0001u << 4) /*!< Set to 1 if the true airspeed field is filled and valid. */
282
#define SBG_ECOM_AIR_DATA_TEMPERATURE_VALID (0x0001u << 5) /*!< Set to 1 if the output air temperature field is filled and valid. */
283
284
/*!
285
* Log structure for AirData.
286
*/
287
typedef struct PACKED _SbgLogAirData
288
{
289
uint32_t timeStamp; /*!< Time in us since the sensor power up OR measurement delay in us. */
290
uint16_t status; /*!< Airdata sensor status bitmask. */
291
float pressureAbs; /*!< Raw absolute pressure measured by the barometer sensor in Pascals. */
292
float altitude; /*!< Altitude computed from barometric altimeter in meters and positive upward. */
293
float pressureDiff; /*!< Raw differential pressure measured by the pitot tube in Pascal. */
294
float trueAirspeed; /*!< True airspeed measured by a pitot tube in m.s^-1 and positive forward. */
295
float airTemperature; /*!< Outside air temperature in C that could be used to compute true airspeed from differential pressure. */
296
} SbgLogAirData;
297
298
/*!
299
* Log magnetometer data status mask definitions
300
*/
301
#define SBG_ECOM_MAG_MAG_X_BIT (0x00000001u << 0) /*!< Set to 1 if the magnetometer X passes Built In Test. */
302
#define SBG_ECOM_MAG_MAG_Y_BIT (0x00000001u << 1) /*!< Set to 1 if the magnetometer Y passes Built In Test. */
303
#define SBG_ECOM_MAG_MAG_Z_BIT (0x00000001u << 2) /*!< Set to 1 if the magnetometer Z passes Built In Test. */
304
305
#define SBG_ECOM_MAG_ACCEL_X_BIT (0x00000001u << 3) /*!< Set to 1 if the accelerometer X passes Built In Test. */
306
#define SBG_ECOM_MAG_ACCEL_Y_BIT (0x00000001u << 4) /*!< Set to 1 if the accelerometer Y passes Built In Test. */
307
#define SBG_ECOM_MAG_ACCEL_Z_BIT (0x00000001u << 5) /*!< Set to 1 if the accelerometer Z passes Built In Test. */
308
309
#define SBG_ECOM_MAG_MAGS_IN_RANGE (0x00000001u << 6) /*!< Set to 1 if all magnetometers are within operating range. */
310
#define SBG_ECOM_MAG_ACCELS_IN_RANGE (0x00000001u << 7) /*!< Set to 1 if all accelerometers are within operating range. */
311
312
#define SBG_ECOM_MAG_CALIBRATION_OK (0x00000001u << 8) /*!< Set to 1 if the magnetometers seems to be calibrated. */
313
314
/*!
315
* Structure that stores data for the SBG_ECOM_LOG_MAG message.
316
*/
317
typedef struct PACKED _SbgLogMag
318
{
319
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
320
uint16_t status; /*!< Magnetometer status bitmask. */
321
float magnetometers[3]; /*!< X, Y, Z magnetometer data in A.U. */
322
float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */
323
} SbgLogMag;
324
325
/*!
326
* Structure that stores data for the SBG_ECOM_LOG_MAG_CALIB message.
327
*/
328
typedef struct PACKED _SbgLogMagCalib
329
{
330
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
331
uint16_t reserved; /*!< Reserved for future use. */
332
uint8_t magData[16]; /*!< Magnetometers calibration data. */
333
} SbgLogMagCalib;
334
335
336
typedef struct PACKED _SbgLogStatusData
337
{
338
uint32_t timeStamp; /*!< Time in us since the sensor power up. */
339
uint16_t generalStatus; /*!< General status bitmask and enums. */
340
uint16_t reserved1; /*!< Reserved status field for future use */
341
uint32_t comStatus; /*!< Communication status bitmask and enums. */
342
uint32_t aidingStatus; /*!< Aiding equipments status bitmask and enums. */
343
uint32_t reserved2; /*!< Reserved status field for future use. */
344
uint16_t reserved3; /*!< Reserved status field for future use. */
345
uint32_t uptime; /*!< System uptime in seconds. */
346
} SbgLogStatusData;
347
348
/*!
349
* Helper structure to retrieve device info.
350
*/
351
#define SBG_ECOM_INFO_PRODUCT_CODE_LENGTH (32)
352
typedef struct PACKED _SbgEComDeviceInfo
353
{
354
uint8_t productCode[SBG_ECOM_INFO_PRODUCT_CODE_LENGTH]; /*!< Human readable Product Code. */
355
uint32_t serialNumber; /*!< Device serial number */
356
uint32_t calibationRev; /*!< Calibration data revision */
357
uint16_t calibrationYear; /*!< Device Calibration Year */
358
uint8_t calibrationMonth; /*!< Device Calibration Month */
359
uint8_t calibrationDay; /*!< Device Calibration Day */
360
uint32_t hardwareRev; /*!< Device hardware revision */
361
uint32_t firmwareRev; /*!< Firmware revision */
362
} SbgEComDeviceInfo;
363
364
365
366
/*!
367
* Generic errors definitions for SBG Systems projects.
368
*/
369
typedef enum _SbgErrorCode : uint16_t
370
{
371
SBG_NO_ERROR = 0, /*!< The operation was successfully executed. */
372
SBG_ERROR, /*!< We have a generic error. */
373
SBG_NULL_POINTER, /*!< A pointer is null. */
374
SBG_INVALID_CRC, /*!< The received frame has an invalid CRC. */
375
SBG_INVALID_FRAME, /*!< The received frame is invalid <br> */
376
/*!< We have received an unexpected frame (not the cmd we are waiting for or with an invalid data size.<br> */
377
/*!< This could be caused by a desync between questions and answers.<br> */
378
/*!< You should flush the serial port to fix this. */
379
SBG_TIME_OUT, /*!< We have started to receive a frame but not the end. */
380
SBG_WRITE_ERROR, /*!< All bytes hasn't been written. */
381
SBG_READ_ERROR, /*!< All bytes hasn't been read. */
382
SBG_BUFFER_OVERFLOW, /*!< A buffer is too small to contain so much data. */
383
SBG_INVALID_PARAMETER, /*!< An invalid parameter has been found. */
384
SBG_NOT_READY, /*!< A device isn't ready (Rx isn't ready for example). */
385
SBG_MALLOC_FAILED, /*!< Failed to allocate a buffer. */
386
SGB_CALIB_MAG_NOT_ENOUGH_POINTS, /*!< Not enough points were available to perform magnetometers calibration. */
387
SBG_CALIB_MAG_INVALID_TAKE, /*!< The calibration procedure could not be properly executed due to insufficient precision. */
388
SBG_CALIB_MAG_SATURATION, /*!< Saturation were detected when attempt to calibrate magnetos. */
389
SBG_CALIB_MAG_POINTS_NOT_IN_A_PLANE, /*!< 2D calibration procedure could not be performed. */
390
391
SBG_DEVICE_NOT_FOUND, /*!< A device couldn't be founded or opened PC only error code */
392
SBG_OPERATION_CANCELLED, /*!< An operation was cancelled. PC only error code*/
393
SBG_NOT_CONTINUOUS_FRAME, /*!< We have received a frame that isn't a continuous one. PC only error code*/
394
395
SBG_INCOMPATIBLE_HARDWARE, /*!< Hence valid; the command cannot be executed because of hardware incompatibility */
396
SBG_INVALID_VERSION /*!< Incompatible version */
397
} SbgErrorCode;
398
399
400
typedef struct PACKED _SbgEComACK
401
{
402
uint8_t ackMsg;
403
uint8_t ackMsgClass;
404
SbgErrorCode ackErrorCode;
405
} SbgEComAck;
406
407
/*!
408
* Defintion of all the settings actions available.
409
*/
410
typedef enum _SbgEComSettingsAction
411
{
412
SBG_ECOM_REBOOT_ONLY = 0, /*!< Only reboot the device. */
413
SBG_ECOM_SAVE_SETTINGS = 1, /*!< Save the settings to non-volatile memory and then reboot the device. */
414
SBG_ECOM_RESTORE_DEFAULT_SETTINGS = 2 /*!< Restore default settings, save them to non-volatile memory and reboot the device. */
415
} SbgEComSettingsAction;
416
417
418
typedef enum _SbgEComGpsPosType
419
{
420
SBG_ECOM_POS_NO_SOLUTION = 0, /*!< No valid solution available. */
421
SBG_ECOM_POS_UNKNOWN_TYPE = 1, /*!< An unknown solution type has been computed. */
422
SBG_ECOM_POS_SINGLE = 2, /*!< Single point solution position. */
423
SBG_ECOM_POS_PSRDIFF = 3, /*!< Standard Pseudorange Differential Solution (DGPS). */
424
SBG_ECOM_POS_SBAS = 4, /*!< SBAS satellite used for differential corrections. */
425
SBG_ECOM_POS_OMNISTAR = 5, /*!< Omnistar VBS Position (L1 sub-meter). */
426
SBG_ECOM_POS_RTK_FLOAT = 6, /*!< Floating RTK ambiguity solution (20 cms RTK). */
427
SBG_ECOM_POS_RTK_INT = 7, /*!< Integer RTK ambiguity solution (2 cms RTK). */
428
SBG_ECOM_POS_PPP_FLOAT = 8, /*!< Precise Point Positioning with float ambiguities. */
429
SBG_ECOM_POS_PPP_INT = 9, /*!< Precise Point Positioning with fixed ambiguities. */
430
SBG_ECOM_POS_FIXED = 10 /*!< Fixed location solution position. */
431
} SbgEComGpsPosType;
432
433
#define SBG_ECOM_GPS_POS_TYPE_SHIFT (6u) /*!< Shift used to extract the GPS position type part. */
434
#define SBG_ECOM_GPS_POS_TYPE_MASK (0x0000003Fu) /*!< Mask used to keep only the GPS position type part. */
435
436
437
438
/*!
439
* Define if the onboard magnetic calibration should acquiere points for a 3D or 2D calibration.
440
*/
441
typedef enum _SbgEComMagCalibMode
442
{
443
SBG_ECOM_MAG_CALIB_MODE_2D = 1, /*!< Tell the device that the magnetic calibration will be performed with limited motions.
444
This calibration mode is only designed to be used when roll and pitch motions are less than 5.
445
To work correctly, the device should be rotated through at least a full circle. */
446
SBG_ECOM_MAG_CALIB_MODE_3D = 2 /*!< Tell the device to start a full 3D magnetic calibration procedure.
447
The 3D magnetic calibration offers the best accuracy but needs at least motion of 30 on the roll and pitch angles. */
448
} SbgEComMagCalibMode;
449
450
451
/*!
452
* Used to select the expected dynamics during the magnetic calibration.
453
*/
454
typedef enum _SbgEComMagCalibBandwidth
455
{
456
SBG_ECOM_MAG_CALIB_LOW_BW = 0, /*!< Tell the device that low dynamics will be observed during the magnetic calibration process. */
457
SBG_ECOM_MAG_CALIB_MEDIUM_BW = 1, /*!< Tell the device that normal dynamics will be observed during the magnetic calibration process. */
458
SBG_ECOM_MAG_CALIB_HIGH_BW = 2 /*!< Tell the device that high dynamics will be observed during the magnetic calibration process. */
459
} SbgEComMagCalibBandwidth;
460
461
/*!
462
* General quality indicator of an onboard magnetic calibration.
463
*/
464
typedef enum _SbgEComMagCalibQuality
465
{
466
SBG_ECOM_MAG_CALIB_QUAL_OPTIMAL = 0, /*!< All acquired points fit very well on a unit sphere after the calibration. */
467
SBG_ECOM_MAG_CALIB_QUAL_GOOD = 1, /*!< Small deviations of the magnetic field norm have been detected. The magnetic calibration should although provide accurate heading. */
468
SBG_ECOM_MAG_CALIB_QUAL_POOR = 2, /*!< Large deviations of the magnetic field norm have been detected. It may come from external magnetic distortions during the calibration. */
469
SBG_ECOM_MAG_CALIB_QUAL_INVALID = 3 /*!< No valid magnetic calibration has been computed. It could comes from too much magnetic disturbances, insufficient or invalid motions. */
470
} SbgEComMagCalibQuality;
471
472
/*!
473
* Confidence indicator on results of an onbard magnetic calibration.
474
*/
475
typedef enum _SbgEComMagCalibConfidence
476
{
477
SBG_ECOM_MAG_CALIB_TRUST_HIGH = 0, /*!< Reported quality indicator can be trusted as enough remarkable magnetic field points have been acquired. */
478
SBG_ECOM_MAG_CALIB_TRUST_MEDIUM = 1, /*!< Few remarkable magnetic field points have been used to compute the magnetic calibration leading to a medium confidence in reported quality indicators. */
479
SBG_ECOM_MAG_CALIB_TRUST_LOW = 2 /*!< Even if the quality indicator could report an excellent calibration,
480
The data set used to compute the magnetic calibration was not meaningful enough to compute meaningful quality indicators.
481
This calibration should be used carefully. */
482
} SbgEComMagCalibConfidence;
483
484
#define SBG_ECOM_MAG_CALIB_NOT_ENOUGH_POINTS (0x0001u) /*!< Not enough valid magnetic points have been acquired. */
485
#define SBG_ECOM_MAG_CALIB_TOO_MUCH_DISTORTIONS (0x0002u) /*!< Unable to compute a magnetic calibration due to magnetic interferences or incorrect data set distribution. */
486
#define SBG_ECOM_MAG_CALIB_X_MOTION_ISSUE (0x0004u) /*!< For a 3D calibration: not enough motion on X axis. For a 2D calibration; too much motion on X axis. */
487
#define SBG_ECOM_MAG_CALIB_Y_MOTION_ISSUE (0x0008u) /*!< For a 3D calibration: not enough motion on Y axis. For a 2D calibration; too much motion on Y axis. */
488
#define SBG_ECOM_MAG_CALIB_Z_MOTION_ISSUE (0x0010u) /*!< For a 3D or 2D calibration: not enough motion on Z axis. */
489
#define SBG_ECOM_MAG_CALIB_ALIGNMENT_ISSUE (0x0020u) /*!< For a 3D calibration: the alignment between the magnetometers and the inertial frame seems to be invalid. */
490
491
492
/*!
493
* Helper structure to retrieve onboard magnetic calibration results.
494
*/
495
typedef struct PACKED _SbgEComMagCalibResults
496
{
497
SbgEComMagCalibQuality quality; /*!< General magnetic calibration quality indicator. */
498
SbgEComMagCalibConfidence confidence; /*!< Confidence indicator that should be read to interpret the quality indicator. */
499
uint16_t advancedStatus; /*!< Set of bit masks used to report advanced information on the magnetic calibration status.*/
500
501
float beforeMeanError; /*!< Mean magnetic field norm error observed before calibration. */
502
float beforeStdError; /*!< Standard deviation of the magnetic field norm error observed before calibration. */
503
float beforeMaxError; /*!< Maximum magnetic field norm error observed before calibration. */
504
505
float afterMeanError; /*!< Mean magnetic field norm error observed after calibration. */
506
float afterStdError; /*!< Standard deviation of the magnetic field norm error observed after calibration. */
507
float afterMaxError; /*!< Maximum magnetic field norm error observed after calibration. */
508
509
float meanAccuracy; /*!< Mean expected heading accuracy in radians. */
510
float stdAccuracy; /*!< Standard deviation of the expected heading accuracy in radians. */
511
float maxAccuracy; /*!< Maximum expected heading accuracy in radians. */
512
513
uint16_t numPoints; /*!< Number of magnetic field points stored internally and used to compute the magnetic calibration. */
514
uint16_t maxNumPoints; /*!< Maximum number of magnetic field points that can be stored internally. */
515
float offset[3]; /*!< Computed Hard Iron correction vector offset. */
516
float matrix[9]; /*!< Computed Hard & Soft Iron correction matrix. */
517
} SbgEComMagCalibResults;
518
519
520
typedef struct _SbgEComSetMagCal
521
{
522
float offset[3]; /*!< Computed Hard Iron correction vector offset. */
523
float matrix[9]; /*!< Computed Hard & Soft Iron correction matrix. */
524
} SbgEComSetMagCal;
525
526
527
/*!
528
* Enum that defines all the message classes available.
529
*/
530
typedef enum _SbgEComClass
531
{
532
SBG_ECOM_CLASS_LOG_ECOM_0 = 0x00, /*!< Class that contains sbgECom protocol input/output log messages. */
533
534
SBG_ECOM_CLASS_LOG_ECOM_1 = 0x01, /*!< Class that contains special sbgECom output messages that handle high frequency output */
535
536
SBG_ECOM_CLASS_LOG_NMEA_0 = 0x02, /*!< Class that contains NMEA (and NMEA like) output logs. <br>
537
Note: This class is only used for identification purpose and does not contain any sbgECom message. */
538
SBG_ECOM_CLASS_LOG_NMEA_1 = 0x03, /*!< Class that contains proprietary NMEA (and NMEA like) output logs. <br>
539
Note: This class is only used for identification purpose and does not contain any sbgECom message. */
540
SBG_ECOM_CLASS_LOG_THIRD_PARTY_0 = 0x04, /*!< Class that contains third party output logs.
541
Note: This class is only used for identification purpose and does not contain any sbgECom message. */
542
SBG_ECOM_CLASS_LOG_CMD_0 = 0x10 /*!< Class that contains sbgECom protocol commands */
543
} SbgEComClass;
544
545
//----------------------------------------------------------------------//
546
//- Definition of all messages id for sbgECom -//
547
//----------------------------------------------------------------------//
548
549
/*!
550
* Enum that defines all the available ECom output logs from the sbgECom library.
551
*/
552
typedef enum _SbgEComLog
553
{
554
SBG_ECOM_LOG_STATUS = 1, /*!< Status general, clock, com aiding, solution, heave */
555
556
SBG_ECOM_LOG_UTC_TIME = 2, /*!< Provides UTC time reference */
557
558
SBG_ECOM_LOG_IMU_DATA = 3, /*!< DEPRECATED: Synchronous IMU measurements (time aligned to UTC - NEVER use for Post Processing). */
559
560
SBG_ECOM_LOG_MAG = 4, /*!< Magnetic data with associated accelerometer on each axis */
561
SBG_ECOM_LOG_MAG_CALIB = 5, /*!< Magnetometer calibration data (raw buffer) */
562
563
SBG_ECOM_LOG_EKF_EULER = 6, /*!< Includes roll, pitch, yaw and their accuracies on each axis */
564
SBG_ECOM_LOG_EKF_QUAT = 7, /*!< Includes the 4 quaternions values */
565
SBG_ECOM_LOG_EKF_NAV = 8, /*!< Position and velocities in NED coordinates with the accuracies on each axis */
566
567
SBG_ECOM_LOG_SHIP_MOTION = 9, /*!< Heave, surge and sway and accelerations on each axis. */
568
569
SBG_ECOM_LOG_GPS1_VEL = 13, /*!< GPS velocities from primary or secondary GPS receiver */
570
SBG_ECOM_LOG_GPS1_POS = 14, /*!< GPS positions from primary or secondary GPS receiver */
571
SBG_ECOM_LOG_GPS1_HDT = 15, /*!< GPS true heading from dual antenna system */
572
573
SBG_ECOM_LOG_GPS2_VEL = 16, /*!< GPS 2 velocity log data. */
574
SBG_ECOM_LOG_GPS2_POS = 17, /*!< GPS 2 position log data. */
575
SBG_ECOM_LOG_GPS2_HDT = 18, /*!< GPS 2 true heading log data. */
576
577
SBG_ECOM_LOG_ODO_VEL = 19, /*!< Provides odometer velocity */
578
579
SBG_ECOM_LOG_EVENT_A = 24, /*!< Event markers sent when events are detected on sync in A pin */
580
SBG_ECOM_LOG_EVENT_B = 25, /*!< Event markers sent when events are detected on sync in B pin */
581
SBG_ECOM_LOG_EVENT_C = 26, /*!< Event markers sent when events are detected on sync in C pin */
582
SBG_ECOM_LOG_EVENT_D = 27, /*!< Event markers sent when events are detected on sync in D pin */
583
SBG_ECOM_LOG_EVENT_E = 28, /*!< Event markers sent when events are detected on sync in E pin */
584
585
SBG_ECOM_LOG_DVL_BOTTOM_TRACK = 29, /*!< Doppler Velocity Log for bottom tracking data. */
586
SBG_ECOM_LOG_DVL_WATER_TRACK = 30, /*!< Doppler Velocity log for water layer data. */
587
588
SBG_ECOM_LOG_GPS1_RAW = 31, /*!< GPS 1 raw data for post processing. */
589
590
SBG_ECOM_LOG_SHIP_MOTION_HP = 32, /*!< Return delayed ship motion such as surge, sway, heave. */
591
592
SBG_ECOM_LOG_AIR_DATA = 36, /*!< Air Data aiding such as barometric altimeter and true air speed. */
593
594
SBG_ECOM_LOG_USBL = 37, /*!< Raw USBL position data for sub-sea navigation. */
595
596
SBG_ECOM_LOG_GPS2_RAW = 38, /*!< GPS 2 raw data for post processing. */
597
598
599
SBG_ECOM_LOG_IMU_SHORT = 44, /*!< Asynchronous IMU measurements output at the IMU rate and to use for Post Processing with Qinertia. */
600
601
SBG_ECOM_LOG_EVENT_OUT_A = 45, /*!< Event marker used to timestamp each generated Sync Out A signal. */
602
SBG_ECOM_LOG_EVENT_OUT_B = 46, /*!< Event marker used to timestamp each generated Sync Out B signal. */
603
604
SBG_ECOM_LOG_DEPTH = 47, /*!< Depth sensor measurement log used for sub-sea navigation. */
605
SBG_ECOM_LOG_DIAG = 48, /*!< Diagnostic log. */
606
607
SBG_ECOM_LOG_RTCM_RAW = 49, /*!< RTCM raw data. */
608
609
SBG_ECOM_LOG_GPS1_SAT = 50, /*!< GPS 1 Satellite data. */
610
SBG_ECOM_LOG_GPS2_SAT = 51, /*!< GNSS2 Satellite data. */
611
612
SBG_ECOM_LOG_EKF_ROT_ACCEL_BODY = 52, /*!< INS body rotation rate and lateral acceleration (bias, earth rotation and gravity free compensated). */
613
SBG_ECOM_LOG_EKF_ROT_ACCEL_NED = 53, /*!< INS North/East/Down rotation rate and lateral acceleration (bias, earth rotation and gravity free compensated). */
614
SBG_ECOM_LOG_EKF_VEL_BODY = 54, /*!< INS X,Y,Z body velocity and standard deviation. */
615
616
SBG_ECOM_LOG_SESSION_INFO = 55, /*!< Session information, including device information and current settings. */
617
618
SBG_ECOM_LOG_EKF_DEBUG = 56, /*!< EKF debug data. */
619
620
SBG_ECOM_LOG_PTP_STATUS = 57, /*!< PTP status. */
621
622
SBG_ECOM_LOG_VELOCITY_1 = 58, /*!< Generic velocity 1 log. */
623
624
SBG_ECOM_LOG_VIB_MON_FFT = 59, /*!< Vibration monitoring FFT data for post processing. */
625
SBG_ECOM_LOG_VIB_MON_REPORT = 60, /*!< Vibration monitoring report information. */
626
627
SBG_ECOM_LOG_ECOM_NUM_MESSAGES /*!< Helper definition to know the number of ECom messages */
628
} SbgEComLog;
629
630
/*!
631
* Enum that defines all the available ECom output logs in the class SBG_ECOM_CLASS_LOG_ECOM_1
632
*/
633
typedef enum _SbgEComLog1MsgId
634
{
635
SBG_ECOM_LOG_FAST_IMU_DATA = 0, /*!< Provides accelerometers, gyroscopes, time and status at 1KHz rate. */
636
SBG_ECOM_LOG_ECOM_1_NUM_MESSAGES /*!< Helper definition to know the number of ECom messages */
637
} SbgEComLog1;
638
639
640
/*!
641
* Enum that defines all the available commands for the sbgECom library.
642
*/
643
typedef enum _SbgEComCmd
644
{
645
/* Acknowledge */
646
SBG_ECOM_CMD_ACK = 0, /*!< Acknowledge */
647
648
/* Special settings commands */
649
SBG_ECOM_CMD_SETTINGS_ACTION = 1, /*!< Performs various settings actions */
650
SBG_ECOM_CMD_IMPORT_SETTINGS = 2, /*!< Imports a new settings structure to the sensor */
651
SBG_ECOM_CMD_EXPORT_SETTINGS = 3, /*!< Export the whole configuration from the sensor */
652
653
/* Device info */
654
SBG_ECOM_CMD_INFO = 4, /*!< Get basic device information */
655
656
/* Sensor parameters */
657
SBG_ECOM_CMD_INIT_PARAMETERS = 5, /*!< Initial configuration */
658
SBG_ECOM_CMD_SET_MOTION_PROFILE = 6, /*!< Set a new motion profile */
659
SBG_ECOM_CMD_MOTION_PROFILE_ID = 7, /*!< Get motion profile information */
660
SBG_ECOM_CMD_IMU_ALIGNMENT_LEVER_ARM = 8, /*!< Sensor alignment and lever arm on vehicle configuration */
661
SBG_ECOM_CMD_AIDING_ASSIGNMENT = 9, /*!< Aiding assignments such as RTCM / GPS / Odometer configuration */
662
663
/* Magnetometer configuration */
664
SBG_ECOM_CMD_MAGNETOMETER_SET_MODEL = 10, /*!< Set a new magnetometer error model */
665
SBG_ECOM_CMD_MAGNETOMETER_MODEL_ID = 11, /*!< Get magnetometer error model information */
666
SBG_ECOM_CMD_MAGNETOMETER_REJECT_MODE = 12, /*!< Magnetometer aiding rejection mode */
667
SBG_ECOM_CMD_SET_MAG_CALIB = 13, /*!< Set magnetic soft and hard Iron calibration data */
668
669
/* Magnetometer onboard calibration */
670
SBG_ECOM_CMD_START_MAG_CALIB = 14, /*!< Start / reset internal magnetic field logging for calibration. */
671
SBG_ECOM_CMD_COMPUTE_MAG_CALIB = 15, /*!< Compute a magnetic calibration based on previously logged data. */
672
673
/* GNSS configuration */
674
SBG_ECOM_CMD_GNSS_1_SET_MODEL = 16, /*!< Set a new GNSS model */
675
SBG_ECOM_CMD_GNSS_1_MODEL_ID = 17, /*!< Get GNSS model information */
676
SBG_ECOM_CMD_GNSS_1_LEVER_ARM_ALIGNMENT = 18, /*!< GNSS installation configuration (lever arm, antenna alignments) */
677
SBG_ECOM_CMD_GNSS_1_REJECT_MODES = 19, /*!< GNSS aiding rejection modes configuration. */
678
679
/* Odometer configuration */
680
SBG_ECOM_CMD_ODO_CONF = 20, /*!< Odometer gain, direction configuration */
681
SBG_ECOM_CMD_ODO_LEVER_ARM = 21, /*!< Odometer installation configuration (lever arm) */
682
SBG_ECOM_CMD_ODO_REJECT_MODE = 22, /*!< Odometer aiding rejection mode configuration. */
683
684
/* Interfaces configuration */
685
SBG_ECOM_CMD_UART_CONF = 23, /*!< UART interfaces configuration */
686
SBG_ECOM_CMD_CAN_BUS_CONF = 24, /*!< CAN bus interface configuration */
687
SBG_ECOM_CMD_CAN_OUTPUT_CONF = 25, /*!< CAN identifiers configuration */
688
689
/* Events configuration */
690
SBG_ECOM_CMD_SYNC_IN_CONF = 26, /*!< Synchronization inputs configuration */
691
SBG_ECOM_CMD_SYNC_OUT_CONF = 27, /*!< Synchronization outputs configuration */
692
693
/* Output configuration */
694
SBG_ECOM_CMD_NMEA_TALKER_ID = 29, /*!< NMEA talker ID configuration */
695
SBG_ECOM_CMD_OUTPUT_CONF = 30, /*!< Output configuration */
696
SBG_ECOM_CMD_LEGACY_CONT_OUTPUT_CONF = 31, /*!< Legacy serial output mode configuration */
697
698
/* Avanced configuration */
699
SBG_ECOM_CMD_ADVANCED_CONF = 32, /*!< Advanced settings configuration */
700
701
/* Features related commands */
702
SBG_ECOM_CMD_FEATURES = 33, /*!< Retrieve device features */
703
704
/* Licenses related commands */
705
SBG_ECOM_CMD_LICENSE_APPLY = 34, /*!< Upload and apply a new license */
706
707
/* Message class output switch */
708
SBG_ECOM_CMD_OUTPUT_CLASS_ENABLE = 35, /*!< Enable/disable the output of an entire class */
709
710
/* Ethernet configuration */
711
SBG_ECOM_CMD_ETHERNET_CONF = 36, /*!< Set/get Ethernet configuration such as DHCP mode and IP address. */
712
SBG_ECOM_CMD_ETHERNET_INFO = 37, /*!< Return the current IP used by the device. */
713
714
/* Misc. */
715
SBG_ECOM_LOG_ECOM_NUM_CMDS /*!< Helper definition to know the number of commands */
716
} SbgEComCmd;
717
718
719
#endif // AP_EXTERNAL_AHRS_SBG_ENABLED
720
721
722