AP_GPS_SBF: fix accuracy reported by driver

This commit is contained in:
Michael Oborne 2016-11-12 10:48:33 +08:00 committed by Randy Mackay
parent ac3744ad2b
commit c62050dc1b
1 changed files with 4 additions and 3 deletions

View File

@ -226,9 +226,10 @@ AP_GPS_SBF::process_message(void)
state.ground_speed = (float)safe_sqrt(ground_vector_sq);
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;
}