From 30df8796ce2ebb6e4d69c6842d493be6855a7f19 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 29 May 2013 21:44:08 +1000 Subject: [PATCH] Copter: fixed loading of waypoints copter code assumes that command_total includes the home waypoint --- ArduCopter/GCS_Mavlink.pde | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 451068e3cc..efb48ac6c3 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1573,7 +1573,11 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) waypoint_receiving = true; waypoint_sending = false; waypoint_request_i = 0; - waypoint_request_last= g.command_total; + // note that ArduCopter sets waypoint_request_last to + // command_total-1, whereas plane and rover use + // command_total. This is because the copter code assumes + // command_total includes home + waypoint_request_last= g.command_total - 1; waypoint_timelast_request = 0; break; }