diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index d990ed58e6..3bcaefc6d4 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -439,7 +439,7 @@ void Rover::update_current_mode(void) if (rtl_complete || verify_RTL()) { // we have reached destination so stop where we are if (fabsf(g2.motors.get_throttle()) > g.throttle_min.get()) { - gcs_send_mission_item_reached_message(0); + gcs().send_mission_item_reached_message(0); } g2.motors.set_throttle(g.throttle_min.get()); g2.motors.set_steering(0.0f); diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index b02d0be3c2..d67a5e88b5 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1592,14 +1592,6 @@ void Rover::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 Rover::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/APMrover2/Rover.h b/APMrover2/Rover.h index 69ba475c09..e96cf9582a 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -451,7 +451,6 @@ private: void send_rangefinder(mavlink_channel_t chan); void send_current_waypoint(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_retry_deferred(void); diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index ed638516f9..7f47ffea8d 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -145,7 +145,7 @@ bool Rover::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;