mirror of https://github.com/ArduPilot/ardupilot
AP_NavEKF2: Send correct data over mavlink status message
This commit is contained in:
parent
1950008248
commit
8630874ef3
|
@ -535,7 +535,7 @@ void NavEKF2_core::send_status_report(mavlink_channel_t chan)
|
|||
getVariances(velVar, posVar, hgtVar, magVar, tasVar, offset);
|
||||
|
||||
// send message
|
||||
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), tasVar);
|
||||
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), sqrtf(auxRngTestRatio));
|
||||
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue