From 10c8af3409fcd4ea28ca5ddb0678a907a43d0d11 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Sep 2023 12:50:44 +1000 Subject: [PATCH] AP_NavEKF3: do not use fmaxF on floating point values it returns double, which will not fit into this float --- libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp index 2a9eeefdf4..04bf81ec20 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Outputs.cpp @@ -621,7 +621,7 @@ void NavEKF3_core::send_status_report(GCS_MAVLINK &link) const velVar, posVar, hgtVar, - fmaxF(fmaxF(magVar.x,magVar.y),magVar.z), + fmaxf(fmaxf(magVar.x,magVar.y),magVar.z), temp, flags, tasVar