AP_GPS: Add horizontal, vertical and speed accuracy to the GPS_RAW_INT message

This commit is contained in:
Dr.-Ing. Amilcar Do Carmo Lucas 2017-09-22 10:16:12 +02:00 committed by Andrew Tridgell
parent 56d87bfb20
commit 479d4be3fd

View File

@ -890,6 +890,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
last_send_time_ms[chan] = now; last_send_time_ms[chan] = now;
} }
const Location &loc = location(0); const Location &loc = location(0);
float hacc = 0.0f;
float vacc = 0.0f;
float sacc = 0.0f;
horizontal_accuracy(0, hacc);
vertical_accuracy(0, vacc);
speed_accuracy(0, sacc);
mavlink_msg_gps_raw_int_send( mavlink_msg_gps_raw_int_send(
chan, chan,
last_fix_time_ms(0)*(uint64_t)1000, last_fix_time_ms(0)*(uint64_t)1000,
@ -901,7 +907,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
get_vdop(0), get_vdop(0),
ground_speed(0)*100, // cm/s ground_speed(0)*100, // cm/s
ground_course(0)*100, // 1/100 degrees, ground_course(0)*100, // 1/100 degrees,
num_sats(0)); num_sats(0),
0, // TODO: Elipsoid height in mm
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
} }
void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) void AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan)