From 66d8be825fd44d573309e55dad4a80c281b92782 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 2 Dec 2021 13:04:02 +1100 Subject: [PATCH] AP_Logger: move LogOriginType into AP_AHRS only used to log the origins by the AHRS library --- libraries/AP_AHRS/AP_AHRS.h | 2 +- libraries/AP_AHRS/AP_AHRS_Logging.cpp | 4 ++-- libraries/AP_Logger/LogStructure.h | 5 ----- 3 files changed, 3 insertions(+), 8 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 0bf9f0299a..1b0510bb56 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -430,7 +430,7 @@ public: ekf_origin = 0, ahrs_home = 1 }; - void Write_Origin(uint8_t origin_type, const Location &loc) const; + void Write_Origin(LogOriginType origin_type, const Location &loc) const; void Write_POS(void) const; // return a smoothed and corrected gyro vector in radians/second diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index 1d92118181..7d4ed282d9 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -63,12 +63,12 @@ void AP_AHRS::Write_Attitude(const Vector3f &targets) const AP::logger().WriteBlock(&pkt, sizeof(pkt)); } -void AP_AHRS::Write_Origin(uint8_t origin_type, const Location &loc) const +void AP_AHRS::Write_Origin(LogOriginType origin_type, const Location &loc) const { const struct log_ORGN pkt{ LOG_PACKET_HEADER_INIT(LOG_ORGN_MSG), time_us : AP_HAL::micros64(), - origin_type : origin_type, + origin_type : (uint8_t)origin_type, latitude : loc.lat, longitude : loc.lng, altitude : loc.alt diff --git a/libraries/AP_Logger/LogStructure.h b/libraries/AP_Logger/LogStructure.h index a966072161..6e9dbbe7a0 100644 --- a/libraries/AP_Logger/LogStructure.h +++ b/libraries/AP_Logger/LogStructure.h @@ -1433,8 +1433,3 @@ enum LogMessages : uint8_t { static_assert(_LOG_LAST_MSG_ <= 255, "Too many message formats"); static_assert(LOG_MODE_MSG < 128, "Duplicate message format IDs"); - -enum LogOriginType { - ekf_origin = 0, - ahrs_home = 1 -};