Path: blob/master/libraries/AP_GPS/LogStructure_SBP.h
9594 views
#pragma once12#include <AP_Logger/LogStructure.h>3#include "AP_GPS_config.h"45#define LOG_IDS_FROM_GPS_SBP \6LOG_MSG_SBPHEALTH, \7LOG_MSG_SBPEVENT89// @LoggerMessage: SBPH10// @Description: Swift Health Data11// @Field: TimeUS: Time since system startup12// @Field: CrcError: Number of packet CRC errors on serial connection13// @Field: LastInject: Timestamp of last raw data injection to GPS14// @Field: IARhyp: Current number of integer ambiguity hypotheses1516struct PACKED log_SbpHealth {17LOG_PACKET_HEADER;18uint64_t time_us;19uint32_t crc_error_counter;20uint32_t last_injected_data_ms;21uint32_t last_iar_num_hypotheses;22};2324// @LoggerMessage: SBRE25// @Description: Swift Time Data26// @Field: TimeUS: Time since system startup27// @Field: GWk: GPS week number28// @Field: GMS: Milliseconds through GPS week29// @Field: ns_residual: residual of milliseconds rounding in ns30// @Field: level: GPIO pin levels31// @Field: quality: time quality3233struct PACKED log_SbpEvent {34LOG_PACKET_HEADER;35uint64_t time_us;36uint16_t wn;37uint32_t tow;38int32_t ns_residual;39uint8_t level;40uint8_t quality;41};4243#if AP_GPS_SBP_ENABLED44#define LOG_STRUCTURE_FROM_GPS_SBP \45{ LOG_MSG_SBPHEALTH, sizeof(log_SbpHealth), \46"SBPH", "QIII", "TimeUS,CrcError,LastInject,IARhyp", "s---", "F---" , true }, \47{ LOG_MSG_SBPEVENT, sizeof(log_SbpEvent), \48"SBRE", "QHIiBB", "TimeUS,GWk,GMS,ns_residual,level,quality", "s?????", "F?????" },49#else50#define LOG_STRUCTURE_FROM_GPS_SBP51#endif525354