diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index f7a7a2f1e0..41944d77ec 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -2134,14 +2134,6 @@ void Plane::mavlink_delay_cb() in_mavlink_delay = false; } -/* - * send a mission item reached message and load the index before the send attempt in case it may get delayed - */ -void Plane::gcs_send_mission_item_reached_message(uint16_t mission_index) -{ - gcs().send_mission_item_reached_message(mission_index); -} - /* * send data streams in the given rate range on both links */ diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8ff64ca1f8..65cae85776 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -822,7 +822,6 @@ private: void send_aoa_ssa(mavlink_channel_t chan); bool telemetry_delayed(mavlink_channel_t chan); - void gcs_send_mission_item_reached_message(uint16_t mission_index); void gcs_data_stream_send(void); void gcs_update(void); void gcs_send_airspeed_calibration(const Vector3f &vg); diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 3b0be36ab0..999ece81d0 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1004,7 +1004,7 @@ bool Plane::verify_command_callback(const AP_Mission::Mission_Command& cmd) // send message to GCS if (cmd_complete) { - gcs_send_mission_item_reached_message(cmd.index); + gcs().send_mission_item_reached_message(cmd.index); } return cmd_complete; diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index cffad479b1..df0430dcb5 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -197,7 +197,7 @@ void Plane::update_loiter(uint16_t radius) loiter.start_time_ms = millis(); if (control_mode == GUIDED || control_mode == AVOID_ADSB) { // starting a loiter in GUIDED means we just reached the target point - gcs_send_mission_item_reached_message(0); + gcs().send_mission_item_reached_message(0); } if (quadplane.guided_mode_enabled()) { quadplane.guided_start();