From d5670ace3bdf9ce851460a3452b7a46c7652c146 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 12 May 2022 08:04:36 +1000 Subject: [PATCH] AP_NavEKF3: fixed use of configured() vs configured_in_storage() --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index da6846cb96..93a4a46ea0 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1609,7 +1609,7 @@ void NavEKF3::writeWheelOdom(float delAng, float delTime, uint32_t timeStamp_ms, void NavEKF3::convert_parameters() { // exit immediately if param conversion has been done before - if (sources.configured_in_storage()) { + if (sources.configured()) { return; } @@ -1646,12 +1646,12 @@ void NavEKF3::convert_parameters() case 3: default: // EK3_GPS_TYPE == 3 (No GPS) we don't know what to do, could be optical flow, beacon or external nav - sources.mark_configured_in_storage(); + sources.mark_configured(); break; } } else { // mark configured in storage so conversion is only run once - sources.mark_configured_in_storage(); + sources.mark_configured(); } // use EK3_ALT_SOURCE to set EK3_SRC1_POSZ