mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_GPS_SBF: fix accuracy reported by driver
This commit is contained in:
parent
ac3744ad2b
commit
c62050dc1b
@ -227,8 +227,9 @@ AP_GPS_SBF::process_message(void)
|
||||
|
||||
state.ground_course = wrap_360(degrees(atan2f(state.velocity[1], state.velocity[0])));
|
||||
|
||||
state.horizontal_accuracy = (float)temp.HAccuracy * 0.01f;
|
||||
state.vertical_accuracy = (float)temp.VAccuracy * 0.01f;
|
||||
// value is expressed as twice the rms error = int16 * 0.01/2
|
||||
state.horizontal_accuracy = (float)temp.HAccuracy * 0.005f;
|
||||
state.vertical_accuracy = (float)temp.VAccuracy * 0.005f;
|
||||
state.have_horizontal_accuracy = true;
|
||||
state.have_vertical_accuracy = true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user