mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-24 08:44:08 -04:00
AP_NavEKF3: make mag variance reporting consistent
logged scaled variance should match the value used in MAVLink EKF_STATUS_REPORT
This commit is contained in:
parent
6e5f61935c
commit
8be1755b12
@ -598,10 +598,10 @@ void NavEKF3_core::send_status_report(mavlink_channel_t chan)
|
|||||||
} else {
|
} else {
|
||||||
temp = 0.0f;
|
temp = 0.0f;
|
||||||
}
|
}
|
||||||
|
const float mag_max = fmaxf(fmaxf(magVar.x,magVar.y),magVar.z);
|
||||||
|
|
||||||
// send message
|
// send message
|
||||||
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, magVar.length(), temp, tasVar);
|
mavlink_msg_ekf_status_report_send(chan, flags, velVar, posVar, hgtVar, mag_max, temp, tasVar);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// report the reason for why the backend is refusing to initialise
|
// report the reason for why the backend is refusing to initialise
|
||||||
|
Loading…
Reference in New Issue
Block a user