AP_GPS: fixed build

This commit is contained in:
Andrew Tridgell 2020-01-10 19:11:52 +11:00
parent ac65b6ec47
commit 9261b32430

View File

@ -1002,7 +1002,7 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
hacc * 1000, // one-sigma standard deviation in mm
vacc * 1000, // one-sigma standard deviation in mm
sacc * 1000, // one-sigma standard deviation in mm/s
0); // TODO one-sigma heading accuracy standard deviation
0, 0); // TODO one-sigma heading accuracy standard deviation
}
#if GPS_MAX_RECEIVERS > 1
@ -1032,7 +1032,7 @@ void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)
ground_course(1)*100, // 1/100 degrees,
num_sats(1),
state[1].rtk_num_sats,
state[1].rtk_age_ms);
state[1].rtk_age_ms, 0);
}
#endif // GPS_MAX_RECEIVERS