From 1e51988ecc023c09764dc4b3fb3f64756d6a39f1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 16 Sep 2012 15:05:48 +1000 Subject: [PATCH] APM: allow update of last waypoint fixed off by one error --- ArduPlane/GCS_Mavlink.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 48826c39f1..62b9cef019 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1407,7 +1407,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) if (mavlink_check_target(packet.target_system,packet.target_component)) break; // start waypoint receiving - if (packet.start_index >= g.command_total || + if (packet.start_index > g.command_total || packet.end_index > g.command_total || packet.end_index < packet.start_index) { send_text(SEVERITY_LOW,PSTR("flight plan update rejected"));