From 2ef7a1e56d70bef2d9d2d73ee51c6e0d481e1b54 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 24 Mar 2024 15:42:57 +0000 Subject: [PATCH 1/3] AP_NavEKF2: use set_and_defualt when changing imu mask --- libraries/AP_NavEKF2/AP_NavEKF2.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index e4fce86ef7c41..bc958e012aef6 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -643,7 +643,7 @@ bool NavEKF2::InitialiseFilter(void) // don't allow more filters than IMUs uint8_t mask = (1U< Date: Sun, 24 Mar 2024 15:42:57 +0000 Subject: [PATCH 2/3] AP_NavEKF3: use set_and_defualt when changing imu mask --- libraries/AP_NavEKF3/AP_NavEKF3.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index d7d4d3c61a8e5..26bbeffc23d5e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -781,7 +781,7 @@ bool NavEKF3::InitialiseFilter(void) // don't run multiple filters for 1 IMU uint8_t mask = (1U< Date: Sun, 24 Mar 2024 16:40:14 +0000 Subject: [PATCH 3/3] AP_DAL: Standalone: add int8 parameter set_and_default method to avoid include --- libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp b/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp index e17981542f9c0..6a9371ada0b73 100644 --- a/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp +++ b/libraries/AP_DAL/examples/AP_DAL_Standalone/main.cpp @@ -9,6 +9,11 @@ void AP_Param::setup_object_defaults(void const*, AP_Param::GroupInfo const*) {} +template +void AP_ParamT::set_and_default(const T &v) {} +template class AP_ParamT; + + int AP_HAL::Util::vsnprintf(char*, size_t, char const*, va_list) { return -1; } void *nologger = nullptr;