mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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:
parent
ac96365a61
commit
10c8af3409
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user