Defines all sbgECom commands identifiers. More...
Go to the source code of this file.
Macros | |
#define | SBG_ECOM_BUILD_ID(classId, logId) (((uint16_t)classId << 8) | (uint8_t)logId) |
Typedefs | |
typedef enum _SbgEComClass | SbgEComClass |
typedef enum _SbgEComCmd | SbgEComCmd |
typedef enum _SbgEComIdNmea1Log | SbgEComIdNmea1Log |
typedef enum _SbgEComIdThirdParty | SbgEComIdThirdParty |
typedef enum _SbgEComLog | SbgEComLog |
typedef enum _SbgEComLog1MsgId | SbgEComLog1 |
typedef uint8_t | SbgEComMsgId |
typedef enum _SbgEComNmeaLog | SbgEComNmeaLog |
Functions | |
SBG_INLINE bool | sbgEComMsgClassIsALog (SbgEComClass msgClass) |
Defines all sbgECom commands identifiers.
Copyright (C) 2007-2013, SBG Systems SAS. All rights reserved.
This source code is intended for use only by SBG Systems SAS and those that have explicit written permission to use it from SBG Systems SAS.
THIS CODE AND INFORMATION IS PROVIDED "AS IS" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A PARTICULAR PURPOSE.
Definition in file sbgEComIds.h.
#define SBG_ECOM_BUILD_ID | ( | classId, | |
logId | |||
) | (((uint16_t)classId << 8) | (uint8_t)logId) |
Helper macro to build an id with its class
Definition at line 37 of file sbgEComIds.h.
typedef enum _SbgEComClass SbgEComClass |
Enum that defines all the message classes available.
typedef enum _SbgEComCmd SbgEComCmd |
Enum that defines all the available commands for the sbgECom library.
typedef enum _SbgEComIdNmea1Log SbgEComIdNmea1Log |
Enum that defines all the available Proprietary Nmea output logs from the sbgECom library.
typedef enum _SbgEComIdThirdParty SbgEComIdThirdParty |
Enum that defines all the available Proprietary output logs from the sbgECom library.
typedef enum _SbgEComLog SbgEComLog |
Enum that defines all the available ECom output logs from the sbgECom library.
typedef enum _SbgEComLog1MsgId SbgEComLog1 |
Enum that defines all the available ECom output logs in the class SBG_ECOM_CLASS_LOG_ECOM_1
typedef uint8_t SbgEComMsgId |
This type defines any message identifier. Because message identifiers enum will be different with each class id, we use a generic uint8_t rather than an enum.
Definition at line 289 of file sbgEComIds.h.
typedef enum _SbgEComNmeaLog SbgEComNmeaLog |
Enum that defines all the available Nmea output logs from the sbgECom library.
enum _SbgEComClass |
Enum that defines all the message classes available.
Definition at line 46 of file sbgEComIds.h.
enum _SbgEComCmd |
Enum that defines all the available commands for the sbgECom library.
Enumerator | |
---|---|
SBG_ECOM_CMD_ACK | Acknowledge |
SBG_ECOM_CMD_SETTINGS_ACTION | Performs various settings actions |
SBG_ECOM_CMD_IMPORT_SETTINGS | Imports a new settings structure to the sensor |
SBG_ECOM_CMD_EXPORT_SETTINGS | Export the whole configuration from the sensor |
SBG_ECOM_CMD_INFO | Get basic device information |
SBG_ECOM_CMD_INIT_PARAMETERS | Initial configuration |
SBG_ECOM_CMD_MOTION_PROFILE_ID | Set/get motion profile information |
SBG_ECOM_CMD_IMU_ALIGNMENT_LEVER_ARM | Sensor alignment and lever arm on vehicle configuration |
SBG_ECOM_CMD_AIDING_ASSIGNMENT | Aiding assignments such as RTCM / GPS / Odometer configuration |
SBG_ECOM_CMD_MAGNETOMETER_MODEL_ID | Set/get magnetometer error model information |
SBG_ECOM_CMD_MAGNETOMETER_REJECT_MODE | Magnetometer aiding rejection mode |
SBG_ECOM_CMD_SET_MAG_CALIB | Set magnetic soft and hard Iron calibration data |
SBG_ECOM_CMD_START_MAG_CALIB | Start / reset internal magnetic field logging for calibration. |
SBG_ECOM_CMD_COMPUTE_MAG_CALIB | Compute a magnetic calibration based on previously logged data. |
SBG_ECOM_CMD_GNSS_1_MODEL_ID | Set/get GNSS model information |
SBG_ECOM_CMD_GNSS_1_LEVER_ARM_ALIGNMENT | DEPRECATED: GNSS installation configuration (lever arm, antenna alignments) |
SBG_ECOM_CMD_GNSS_1_INSTALLATION | Define or retrieve the GNSS 1 main and secondary lever arms configuration. |
SBG_ECOM_CMD_GNSS_1_REJECT_MODES | GNSS aiding rejection modes configuration. |
SBG_ECOM_CMD_ODO_CONF | Odometer gain, direction configuration |
SBG_ECOM_CMD_ODO_LEVER_ARM | Odometer installation configuration (lever arm) |
SBG_ECOM_CMD_ODO_REJECT_MODE | Odometer aiding rejection mode configuration. |
SBG_ECOM_CMD_UART_CONF | UART interfaces configuration |
SBG_ECOM_CMD_CAN_BUS_CONF | CAN bus interface configuration |
SBG_ECOM_CMD_CAN_OUTPUT_CONF | CAN identifiers configuration |
SBG_ECOM_CMD_SYNC_IN_CONF | Synchronization inputs configuration |
SBG_ECOM_CMD_SYNC_OUT_CONF | Synchronization outputs configuration |
SBG_ECOM_CMD_NMEA_TALKER_ID | NMEA talker ID configuration |
SBG_ECOM_CMD_OUTPUT_CONF | Output configuration |
SBG_ECOM_CMD_LEGACY_CONT_OUTPUT_CONF | Legacy serial output mode configuration |
SBG_ECOM_CMD_ADVANCED_CONF | Advanced settings configuration |
SBG_ECOM_CMD_FEATURES | Retrieve device features |
SBG_ECOM_CMD_LICENSE_APPLY | Upload and apply a new license |
SBG_ECOM_CMD_OUTPUT_CLASS_ENABLE | Enable/disable the output of an entire class |
SBG_ECOM_CMD_ETHERNET_CONF | Set/get Ethernet configuration such as DHCP mode and IP address. |
SBG_ECOM_CMD_ETHERNET_INFO | Return the current IP used by the device. |
SBG_ECOM_CMD_VALIDITY_THRESHOLDS | Set/get Validity flag thresholds for position, velocity, attitude and heading |
SBG_ECOM_CMD_DVL_MODEL_ID | Set/get DVL model id to use |
SBG_ECOM_CMD_DVL_INSTALLATION | DVL installation configuration (lever arm, alignments) |
SBG_ECOM_CMD_DVL_REJECT_MODES | DVL aiding rejection modes configuration. |
SBG_ECOM_CMD_AIRDATA_MODEL_ID | Set/get AirData model id and protocol to use. |
SBG_ECOM_CMD_AIRDATA_LEVER_ARM | AirData installation configuration (lever arm, offsets) |
SBG_ECOM_CMD_AIRDATA_REJECT_MODES | AirData aiding rejection modes configuration. |
SBG_ECOM_CMD_ODO_CAN_CONF | Configuration for CAN based odometer (CAN ID & DBC) |
SBG_ECOM_LOG_ECOM_NUM_CMDS | Helper definition to know the number of commands |
Definition at line 196 of file sbgEComIds.h.
enum _SbgEComIdNmea1Log |
Enum that defines all the available Proprietary Nmea output logs from the sbgECom library.
Enumerator | |
---|---|
SBG_ECOM_LOG_NMEA_1_PRDID | RDI proprietary sentence. Pitch, Roll, Heading |
SBG_ECOM_LOG_NMEA_1_PSBGI | SBG Systems proprietary sentence. Rotation rates, accelerations. |
SBG_ECOM_LOG_NMEA_1_PASHR | Proprietary sentence. Roll, Pitch, Heading, Heave. |
SBG_ECOM_LOG_NMEA_1_PSBGB | SBG Systems proprietary sentence. Attitude, heading, heave, angular rates, velocity. |
SBG_ECOM_LOG_NMEA_1_PHINF | Ixblue NMEA like log used to output Status information. |
SBG_ECOM_LOG_NMEA_1_PHTRO | Ixblue NMEA like log used to output Roll and Pitch. |
SBG_ECOM_LOG_NMEA_1_PHLIN | Ixblue NMEA like log used to output Surge, Sway and Heave. |
SBG_ECOM_LOG_NMEA_1_PHOCT | Ixblue NMEA like log used to output attitude and ship motion. |
SBG_ECOM_LOG_NMEA_1_INDYN | Ixblue NMEA like log used to output position, heading, attitude, attitude rate and speed. |
SBG_ECOM_LOG_NMEA_1_NUM_MESSAGES | Helper definition to know the number of NMEA messages |
Definition at line 158 of file sbgEComIds.h.
enum _SbgEComIdThirdParty |
Enum that defines all the available Proprietary output logs from the sbgECom library.
Enumerator | |
---|---|
SBG_ECOM_THIRD_PARTY_TSS1 | Roll, Pitch, Heave, heave accelerations |
SBG_ECOM_THIRD_PARTY_KVH | Roll, Pitch, Yaw |
SBG_ECOM_THIRD_PARTY_PD0 | Teledyne PD0 DVL proprietary frame. |
SBG_ECOM_THIRD_PARTY_SIMRAD_1000 | Konsberg SimRad 1000 proprietary frame that outputs Roll, Pitch and Heading. |
SBG_ECOM_THIRD_PARTY_SIMRAD_3000 | Konsberg SimRad 3000 proprietary frame that outputs Roll, Pitch and Heading. |
SBG_ECOM_THIRD_PARTY_SEAPATH_B26 | Konsberg Seapth Binary Log 26 used for MBES FM mode. |
SBG_ECOM_THIRD_PARTY_DOLOG_HRP | DOLOG Heading, Roll, Pitch proprietary and binary message. |
SBG_ECOM_THIRD_PARTY_AHRS_500 | Crossbow AHRS-500 Data Packet output with attitude, rate, acceleration and status. |
SBG_ECOM_LOG_THIRD_PARTY_NUM_MESSAGES | Helper definition to know the number of third party messages |
Definition at line 177 of file sbgEComIds.h.
enum _SbgEComLog |
Enum that defines all the available ECom output logs from the sbgECom library.
Enumerator | |
---|---|
SBG_ECOM_LOG_STATUS | Status general, clock, com aiding, solution, heave |
SBG_ECOM_LOG_UTC_TIME | Provides UTC time reference |
SBG_ECOM_LOG_IMU_DATA | Includes IMU status, acc., gyro, temp delta speeds and delta angles values |
SBG_ECOM_LOG_MAG | Magnetic data with associated accelerometer on each axis |
SBG_ECOM_LOG_MAG_CALIB | Magnetometer calibration data (raw buffer) |
SBG_ECOM_LOG_EKF_EULER | Includes roll, pitch, yaw and their accuracies on each axis |
SBG_ECOM_LOG_EKF_QUAT | Includes the 4 quaternions values |
SBG_ECOM_LOG_EKF_NAV | Position and velocities in NED coordinates with the accuracies on each axis |
SBG_ECOM_LOG_SHIP_MOTION | Heave, surge and sway and accelerations on each axis. |
SBG_ECOM_LOG_GPS1_VEL | GPS velocities from primary or secondary GPS receiver |
SBG_ECOM_LOG_GPS1_POS | GPS positions from primary or secondary GPS receiver |
SBG_ECOM_LOG_GPS1_HDT | GPS true heading from dual antenna system |
SBG_ECOM_LOG_GPS1_RAW | GPS 1 raw data for post processing. |
SBG_ECOM_LOG_GPS2_VEL | GPS 2 velocity log data. |
SBG_ECOM_LOG_GPS2_POS | GPS 2 position log data. |
SBG_ECOM_LOG_GPS2_HDT | GPS 2 true heading log data. |
SBG_ECOM_LOG_GPS2_RAW | GPS 2 raw data for post processing. |
SBG_ECOM_LOG_ODO_VEL | Provides odometer velocity |
SBG_ECOM_LOG_EVENT_A | Event markers sent when events are detected on sync in A pin |
SBG_ECOM_LOG_EVENT_B | Event markers sent when events are detected on sync in B pin |
SBG_ECOM_LOG_EVENT_C | Event markers sent when events are detected on sync in C pin |
SBG_ECOM_LOG_EVENT_D | Event markers sent when events are detected on sync in D pin |
SBG_ECOM_LOG_EVENT_E | Event markers sent when events are detected on sync in E pin |
SBG_ECOM_LOG_DVL_BOTTOM_TRACK | Doppler Velocity Log for bottom tracking data. |
SBG_ECOM_LOG_DVL_WATER_TRACK | Doppler Velocity log for water layer data. |
SBG_ECOM_LOG_SHIP_MOTION_HP | Return delayed ship motion such as surge, sway, heave. |
SBG_ECOM_LOG_AIR_DATA | Air Data aiding such as barometric altimeter and true air speed. |
SBG_ECOM_LOG_USBL | Raw USBL position data for subsea navigation. |
SBG_ECOM_LOG_DEBUG_0 | Debug Log. |
SBG_ECOM_LOG_IMU_RAW_DATA | Factory only log. |
SBG_ECOM_LOG_DEBUG_1 | Debug Log. |
SBG_ECOM_LOG_DEBUG_2 | Debug Log. |
SBG_ECOM_LOG_DEBUG_3 | Debug Log. |
SBG_ECOM_LOG_IMU_SHORT | Short IMU message recommended for post processing usages. |
SBG_ECOM_LOG_EVENT_OUT_A | Event marker used to time stamp each generated Sync Out A signal. |
SBG_ECOM_LOG_EVENT_OUT_B | Event marker used to time stamp each generated Sync Out B signal. |
SBG_ECOM_LOG_DEPTH | Depth sensor measurement log used for subsea navigation. |
SBG_ECOM_LOG_DIAG | Diagnostic log. |
SBG_ECOM_LOG_ECOM_NUM_MESSAGES | Helper definition to know the number of ECom messages |
Definition at line 69 of file sbgEComIds.h.
enum _SbgEComLog1MsgId |
Enum that defines all the available ECom output logs in the class SBG_ECOM_CLASS_LOG_ECOM_1
Enumerator | |
---|---|
SBG_ECOM_LOG_FAST_IMU_DATA | Provides accelerometers, gyroscopes, time and status at 1KHz rate. |
SBG_ECOM_LOG_ECOM_1_NUM_MESSAGES | Helper definition to know the number of ECom messages |
Definition at line 133 of file sbgEComIds.h.
enum _SbgEComNmeaLog |
Enum that defines all the available Nmea output logs from the sbgECom library.
Enumerator | |
---|---|
SBG_ECOM_LOG_NMEA_GGA | Latitude, Longitude, Altitude, Quality indicator. |
SBG_ECOM_LOG_NMEA_RMC | Latitude, Longitude, velocity, course over ground. |
SBG_ECOM_LOG_NMEA_ZDA | UTC Time. |
SBG_ECOM_LOG_NMEA_HDT | Heading (True). |
SBG_ECOM_LOG_NMEA_GST | GPS Pseudorange Noise Statistics. |
SBG_ECOM_LOG_NMEA_VBW | Water referenced and ground referenced speed data. |
SBG_ECOM_LOG_NMEA_DPT | Depth sensor output. |
SBG_ECOM_LOG_NMEA_VTG | Track an Speed over the ground. |
SBG_ECOM_LOG_NMEA_NUM_MESSAGES | Helper definition to know the number of NMEA messages |
Definition at line 142 of file sbgEComIds.h.
SBG_INLINE bool sbgEComMsgClassIsALog | ( | SbgEComClass | msgClass | ) |
Test if the message class is a binary log one.
[in] | msgClass | Message class. |
Definition at line 301 of file sbgEComIds.h.