diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 4293e78fee..881210c992 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -718,7 +718,6 @@ private: void init_visual_odom(); void update_visual_odom(); void send_pid_tuning(mavlink_channel_t chan); - void gcs_send_mission_item_reached_message(uint16_t mission_index); void gcs_data_stream_send(void); void gcs_check_input(void); void do_erase_logs(void); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 1ad0928b9a..1a42179321 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -2046,14 +2046,6 @@ void Copter::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 Copter::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/ArduCopter/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 8d7e320f58..3d59a90988 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -182,7 +182,7 @@ bool Copter::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;