From e15f72ce58b458f47db1ffc62b84c926a69973a9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 11 Oct 2024 20:15:51 +1100 Subject: [PATCH] AP_DAL: document more replay messages --- libraries/AP_DAL/LogStructure.h | 31 +++++++++++++++++++++++-------- 1 file changed, 23 insertions(+), 8 deletions(-) diff --git a/libraries/AP_DAL/LogStructure.h b/libraries/AP_DAL/LogStructure.h index 873251c7dd..c8ef343584 100644 --- a/libraries/AP_DAL/LogStructure.h +++ b/libraries/AP_DAL/LogStructure.h @@ -40,19 +40,24 @@ LOG_RWOH_MSG, \ LOG_RBOH_MSG -// Replay Data Structures +// @LoggerMessage: RFRH +// @Description: Replay FRame Header struct log_RFRH { uint64_t time_us; uint32_t time_flying_ms; uint8_t _end; }; +// @LoggerMessage: RFRF +// @Description: Replay FRame data - Finished frame struct log_RFRF { uint8_t frame_types; uint8_t core_slow; uint8_t _end; }; +// @LoggerMessage: RFRN +// @Description: Replay FRame - aNother frame header struct log_RFRN { int32_t lat; int32_t lng; @@ -73,7 +78,8 @@ struct log_RFRN { uint8_t _end; }; -// Replay Data Structure - Inertial Sensor header +// @LoggerMessage: RISH +// @Description: Replay Inertial Sensor header struct log_RISH { uint16_t loop_rate_hz; uint8_t first_usable_gyro; @@ -84,7 +90,8 @@ struct log_RISH { uint8_t _end; }; -// Replay Data Structure - Inertial Sensor instance data +// @LoggerMessage: RISI +// @Description: Replay Inertial Sensor instance data struct log_RISI { Vector3f delta_velocity; Vector3f delta_angle; @@ -99,14 +106,14 @@ struct log_RISI { }; // @LoggerMessage: REV2 -// @Description: Replay Event +// @Description: Replay Event (EKF2) struct log_REV2 { uint8_t event; uint8_t _end; }; // @LoggerMessage: RSO2 -// @Description: Replay Set Origin event +// @Description: Replay Set Origin event (EKF2) struct log_RSO2 { int32_t lat; int32_t lng; @@ -115,7 +122,7 @@ struct log_RSO2 { }; // @LoggerMessage: RWA2 -// @Description: Replay set-default-airspeed event +// @Description: Replay set-default-airspeed event (EKF2) struct log_RWA2 { float airspeed; float uncertainty; @@ -123,8 +130,14 @@ struct log_RWA2 { }; // same structures for EKF3 +// @LoggerMessage: REV3 +// @Description: Replay Event (EKF3) #define log_REV3 log_REV2 +// @LoggerMessage: RSO3 +// @Description: Replay Set Origin event (EKF3) #define log_RSO3 log_RSO2 +// @LoggerMessage: RWA3 +// @Description: Replay set-default-airspeed event (EKF3) #define log_RWA3 log_RWA2 // @LoggerMessage: REY3 @@ -220,14 +233,16 @@ struct log_RGPJ { uint8_t _end; }; -// Replay Data Structure - Airspeed Sensor header +// @LoggerMessage: RASH +// @Description: Replay Airspeed Sensor Header struct log_RASH { uint8_t num_sensors; uint8_t primary; uint8_t _end; }; -// Replay Data Structure - Airspeed Sensor instance +// @LoggerMessage: RASI +// @Description: Replay Airspeed Sensor Instance data struct log_RASI { float airspeed; uint32_t last_update_ms;