diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 1154015f06..35c5c02758 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -97,7 +97,7 @@ void AP_DAL::end_frame(void) } } -void AP_DAL::log_event2(AP_DAL::Event2 event) +void AP_DAL::log_event2(AP_DAL::Event event) { #if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay) end_frame(); @@ -130,7 +130,7 @@ void AP_DAL::log_writeDefaultAirSpeed2(const float aspeed) #endif } -void AP_DAL::log_event3(AP_DAL::Event3 event) +void AP_DAL::log_event3(AP_DAL::Event event) { #if !APM_BUILD_TYPE(APM_BUILD_AP_DAL_Standalone) && !APM_BUILD_TYPE(APM_BUILD_Replay) end_frame(); diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index 40299a002e..a9821b9919 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -32,23 +32,7 @@ public: LogWriteEKF3 = 1<<5, }; - enum class Event2 : uint8_t { - resetGyroBias = 0, - resetHeightDatum = 1, - setInhibitGPS = 2, - setTakeoffExpected = 3, - unsetTakeoffExpected = 4, - setTouchdownExpected = 5, - unsetTouchdownExpected = 6, - setInhibitGpsVertVelUse = 7, - unsetInhibitGpsVertVelUse = 8, - setTerrainHgtStable = 9, - unsetTerrainHgtStable = 10, - requestYawReset = 11, - checkLaneSwitch = 12, - }; - - enum class Event3 : uint8_t { + enum class Event : uint8_t { resetGyroBias = 0, resetHeightDatum = 1, setInhibitGPS = 2, @@ -88,11 +72,11 @@ public: uint32_t micros() const { return _micros; } uint32_t millis() const { return _millis; } - void log_event2(Event2 event); + void log_event2(Event event); void log_SetOriginLLH2(const Location &loc); void log_writeDefaultAirSpeed2(float aspeed); - void log_event3(Event3 event); + void log_event3(Event event); void log_SetOriginLLH3(const Location &loc); void log_writeDefaultAirSpeed3(float aspeed); void log_writeEulerYawAngle(float yawAngle, float yawAngleErr, uint32_t timeStamp_ms, uint8_t type); diff --git a/libraries/AP_DAL/LogStructure.h b/libraries/AP_DAL/LogStructure.h index 0bed35dd76..d25f19f6a8 100644 --- a/libraries/AP_DAL/LogStructure.h +++ b/libraries/AP_DAL/LogStructure.h @@ -118,28 +118,10 @@ struct log_RWA2 { uint8_t _end; }; -// @LoggerMessage: REV3 -// @Description: Replay Event -struct log_REV3 { - uint8_t event; - uint8_t _end; -}; - -// @LoggerMessage: RSO3 -// @Description: Replay Set Origin event -struct log_RSO3 { - int32_t lat; - int32_t lng; - int32_t alt; - uint8_t _end; -}; - -// @LoggerMessage: RWA3 -// @Description: Replay set-default-airspeed event -struct log_RWA3 { - float airspeed; - uint8_t _end; -}; +// same structures for EKF3 +#define log_REV3 log_REV2 +#define log_RSO3 log_RSO2 +#define log_RWA3 log_RWA2 // @LoggerMessage: REY3 // @Description: Replay Euler Yaw event