mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: fix infinite loop with nav commands that won't start
Discovered this when trying to run the standard CMAC mission on Sub
This commit is contained in:
parent
a24a8c110b
commit
f07d40a570
|
@ -1703,7 +1703,7 @@ bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index)
|
|||
uint8_t max_loops = 255;
|
||||
|
||||
// search until we find next nav command or reach end of command list
|
||||
while (!_flags.nav_cmd_loaded) {
|
||||
while (!_flags.nav_cmd_loaded && max_loops-- > 0) {
|
||||
// get next command
|
||||
Mission_Command cmd;
|
||||
if (!get_next_cmd(cmd_index, cmd, true)) {
|
||||
|
@ -1746,17 +1746,18 @@ bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index)
|
|||
_do_cmd = cmd;
|
||||
_flags.do_cmd_loaded = true;
|
||||
start_command(_do_cmd);
|
||||
} else {
|
||||
// protect against endless loops of do-commands
|
||||
if (max_loops-- == 0) {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
}
|
||||
// move onto next command
|
||||
cmd_index = cmd.index+1;
|
||||
}
|
||||
|
||||
if (max_loops == 0) {
|
||||
// infinite loop. This can happen if there's a loop involving
|
||||
// only nav commands (no DO commands) which won't start()
|
||||
return false;
|
||||
}
|
||||
|
||||
// if we have not found a do command then set flag to show there are no do-commands to be run before nav command completes
|
||||
if (!_flags.do_cmd_loaded) {
|
||||
_flags.do_cmd_all_done = true;
|
||||
|
|
Loading…
Reference in New Issue