AP_NavEKF3: do not use fmaxF on floating point values

it returns double, which will not fit into this float
This commit is contained in:
Peter Barker 2023-09-08 12:50:44 +10:00 committed by Andrew Tridgell
parent ac96365a61
commit 10c8af3409
1 changed files with 1 additions and 1 deletions

View File

@ -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