mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
APM: allow update of last waypoint
fixed off by one error
This commit is contained in:
parent
bd31f340a7
commit
208b878988
@ -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"));
|
||||
|
Loading…
Reference in New Issue
Block a user