APM: allow update of last waypoint

fixed off by one error
This commit is contained in:
Andrew Tridgell 2012-09-16 15:05:48 +10:00
parent 644b3c6e17
commit 1e51988ecc

View File

@ -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"));