From 8322525431927feb3b91fdbd7975b67ef549a56c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Apr 2014 11:41:10 +1000 Subject: [PATCH] Rover: show next wp when not running a mission this lets the GCS know what wp would be run if auto mode is selected --- APMrover2/GCS_Mavlink.pde | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/APMrover2/GCS_Mavlink.pde b/APMrover2/GCS_Mavlink.pde index 243e48d935..81b72e207d 100644 --- a/APMrover2/GCS_Mavlink.pde +++ b/APMrover2/GCS_Mavlink.pde @@ -518,13 +518,7 @@ static void NOINLINE send_rangefinder(mavlink_channel_t chan) static void NOINLINE send_current_waypoint(mavlink_channel_t chan) { - uint16_t current_cmd_index; - if (mission.state() == AP_Mission::MISSION_RUNNING) { - current_cmd_index = mission.get_current_nav_cmd().index; - }else{ - current_cmd_index = AP_MISSION_CMD_INDEX_NONE; - } - mavlink_msg_mission_current_send(chan, current_cmd_index); + mavlink_msg_mission_current_send(chan, mission.get_current_nav_cmd().index); } static void NOINLINE send_statustext(mavlink_channel_t chan)