Path: blob/master/libraries/AP_ExternalAHRS/AP_ExternalAHRS_SBG_structs.h
6351 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15support for serial connected SBG INS system16*/1718#pragma once1920#include "AP_ExternalAHRS_config.h"2122#if AP_EXTERNAL_AHRS_SBG_ENABLED2324/*!25* Clock status and UTC time status definitions.26*/27#define SBG_ECOM_CLOCK_STATUS_SHIFT (1u) /*!< Shift used to extract the clock status part. */28#define SBG_ECOM_CLOCK_STATUS_MASK (0x000Fu) /*!< Mask used to keep only the clock status part. */29#define SBG_ECOM_CLOCK_UTC_STATUS_SHIFT (6u) /*!< Shift used to extract the clock UTC status part. */30#define SBG_ECOM_CLOCK_UTC_STATUS_MASK (0x000Fu) /*!< Mask used to keep only the clock UTC status part. */3132/*!33* Clock status enum.34*/35typedef enum _SbgEComClockStatus36{37SBG_ECOM_CLOCK_ERROR = 0, /*!< An error has occurred on the clock estimation. */38SBG_ECOM_CLOCK_FREE_RUNNING = 1, /*!< The clock is only based on the internal crystal. */39SBG_ECOM_CLOCK_STEERING = 2, /*!< A PPS has been detected and the clock is converging to it. */40SBG_ECOM_CLOCK_VALID = 3 /*!< The clock has converged to the PPS and is within 500ns. */41} SbgEComClockStatus;4243/*!44* Status for the UTC time data.45*/46typedef enum _SbgEComClockUtcStatus47{48SBG_ECOM_UTC_INVALID = 0, /*!< The UTC time is not known, we are just propagating the UTC time internally. */49SBG_ECOM_UTC_NO_LEAP_SEC = 1, /*!< We have received valid UTC time information but we don't have the leap seconds information. */50SBG_ECOM_UTC_VALID = 2 /*!< We have received valid UTC time data with valid leap seconds. */51} SbgEComClockUtcStatus;5253static inline SbgEComClockStatus sbgEComLogUtcGetClockStatus(uint16_t status) {54return (SbgEComClockStatus)((status >> SBG_ECOM_CLOCK_STATUS_SHIFT) & SBG_ECOM_CLOCK_STATUS_MASK);55}56static inline SbgEComClockUtcStatus sbgEComLogUtcGetClockUtcStatus(uint16_t status) {57return (SbgEComClockUtcStatus)((status >> SBG_ECOM_CLOCK_UTC_STATUS_SHIFT) & SBG_ECOM_CLOCK_UTC_STATUS_MASK);58}596061typedef struct PACKED _SbgLogUtcData62{63uint32_t timeStamp; /*!< Time in us since the sensor power up. */64uint16_t status; /*!< UTC time and clock status information */65uint16_t year; /*!< Year for example: 2013. */66int8_t month; /*!< Month in year [1 .. 12]. */67int8_t day; /*!< Day in month [1 .. 31]. */68int8_t hour; /*!< Hour in day [0 .. 23]. */69int8_t minute; /*!< Minute in hour [0 .. 59]. */70int8_t second; /*!< Second in minute [0 .. 60]. (60 is used only when a leap second is added) */71int32_t nanoSecond; /*!< Nanosecond of current second in ns. */72uint32_t gpsTimeOfWeek; /*!< GPS time of week in ms. */73} SbgLogUtcData;74757677/*!78* Structure that stores data for the SBG_ECOM_LOG_GPS#_VEL message.79*/80typedef struct PACKED _SbgLogGpsVel81{82uint32_t timeStamp; /*!< Time in us since the sensor power up. */83uint32_t status; /*!< GPS velocity status, type and bitmask. */84uint32_t timeOfWeek; /*!< GPS time of week in ms. */85float velocity[3]; /*!< GPS North, East, Down velocity in m.s^-1. */86float velocityAcc[3]; /*!< GPS North, East, Down velocity 1 sigma accuracy in m.s^-1. */87float course; /*!< Track ground course in degrees. */88float courseAcc; /*!< Course accuracy in degrees. */89} SbgLogGpsVel;9091/*!92* Structure that stores data for the SBG_ECOM_LOG_GPS#_POS message.93*/94typedef struct PACKED _SbgLogGpsPos95{96uint32_t timeStamp; /*!< Time in us since the sensor power up. */97uint32_t status; /*!< GPS position status, type and bitmask. */98uint32_t timeOfWeek; /*!< GPS time of week in ms. */99double latitude; /*!< Latitude in degrees, positive north. */100double longitude; /*!< Longitude in degrees, positive east. */101double altitude; /*!< Altitude above Mean Sea Level in meters. */102float undulation; /*!< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation). */103float latitudeAccuracy; /*!< 1 sigma latitude accuracy in meters. */104float longitudeAccuracy; /*!< 1 sigma longitude accuracy in meters. */105float altitudeAccuracy; /*!< 1 sigma altitude accuracy in meters. */106uint8_t numSvUsed; /*!< Number of space vehicles used to compute the solution (since version 1.4). */107uint16_t baseStationId; /*!< Base station id for differential corrections (0-4095). Set to 0xFFFF if differential corrections are not used (since version 1.4). */108uint16_t differentialAge; /*!< Differential correction age in 0.01 seconds. Set to 0XFFFF if differential corrections are not used (since version 1.4). */109} SbgLogGpsPos;110111/*!112* Structure that stores data for the SBG_ECOM_LOG_GPS#_HDT message.113*/114typedef struct PACKED _SbgLogGpsHdt115{116uint32_t timeStamp; /*!< Time in us since the sensor power up. */117uint16_t status; /*!< GPS HDT status, type and bitmask. */118uint32_t timeOfWeek; /*!< GPS time of week in ms. */119float heading; /*!< GPS true heading in degrees. */120float headingAccuracy; /*!< 1 sigma GPS true heading accuracy in degrees. */121float pitch; /*!< GPS pitch angle measured from the master to the rover in degrees. */122float pitchAccuracy; /*!< 1 signa GPS pitch angle accuarcy in degrees. */123} SbgLogGpsHdt;124125126127/*!128* Structure that stores data for the SBG_ECOM_LOG_IMU_DATA message.129*/130typedef struct PACKED _SbgLogImuData131{132uint32_t timeStamp; /*!< Time in us since the sensor power up. */133uint16_t status; /*!< IMU status bitmask. */134float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */135float gyroscopes[3]; /*!< X, Y, Z gyroscopes in rad.s^-1. */136float temperature; /*!< Internal temperature in C. */137float deltaVelocity[3]; /*!< X, Y, Z delta velocity in m.s^-2. */138float deltaAngle[3]; /*!< X, Y, Z delta angle in rad.s^-1. */139} SbgLogImuData;140141/*!142* Structure that stores the data for SBG_ECOM_LOG_FAST_IMU_DATA message143*/144typedef struct PACKED _SbgLogFastImuData145{146uint32_t timeStamp; /*!< Time in us since the sensor power up. */147uint16_t status; /*!< IMU status bitmask. */148float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */149float gyroscopes[3]; /*!< X, Y, Z gyroscopes in rad.s^-1. */150} SbgLogFastImuData;151152/*!153* Log inertial data status mask definitions154*/155#define SBG_ECOM_IMU_COM_OK (0x00000001u << 0) /*!< Set to 1 if the communication with the IMU is ok. */156#define SBG_ECOM_IMU_STATUS_BIT (0x00000001u << 1) /*!< Set to 1 if the IMU passes general Built in Tests (calibration, CPU, ...). */157158#define SBG_ECOM_IMU_ACCEL_X_BIT (0x00000001u << 2) /*!< Set to 1 if the accelerometer X passes Built In Test. */159#define SBG_ECOM_IMU_ACCEL_Y_BIT (0x00000001u << 3) /*!< Set to 1 if the accelerometer Y passes Built In Test. */160#define SBG_ECOM_IMU_ACCEL_Z_BIT (0x00000001u << 4) /*!< Set to 1 if the accelerometer Z passes Built In Test. */161162#define SBG_ECOM_IMU_GYRO_X_BIT (0x00000001u << 5) /*!< Set to 1 if the gyroscope X passes Built In Test. */163#define SBG_ECOM_IMU_GYRO_Y_BIT (0x00000001u << 6) /*!< Set to 1 if the gyroscope Y passes Built In Test. */164#define SBG_ECOM_IMU_GYRO_Z_BIT (0x00000001u << 7) /*!< Set to 1 if the gyroscope Z passes Built In Test. */165166#define SBG_ECOM_IMU_ACCELS_IN_RANGE (0x00000001u << 8) /*!< Set to 1 if all accelerometers are within operating range. */167#define SBG_ECOM_IMU_GYROS_IN_RANGE (0x00000001u << 9) /*!< Set to 1 if all gyroscopes are within operating range. */168#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. */169170/*!171* Standard gyroscope scale factor.172*/173#define SBG_ECOM_LOG_IMU_GYRO_SCALE_STD (67108864.0f)174175/*!176* High range gyroscope scale factor derived from 10000 degrees per second maximum range.177*178* Calculation: (2^31 - 1) / (10000 * π / 180)179*/180#define SBG_ECOM_LOG_IMU_GYRO_SCALE_HIGH (12304174.0f)181182/*!183* Maximum value for the standard scale factor, in radians per second.184*185* Approximately equivalent to 1833 °/s.186*/187#define SBG_ECOM_LOG_IMU_GYRO_SCALE_STD_MAX_RAD ((float)INT32_MAX / SBG_ECOM_LOG_IMU_GYRO_SCALE_STD)188189/*!190* Standard accelerometer scale factor.191*/192#define SBG_ECOM_LOG_IMU_ACCEL_SCALE_STD (1048576.0f)193194/*!195* Standard temperature scale factor.196*/197#define SBG_ECOM_LOG_IMU_TEMP_SCALE_STD (256.0f)198199/*!200* Structure that stores data for the SBG_ECOM_LOG_IMU_SHORT message.201*202* This message is sent asynchronously and must be used for post processing.203*204* The delta angle values are scaled based on the gyroscopes output. If any output exceeds205* a predefined limit, the scale factor switches from standard to high range to prevent saturation.206*/207typedef struct PACKED _SbgEComLogImuShort208{209uint32_t timeStamp; /*!< Time in us since the sensor power up. */210uint16_t status; /*!< IMU status bitmask. */211int32_t deltaVelocity[3]; /*!< X, Y, Z delta velocity. Unit is 1048576 LSB for 1 m.s^-2. */212int32_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. */213int16_t temperature; /*!< IMU average temperature. Unit is 256 LSB for 1°C. */214} SbgEComLogImuShort;215216217218#define SBG_ECOM_LOG_EKF_SOLUTION_MODE_MASK (0x0000000Fu) /*!< Mask used to keep only the clock status part. */219220/*!221* Solution filter mode enum.222*/223typedef enum _SbgEComSolutionMode224{225SBG_ECOM_SOL_MODE_UNINITIALIZED = 0, /*!< The Kalman filter is not initialized and the returned data are all invalid. */226SBG_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. */227SBG_ECOM_SOL_MODE_AHRS = 2, /*!< A heading reference is available, the Kalman filter provides full orientation but navigation data drift freely. */228SBG_ECOM_SOL_MODE_NAV_VELOCITY = 3, /*!< The Kalman filter computes orientation and velocity. Position is freely integrated from velocity estimation. */229SBG_ECOM_SOL_MODE_NAV_POSITION = 4 /*!< Nominal mode, the Kalman filter computes all parameters (attitude, velocity, position). Absolute position is provided. */230} SbgEComSolutionMode;231232/*!233* EKF computed orientation using euler angles.234*/235typedef struct PACKED _SbgLogEkfEulerData236{237uint32_t timeStamp; /*!< Time in us since the sensor power up. */238float euler[3]; /*!< Roll, Pitch and Yaw angles in rad. */239float eulerStdDev[3]; /*!< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad. */240uint32_t status; /*!< EKF solution status bitmask and enum. */241} SbgLogEkfEulerData;242243/*!244* EFK computed orientation using quaternion.245*/246typedef struct PACKED _SbgLogEkfQuatData247{248uint32_t timeStamp; /*!< Time in us since the sensor power up. */249float quaternion[4]; /*!< Orientation quaternion stored in W, X, Y, Z form. */250float eulerStdDev[3]; /*!< Roll, Pitch and Yaw angles 1 sigma standard deviation in rad. */251uint32_t status; /*!< EKF solution status bitmask and enum. */252} SbgLogEkfQuatData;253254/*!255* EFK computed navigation data.256*/257typedef struct PACKED _SbgLogEkfNavData258{259uint32_t timeStamp; /*!< Time in us since the sensor power up. */260float velocity[3]; /*!< North, East, Down velocity in m.s^-1. */261float velocityStdDev[3]; /*!< North, East, Down velocity 1 sigma standard deviation in m.s^-1. */262double position[3]; /*!< Latitude, Longitude in degrees positive North and East.263Altitude above Mean Sea Level in meters. */264float undulation; /*!< Altitude difference between the geoid and the Ellipsoid in meters (Height above Ellipsoid = altitude + undulation). */265float positionStdDev[3]; /*!< Latitude, longitude and altitude 1 sigma standard deviation in meters. */266uint32_t status; /*!< EKF solution status bitmask and enum. */267} SbgLogEkfNavData;268269//----------------------------------------------------------------------//270//- Log Air Data status definitions -//271//----------------------------------------------------------------------//272273/*!274* Air Data sensor status mask definitions275*/276#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. */277#define SBG_ECOM_AIR_DATA_PRESSURE_ABS_VALID (0x0001u << 1) /*!< Set to 1 if the pressure field is filled and valid. */278#define SBG_ECOM_AIR_DATA_ALTITUDE_VALID (0x0001u << 2) /*!< Set to 1 if the barometric altitude field is filled and valid. */279#define SBG_ECOM_AIR_DATA_PRESSURE_DIFF_VALID (0x0001u << 3) /*!< Set to 1 if the differential pressure field is filled and valid. */280#define SBG_ECOM_AIR_DATA_AIRPSEED_VALID (0x0001u << 4) /*!< Set to 1 if the true airspeed field is filled and valid. */281#define SBG_ECOM_AIR_DATA_TEMPERATURE_VALID (0x0001u << 5) /*!< Set to 1 if the output air temperature field is filled and valid. */282283/*!284* Log structure for AirData.285*/286typedef struct PACKED _SbgLogAirData287{288uint32_t timeStamp; /*!< Time in us since the sensor power up OR measurement delay in us. */289uint16_t status; /*!< Airdata sensor status bitmask. */290float pressureAbs; /*!< Raw absolute pressure measured by the barometer sensor in Pascals. */291float altitude; /*!< Altitude computed from barometric altimeter in meters and positive upward. */292float pressureDiff; /*!< Raw differential pressure measured by the pitot tube in Pascal. */293float trueAirspeed; /*!< True airspeed measured by a pitot tube in m.s^-1 and positive forward. */294float airTemperature; /*!< Outside air temperature in C that could be used to compute true airspeed from differential pressure. */295} SbgLogAirData;296297/*!298* Log magnetometer data status mask definitions299*/300#define SBG_ECOM_MAG_MAG_X_BIT (0x00000001u << 0) /*!< Set to 1 if the magnetometer X passes Built In Test. */301#define SBG_ECOM_MAG_MAG_Y_BIT (0x00000001u << 1) /*!< Set to 1 if the magnetometer Y passes Built In Test. */302#define SBG_ECOM_MAG_MAG_Z_BIT (0x00000001u << 2) /*!< Set to 1 if the magnetometer Z passes Built In Test. */303304#define SBG_ECOM_MAG_ACCEL_X_BIT (0x00000001u << 3) /*!< Set to 1 if the accelerometer X passes Built In Test. */305#define SBG_ECOM_MAG_ACCEL_Y_BIT (0x00000001u << 4) /*!< Set to 1 if the accelerometer Y passes Built In Test. */306#define SBG_ECOM_MAG_ACCEL_Z_BIT (0x00000001u << 5) /*!< Set to 1 if the accelerometer Z passes Built In Test. */307308#define SBG_ECOM_MAG_MAGS_IN_RANGE (0x00000001u << 6) /*!< Set to 1 if all magnetometers are within operating range. */309#define SBG_ECOM_MAG_ACCELS_IN_RANGE (0x00000001u << 7) /*!< Set to 1 if all accelerometers are within operating range. */310311#define SBG_ECOM_MAG_CALIBRATION_OK (0x00000001u << 8) /*!< Set to 1 if the magnetometers seems to be calibrated. */312313/*!314* Structure that stores data for the SBG_ECOM_LOG_MAG message.315*/316typedef struct PACKED _SbgLogMag317{318uint32_t timeStamp; /*!< Time in us since the sensor power up. */319uint16_t status; /*!< Magnetometer status bitmask. */320float magnetometers[3]; /*!< X, Y, Z magnetometer data in A.U. */321float accelerometers[3]; /*!< X, Y, Z accelerometers in m.s^-2. */322} SbgLogMag;323324/*!325* Structure that stores data for the SBG_ECOM_LOG_MAG_CALIB message.326*/327typedef struct PACKED _SbgLogMagCalib328{329uint32_t timeStamp; /*!< Time in us since the sensor power up. */330uint16_t reserved; /*!< Reserved for future use. */331uint8_t magData[16]; /*!< Magnetometers calibration data. */332} SbgLogMagCalib;333334335typedef struct PACKED _SbgLogStatusData336{337uint32_t timeStamp; /*!< Time in us since the sensor power up. */338uint16_t generalStatus; /*!< General status bitmask and enums. */339uint16_t reserved1; /*!< Reserved status field for future use */340uint32_t comStatus; /*!< Communication status bitmask and enums. */341uint32_t aidingStatus; /*!< Aiding equipments status bitmask and enums. */342uint32_t reserved2; /*!< Reserved status field for future use. */343uint16_t reserved3; /*!< Reserved status field for future use. */344uint32_t uptime; /*!< System uptime in seconds. */345} SbgLogStatusData;346347/*!348* Helper structure to retrieve device info.349*/350#define SBG_ECOM_INFO_PRODUCT_CODE_LENGTH (32)351typedef struct PACKED _SbgEComDeviceInfo352{353uint8_t productCode[SBG_ECOM_INFO_PRODUCT_CODE_LENGTH]; /*!< Human readable Product Code. */354uint32_t serialNumber; /*!< Device serial number */355uint32_t calibationRev; /*!< Calibration data revision */356uint16_t calibrationYear; /*!< Device Calibration Year */357uint8_t calibrationMonth; /*!< Device Calibration Month */358uint8_t calibrationDay; /*!< Device Calibration Day */359uint32_t hardwareRev; /*!< Device hardware revision */360uint32_t firmwareRev; /*!< Firmware revision */361} SbgEComDeviceInfo;362363364365/*!366* Generic errors definitions for SBG Systems projects.367*/368typedef enum _SbgErrorCode : uint16_t369{370SBG_NO_ERROR = 0, /*!< The operation was successfully executed. */371SBG_ERROR, /*!< We have a generic error. */372SBG_NULL_POINTER, /*!< A pointer is null. */373SBG_INVALID_CRC, /*!< The received frame has an invalid CRC. */374SBG_INVALID_FRAME, /*!< The received frame is invalid <br> */375/*!< We have received an unexpected frame (not the cmd we are waiting for or with an invalid data size.<br> */376/*!< This could be caused by a desync between questions and answers.<br> */377/*!< You should flush the serial port to fix this. */378SBG_TIME_OUT, /*!< We have started to receive a frame but not the end. */379SBG_WRITE_ERROR, /*!< All bytes hasn't been written. */380SBG_READ_ERROR, /*!< All bytes hasn't been read. */381SBG_BUFFER_OVERFLOW, /*!< A buffer is too small to contain so much data. */382SBG_INVALID_PARAMETER, /*!< An invalid parameter has been found. */383SBG_NOT_READY, /*!< A device isn't ready (Rx isn't ready for example). */384SBG_MALLOC_FAILED, /*!< Failed to allocate a buffer. */385SGB_CALIB_MAG_NOT_ENOUGH_POINTS, /*!< Not enough points were available to perform magnetometers calibration. */386SBG_CALIB_MAG_INVALID_TAKE, /*!< The calibration procedure could not be properly executed due to insufficient precision. */387SBG_CALIB_MAG_SATURATION, /*!< Saturation were detected when attempt to calibrate magnetos. */388SBG_CALIB_MAG_POINTS_NOT_IN_A_PLANE, /*!< 2D calibration procedure could not be performed. */389390SBG_DEVICE_NOT_FOUND, /*!< A device couldn't be founded or opened PC only error code */391SBG_OPERATION_CANCELLED, /*!< An operation was cancelled. PC only error code*/392SBG_NOT_CONTINUOUS_FRAME, /*!< We have received a frame that isn't a continuous one. PC only error code*/393394SBG_INCOMPATIBLE_HARDWARE, /*!< Hence valid; the command cannot be executed because of hardware incompatibility */395SBG_INVALID_VERSION /*!< Incompatible version */396} SbgErrorCode;397398399typedef struct PACKED _SbgEComACK400{401uint8_t ackMsg;402uint8_t ackMsgClass;403SbgErrorCode ackErrorCode;404} SbgEComAck;405406/*!407* Defintion of all the settings actions available.408*/409typedef enum _SbgEComSettingsAction410{411SBG_ECOM_REBOOT_ONLY = 0, /*!< Only reboot the device. */412SBG_ECOM_SAVE_SETTINGS = 1, /*!< Save the settings to non-volatile memory and then reboot the device. */413SBG_ECOM_RESTORE_DEFAULT_SETTINGS = 2 /*!< Restore default settings, save them to non-volatile memory and reboot the device. */414} SbgEComSettingsAction;415416417typedef enum _SbgEComGpsPosType418{419SBG_ECOM_POS_NO_SOLUTION = 0, /*!< No valid solution available. */420SBG_ECOM_POS_UNKNOWN_TYPE = 1, /*!< An unknown solution type has been computed. */421SBG_ECOM_POS_SINGLE = 2, /*!< Single point solution position. */422SBG_ECOM_POS_PSRDIFF = 3, /*!< Standard Pseudorange Differential Solution (DGPS). */423SBG_ECOM_POS_SBAS = 4, /*!< SBAS satellite used for differential corrections. */424SBG_ECOM_POS_OMNISTAR = 5, /*!< Omnistar VBS Position (L1 sub-meter). */425SBG_ECOM_POS_RTK_FLOAT = 6, /*!< Floating RTK ambiguity solution (20 cms RTK). */426SBG_ECOM_POS_RTK_INT = 7, /*!< Integer RTK ambiguity solution (2 cms RTK). */427SBG_ECOM_POS_PPP_FLOAT = 8, /*!< Precise Point Positioning with float ambiguities. */428SBG_ECOM_POS_PPP_INT = 9, /*!< Precise Point Positioning with fixed ambiguities. */429SBG_ECOM_POS_FIXED = 10 /*!< Fixed location solution position. */430} SbgEComGpsPosType;431432#define SBG_ECOM_GPS_POS_TYPE_SHIFT (6u) /*!< Shift used to extract the GPS position type part. */433#define SBG_ECOM_GPS_POS_TYPE_MASK (0x0000003Fu) /*!< Mask used to keep only the GPS position type part. */434435436437/*!438* Define if the onboard magnetic calibration should acquiere points for a 3D or 2D calibration.439*/440typedef enum _SbgEComMagCalibMode441{442SBG_ECOM_MAG_CALIB_MODE_2D = 1, /*!< Tell the device that the magnetic calibration will be performed with limited motions.443This calibration mode is only designed to be used when roll and pitch motions are less than 5.444To work correctly, the device should be rotated through at least a full circle. */445SBG_ECOM_MAG_CALIB_MODE_3D = 2 /*!< Tell the device to start a full 3D magnetic calibration procedure.446The 3D magnetic calibration offers the best accuracy but needs at least motion of 30 on the roll and pitch angles. */447} SbgEComMagCalibMode;448449450/*!451* Used to select the expected dynamics during the magnetic calibration.452*/453typedef enum _SbgEComMagCalibBandwidth454{455SBG_ECOM_MAG_CALIB_LOW_BW = 0, /*!< Tell the device that low dynamics will be observed during the magnetic calibration process. */456SBG_ECOM_MAG_CALIB_MEDIUM_BW = 1, /*!< Tell the device that normal dynamics will be observed during the magnetic calibration process. */457SBG_ECOM_MAG_CALIB_HIGH_BW = 2 /*!< Tell the device that high dynamics will be observed during the magnetic calibration process. */458} SbgEComMagCalibBandwidth;459460/*!461* General quality indicator of an onboard magnetic calibration.462*/463typedef enum _SbgEComMagCalibQuality464{465SBG_ECOM_MAG_CALIB_QUAL_OPTIMAL = 0, /*!< All acquired points fit very well on a unit sphere after the calibration. */466SBG_ECOM_MAG_CALIB_QUAL_GOOD = 1, /*!< Small deviations of the magnetic field norm have been detected. The magnetic calibration should although provide accurate heading. */467SBG_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. */468SBG_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. */469} SbgEComMagCalibQuality;470471/*!472* Confidence indicator on results of an onbard magnetic calibration.473*/474typedef enum _SbgEComMagCalibConfidence475{476SBG_ECOM_MAG_CALIB_TRUST_HIGH = 0, /*!< Reported quality indicator can be trusted as enough remarkable magnetic field points have been acquired. */477SBG_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. */478SBG_ECOM_MAG_CALIB_TRUST_LOW = 2 /*!< Even if the quality indicator could report an excellent calibration,479The data set used to compute the magnetic calibration was not meaningful enough to compute meaningful quality indicators.480This calibration should be used carefully. */481} SbgEComMagCalibConfidence;482483#define SBG_ECOM_MAG_CALIB_NOT_ENOUGH_POINTS (0x0001u) /*!< Not enough valid magnetic points have been acquired. */484#define SBG_ECOM_MAG_CALIB_TOO_MUCH_DISTORTIONS (0x0002u) /*!< Unable to compute a magnetic calibration due to magnetic interferences or incorrect data set distribution. */485#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. */486#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. */487#define SBG_ECOM_MAG_CALIB_Z_MOTION_ISSUE (0x0010u) /*!< For a 3D or 2D calibration: not enough motion on Z axis. */488#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. */489490491/*!492* Helper structure to retrieve onboard magnetic calibration results.493*/494typedef struct PACKED _SbgEComMagCalibResults495{496SbgEComMagCalibQuality quality; /*!< General magnetic calibration quality indicator. */497SbgEComMagCalibConfidence confidence; /*!< Confidence indicator that should be read to interpret the quality indicator. */498uint16_t advancedStatus; /*!< Set of bit masks used to report advanced information on the magnetic calibration status.*/499500float beforeMeanError; /*!< Mean magnetic field norm error observed before calibration. */501float beforeStdError; /*!< Standard deviation of the magnetic field norm error observed before calibration. */502float beforeMaxError; /*!< Maximum magnetic field norm error observed before calibration. */503504float afterMeanError; /*!< Mean magnetic field norm error observed after calibration. */505float afterStdError; /*!< Standard deviation of the magnetic field norm error observed after calibration. */506float afterMaxError; /*!< Maximum magnetic field norm error observed after calibration. */507508float meanAccuracy; /*!< Mean expected heading accuracy in radians. */509float stdAccuracy; /*!< Standard deviation of the expected heading accuracy in radians. */510float maxAccuracy; /*!< Maximum expected heading accuracy in radians. */511512uint16_t numPoints; /*!< Number of magnetic field points stored internally and used to compute the magnetic calibration. */513uint16_t maxNumPoints; /*!< Maximum number of magnetic field points that can be stored internally. */514float offset[3]; /*!< Computed Hard Iron correction vector offset. */515float matrix[9]; /*!< Computed Hard & Soft Iron correction matrix. */516} SbgEComMagCalibResults;517518519typedef struct _SbgEComSetMagCal520{521float offset[3]; /*!< Computed Hard Iron correction vector offset. */522float matrix[9]; /*!< Computed Hard & Soft Iron correction matrix. */523} SbgEComSetMagCal;524525526/*!527* Enum that defines all the message classes available.528*/529typedef enum _SbgEComClass530{531SBG_ECOM_CLASS_LOG_ECOM_0 = 0x00, /*!< Class that contains sbgECom protocol input/output log messages. */532533SBG_ECOM_CLASS_LOG_ECOM_1 = 0x01, /*!< Class that contains special sbgECom output messages that handle high frequency output */534535SBG_ECOM_CLASS_LOG_NMEA_0 = 0x02, /*!< Class that contains NMEA (and NMEA like) output logs. <br>536Note: This class is only used for identification purpose and does not contain any sbgECom message. */537SBG_ECOM_CLASS_LOG_NMEA_1 = 0x03, /*!< Class that contains proprietary NMEA (and NMEA like) output logs. <br>538Note: This class is only used for identification purpose and does not contain any sbgECom message. */539SBG_ECOM_CLASS_LOG_THIRD_PARTY_0 = 0x04, /*!< Class that contains third party output logs.540Note: This class is only used for identification purpose and does not contain any sbgECom message. */541SBG_ECOM_CLASS_LOG_CMD_0 = 0x10 /*!< Class that contains sbgECom protocol commands */542} SbgEComClass;543544//----------------------------------------------------------------------//545//- Definition of all messages id for sbgECom -//546//----------------------------------------------------------------------//547548/*!549* Enum that defines all the available ECom output logs from the sbgECom library.550*/551typedef enum _SbgEComLog552{553SBG_ECOM_LOG_STATUS = 1, /*!< Status general, clock, com aiding, solution, heave */554555SBG_ECOM_LOG_UTC_TIME = 2, /*!< Provides UTC time reference */556557SBG_ECOM_LOG_IMU_DATA = 3, /*!< DEPRECATED: Synchronous IMU measurements (time aligned to UTC - NEVER use for Post Processing). */558559SBG_ECOM_LOG_MAG = 4, /*!< Magnetic data with associated accelerometer on each axis */560SBG_ECOM_LOG_MAG_CALIB = 5, /*!< Magnetometer calibration data (raw buffer) */561562SBG_ECOM_LOG_EKF_EULER = 6, /*!< Includes roll, pitch, yaw and their accuracies on each axis */563SBG_ECOM_LOG_EKF_QUAT = 7, /*!< Includes the 4 quaternions values */564SBG_ECOM_LOG_EKF_NAV = 8, /*!< Position and velocities in NED coordinates with the accuracies on each axis */565566SBG_ECOM_LOG_SHIP_MOTION = 9, /*!< Heave, surge and sway and accelerations on each axis. */567568SBG_ECOM_LOG_GPS1_VEL = 13, /*!< GPS velocities from primary or secondary GPS receiver */569SBG_ECOM_LOG_GPS1_POS = 14, /*!< GPS positions from primary or secondary GPS receiver */570SBG_ECOM_LOG_GPS1_HDT = 15, /*!< GPS true heading from dual antenna system */571572SBG_ECOM_LOG_GPS2_VEL = 16, /*!< GPS 2 velocity log data. */573SBG_ECOM_LOG_GPS2_POS = 17, /*!< GPS 2 position log data. */574SBG_ECOM_LOG_GPS2_HDT = 18, /*!< GPS 2 true heading log data. */575576SBG_ECOM_LOG_ODO_VEL = 19, /*!< Provides odometer velocity */577578SBG_ECOM_LOG_EVENT_A = 24, /*!< Event markers sent when events are detected on sync in A pin */579SBG_ECOM_LOG_EVENT_B = 25, /*!< Event markers sent when events are detected on sync in B pin */580SBG_ECOM_LOG_EVENT_C = 26, /*!< Event markers sent when events are detected on sync in C pin */581SBG_ECOM_LOG_EVENT_D = 27, /*!< Event markers sent when events are detected on sync in D pin */582SBG_ECOM_LOG_EVENT_E = 28, /*!< Event markers sent when events are detected on sync in E pin */583584SBG_ECOM_LOG_DVL_BOTTOM_TRACK = 29, /*!< Doppler Velocity Log for bottom tracking data. */585SBG_ECOM_LOG_DVL_WATER_TRACK = 30, /*!< Doppler Velocity log for water layer data. */586587SBG_ECOM_LOG_GPS1_RAW = 31, /*!< GPS 1 raw data for post processing. */588589SBG_ECOM_LOG_SHIP_MOTION_HP = 32, /*!< Return delayed ship motion such as surge, sway, heave. */590591SBG_ECOM_LOG_AIR_DATA = 36, /*!< Air Data aiding such as barometric altimeter and true air speed. */592593SBG_ECOM_LOG_USBL = 37, /*!< Raw USBL position data for sub-sea navigation. */594595SBG_ECOM_LOG_GPS2_RAW = 38, /*!< GPS 2 raw data for post processing. */596597598SBG_ECOM_LOG_IMU_SHORT = 44, /*!< Asynchronous IMU measurements output at the IMU rate and to use for Post Processing with Qinertia. */599600SBG_ECOM_LOG_EVENT_OUT_A = 45, /*!< Event marker used to timestamp each generated Sync Out A signal. */601SBG_ECOM_LOG_EVENT_OUT_B = 46, /*!< Event marker used to timestamp each generated Sync Out B signal. */602603SBG_ECOM_LOG_DEPTH = 47, /*!< Depth sensor measurement log used for sub-sea navigation. */604SBG_ECOM_LOG_DIAG = 48, /*!< Diagnostic log. */605606SBG_ECOM_LOG_RTCM_RAW = 49, /*!< RTCM raw data. */607608SBG_ECOM_LOG_GPS1_SAT = 50, /*!< GPS 1 Satellite data. */609SBG_ECOM_LOG_GPS2_SAT = 51, /*!< GNSS2 Satellite data. */610611SBG_ECOM_LOG_EKF_ROT_ACCEL_BODY = 52, /*!< INS body rotation rate and lateral acceleration (bias, earth rotation and gravity free compensated). */612SBG_ECOM_LOG_EKF_ROT_ACCEL_NED = 53, /*!< INS North/East/Down rotation rate and lateral acceleration (bias, earth rotation and gravity free compensated). */613SBG_ECOM_LOG_EKF_VEL_BODY = 54, /*!< INS X,Y,Z body velocity and standard deviation. */614615SBG_ECOM_LOG_SESSION_INFO = 55, /*!< Session information, including device information and current settings. */616617SBG_ECOM_LOG_EKF_DEBUG = 56, /*!< EKF debug data. */618619SBG_ECOM_LOG_PTP_STATUS = 57, /*!< PTP status. */620621SBG_ECOM_LOG_VELOCITY_1 = 58, /*!< Generic velocity 1 log. */622623SBG_ECOM_LOG_VIB_MON_FFT = 59, /*!< Vibration monitoring FFT data for post processing. */624SBG_ECOM_LOG_VIB_MON_REPORT = 60, /*!< Vibration monitoring report information. */625626SBG_ECOM_LOG_ECOM_NUM_MESSAGES /*!< Helper definition to know the number of ECom messages */627} SbgEComLog;628629/*!630* Enum that defines all the available ECom output logs in the class SBG_ECOM_CLASS_LOG_ECOM_1631*/632typedef enum _SbgEComLog1MsgId633{634SBG_ECOM_LOG_FAST_IMU_DATA = 0, /*!< Provides accelerometers, gyroscopes, time and status at 1KHz rate. */635SBG_ECOM_LOG_ECOM_1_NUM_MESSAGES /*!< Helper definition to know the number of ECom messages */636} SbgEComLog1;637638639/*!640* Enum that defines all the available commands for the sbgECom library.641*/642typedef enum _SbgEComCmd643{644/* Acknowledge */645SBG_ECOM_CMD_ACK = 0, /*!< Acknowledge */646647/* Special settings commands */648SBG_ECOM_CMD_SETTINGS_ACTION = 1, /*!< Performs various settings actions */649SBG_ECOM_CMD_IMPORT_SETTINGS = 2, /*!< Imports a new settings structure to the sensor */650SBG_ECOM_CMD_EXPORT_SETTINGS = 3, /*!< Export the whole configuration from the sensor */651652/* Device info */653SBG_ECOM_CMD_INFO = 4, /*!< Get basic device information */654655/* Sensor parameters */656SBG_ECOM_CMD_INIT_PARAMETERS = 5, /*!< Initial configuration */657SBG_ECOM_CMD_SET_MOTION_PROFILE = 6, /*!< Set a new motion profile */658SBG_ECOM_CMD_MOTION_PROFILE_ID = 7, /*!< Get motion profile information */659SBG_ECOM_CMD_IMU_ALIGNMENT_LEVER_ARM = 8, /*!< Sensor alignment and lever arm on vehicle configuration */660SBG_ECOM_CMD_AIDING_ASSIGNMENT = 9, /*!< Aiding assignments such as RTCM / GPS / Odometer configuration */661662/* Magnetometer configuration */663SBG_ECOM_CMD_MAGNETOMETER_SET_MODEL = 10, /*!< Set a new magnetometer error model */664SBG_ECOM_CMD_MAGNETOMETER_MODEL_ID = 11, /*!< Get magnetometer error model information */665SBG_ECOM_CMD_MAGNETOMETER_REJECT_MODE = 12, /*!< Magnetometer aiding rejection mode */666SBG_ECOM_CMD_SET_MAG_CALIB = 13, /*!< Set magnetic soft and hard Iron calibration data */667668/* Magnetometer onboard calibration */669SBG_ECOM_CMD_START_MAG_CALIB = 14, /*!< Start / reset internal magnetic field logging for calibration. */670SBG_ECOM_CMD_COMPUTE_MAG_CALIB = 15, /*!< Compute a magnetic calibration based on previously logged data. */671672/* GNSS configuration */673SBG_ECOM_CMD_GNSS_1_SET_MODEL = 16, /*!< Set a new GNSS model */674SBG_ECOM_CMD_GNSS_1_MODEL_ID = 17, /*!< Get GNSS model information */675SBG_ECOM_CMD_GNSS_1_LEVER_ARM_ALIGNMENT = 18, /*!< GNSS installation configuration (lever arm, antenna alignments) */676SBG_ECOM_CMD_GNSS_1_REJECT_MODES = 19, /*!< GNSS aiding rejection modes configuration. */677678/* Odometer configuration */679SBG_ECOM_CMD_ODO_CONF = 20, /*!< Odometer gain, direction configuration */680SBG_ECOM_CMD_ODO_LEVER_ARM = 21, /*!< Odometer installation configuration (lever arm) */681SBG_ECOM_CMD_ODO_REJECT_MODE = 22, /*!< Odometer aiding rejection mode configuration. */682683/* Interfaces configuration */684SBG_ECOM_CMD_UART_CONF = 23, /*!< UART interfaces configuration */685SBG_ECOM_CMD_CAN_BUS_CONF = 24, /*!< CAN bus interface configuration */686SBG_ECOM_CMD_CAN_OUTPUT_CONF = 25, /*!< CAN identifiers configuration */687688/* Events configuration */689SBG_ECOM_CMD_SYNC_IN_CONF = 26, /*!< Synchronization inputs configuration */690SBG_ECOM_CMD_SYNC_OUT_CONF = 27, /*!< Synchronization outputs configuration */691692/* Output configuration */693SBG_ECOM_CMD_NMEA_TALKER_ID = 29, /*!< NMEA talker ID configuration */694SBG_ECOM_CMD_OUTPUT_CONF = 30, /*!< Output configuration */695SBG_ECOM_CMD_LEGACY_CONT_OUTPUT_CONF = 31, /*!< Legacy serial output mode configuration */696697/* Avanced configuration */698SBG_ECOM_CMD_ADVANCED_CONF = 32, /*!< Advanced settings configuration */699700/* Features related commands */701SBG_ECOM_CMD_FEATURES = 33, /*!< Retrieve device features */702703/* Licenses related commands */704SBG_ECOM_CMD_LICENSE_APPLY = 34, /*!< Upload and apply a new license */705706/* Message class output switch */707SBG_ECOM_CMD_OUTPUT_CLASS_ENABLE = 35, /*!< Enable/disable the output of an entire class */708709/* Ethernet configuration */710SBG_ECOM_CMD_ETHERNET_CONF = 36, /*!< Set/get Ethernet configuration such as DHCP mode and IP address. */711SBG_ECOM_CMD_ETHERNET_INFO = 37, /*!< Return the current IP used by the device. */712713/* Misc. */714SBG_ECOM_LOG_ECOM_NUM_CMDS /*!< Helper definition to know the number of commands */715} SbgEComCmd;716717718#endif // AP_EXTERNAL_AHRS_SBG_ENABLED719720721722