From da1ded7cb94ef72abee61501dbe668a2d2d9d2c4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 16 Jan 2019 11:14:08 +1100 Subject: [PATCH] GCS_MAVLink: rename queued_waypoint_send to queued_mission_request_send --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 37ff969c79..1c4261e8bc 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -124,7 +124,7 @@ public: void send_text(MAV_SEVERITY severity, const char *fmt, ...); void send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list); void queued_param_send(); - void queued_waypoint_send(); + void queued_mission_request_send(); // packetReceived is called on any successful decode of a mavlink message virtual void packetReceived(const mavlink_status_t &status, mavlink_message_t &msg); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index fb24e808d9..76ea199da2 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -174,7 +174,7 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager * handling code */ void -GCS_MAVLINK::queued_waypoint_send() +GCS_MAVLINK::queued_mission_request_send() { if (initialised && waypoint_receiving && @@ -852,7 +852,7 @@ bool GCS_MAVLINK::handle_mission_item(mavlink_message_t *msg, AP_Mission &missio waypoint_timelast_request = AP_HAL::millis(); // if we have enough space, then send the next WP immediately if (HAVE_PAYLOAD_SPACE(chan, MISSION_ITEM)) { - queued_waypoint_send(); + queued_mission_request_send(); } else { send_message(MSG_NEXT_WAYPOINT); } @@ -3616,7 +3616,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id) break; case MSG_NEXT_WAYPOINT: CHECK_PAYLOAD_SIZE(MISSION_REQUEST); - queued_waypoint_send(); + queued_mission_request_send(); ret = true; break; default: