|
|
|
@ -890,6 +890,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
@@ -890,6 +890,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
|
|
|
|
last_send_time_ms[chan] = now; |
|
|
|
|
} |
|
|
|
|
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( |
|
|
|
|
chan, |
|
|
|
|
last_fix_time_ms(0)*(uint64_t)1000, |
|
|
|
@ -901,7 +907,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
@@ -901,7 +907,12 @@ void AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan)
|
|
|
|
|
get_vdop(0), |
|
|
|
|
ground_speed(0)*100, // cm/s
|
|
|
|
|
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) |
|
|
|
|