From 9994e9b7732584cb940a9a2f8767e2d20f5caf4a Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar Do Carmo Lucas" Date: Mon, 3 Jul 2017 21:42:04 +0200 Subject: [PATCH] Copter: improve stream descriptions (NFC) --- ArduCopter/GCS_Mavlink.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index e20d7e8ee4..f65439bb55 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -606,7 +606,7 @@ const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = { // @Param: EXT_STAT // @DisplayName: Extended status stream rate to ground station - // @Description: Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station + // @Description: Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station // @Units: Hz // @Range: 0 10 // @Increment: 1 @@ -722,7 +722,7 @@ GCS_MAVLINK_Copter::data_stream_send(void) send_message(MSG_EXTENDED_STATUS1); // SYS_STATUS, POWER_STATUS send_message(MSG_EXTENDED_STATUS2); // MEMINFO send_message(MSG_CURRENT_WAYPOINT); - send_message(MSG_GPS_RAW); + send_message(MSG_GPS_RAW); // GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available) send_message(MSG_NAV_CONTROLLER_OUTPUT); send_message(MSG_FENCE_STATUS); }