mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 02:48:28 -04:00
AP_NavEKF3: set a min yaw accuracy from GPS of 5 degrees
GPS modules tend to be rather optimistic about their yaw accuracy. By setting a min or 5 degrees we prevent the user constantly getting warnings about yaw innovations
This commit is contained in:
parent
0b435559bd
commit
f24de4e2bc
@ -622,6 +622,12 @@ void NavEKF3_core::readGpsData()
|
|||||||
// if the GPS has yaw data then input that as well
|
// if the GPS has yaw data then input that as well
|
||||||
float yaw_deg, yaw_accuracy_deg;
|
float yaw_deg, yaw_accuracy_deg;
|
||||||
if (AP::gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) {
|
if (AP::gps().gps_yaw_deg(yaw_deg, yaw_accuracy_deg)) {
|
||||||
|
// GPS modules are rather too optimistic about their
|
||||||
|
// accuracy. Set to min of 5 degrees here to prevent
|
||||||
|
// the user constantly receiving warnings about high
|
||||||
|
// normalised yaw innovations
|
||||||
|
const float min_yaw_accuracy_deg = 5.0f;
|
||||||
|
yaw_accuracy_deg = MAX(yaw_accuracy_deg, min_yaw_accuracy_deg);
|
||||||
writeEulerYawAngle(radians(yaw_deg), radians(yaw_accuracy_deg), gpsDataNew.time_ms, 2);
|
writeEulerYawAngle(radians(yaw_deg), radians(yaw_accuracy_deg), gpsDataNew.time_ms, 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user