From 9f02834f6d6a658dcccbb9788165235a5ef82791 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 7 Sep 2015 15:37:13 -0700 Subject: [PATCH] AP_GPS: Broadcast vDOP data over mavlink --- libraries/AP_GPS/AP_GPS.cpp | 4 ++-- libraries/AP_GPS/AP_GPS.h | 8 ++++++++ 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index a8a1c40c86..b854ee9d3a 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -551,7 +551,7 @@ AP_GPS::send_mavlink_gps_raw(mavlink_channel_t chan) loc.lng, // in 1E7 degrees loc.alt * 10UL, // in mm get_hdop(0), - 65535, + get_vdop(0), ground_speed(0)*100, // cm/s ground_course_cd(0), // 1/100 degrees, num_sats(0)); @@ -580,7 +580,7 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) loc.lng, loc.alt * 10UL, get_hdop(1), - 65535, + get_vdop(1), ground_speed(1)*100, // cm/s ground_course_cd(1), // 1/100 degrees, num_sats(1), diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 4effa17146..318bf2a324 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -282,6 +282,14 @@ public: return get_hdop(primary_instance); } + // vertical dilution of precision + uint16_t get_vdop(uint8_t instance) const { + return _GPS_STATE(instance).vdop; + } + uint16_t get_vdop() const { + return get_vdop(primary_instance); + } + // the time we got our last fix in system milliseconds. This is // used when calculating how far we might have moved since that fix uint32_t last_fix_time_ms(uint8_t instance) const {