mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: Publish the number of satellites in the RTK correction messages, and the age of the RTK correction messages
This commit is contained in:
parent
ae47ac5a09
commit
b791fef7cb
|
@ -206,6 +206,8 @@ AP_GPS_NOVA::process_message(void)
|
|||
state.vertical_accuracy = (float) bestposu.hgtsdev;
|
||||
state.have_horizontal_accuracy = true;
|
||||
state.have_vertical_accuracy = true;
|
||||
state.rtk_age_ms = bestposu.diffage * 1000;
|
||||
state.rtk_num_sats = bestposu.svsused;
|
||||
|
||||
if (bestposu.solstat == 0) // have a solution
|
||||
{
|
||||
|
|
|
@ -223,7 +223,8 @@ 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.rtk_age_ms = temp.MeanCorrAge * 10;
|
||||
|
||||
// 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;
|
||||
|
|
Loading…
Reference in New Issue