mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: correct check of reported antenna distance vs stated offset
This commit is contained in:
parent
e979a9076c
commit
b30563e10b
|
@ -367,7 +367,7 @@ bool AP_GPS_Backend::calculate_moving_base_yaw(AP_GPS::GPS_State &interim_state,
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
if ((offset_dist - reported_distance) > (min_dist * permitted_error_length_pct)) {
|
if (fabsf(offset_dist - reported_distance) > (min_dist * permitted_error_length_pct)) {
|
||||||
// the magnitude of the vector is much further then we were expecting
|
// the magnitude of the vector is much further then we were expecting
|
||||||
Debug("Exceeded the permitted error margin %f > %f",
|
Debug("Exceeded the permitted error margin %f > %f",
|
||||||
(double)(offset_dist - reported_distance), (double)(min_dist * permitted_error_length_pct));
|
(double)(offset_dist - reported_distance), (double)(min_dist * permitted_error_length_pct));
|
||||||
|
|
Loading…
Reference in New Issue