AP_Mission: If a command fails to start immediately cycle to the next
This commit is contained in:
parent
18512eebbb
commit
7db5daadad
@ -1411,8 +1411,9 @@ bool AP_Mission::advance_current_nav_cmd(uint16_t starting_index)
|
|||||||
}
|
}
|
||||||
// set current navigation command and start it
|
// set current navigation command and start it
|
||||||
_nav_cmd = cmd;
|
_nav_cmd = cmd;
|
||||||
_flags.nav_cmd_loaded = true;
|
if (_cmd_start_fn(_nav_cmd)) {
|
||||||
_cmd_start_fn(_nav_cmd);
|
_flags.nav_cmd_loaded = true;
|
||||||
|
}
|
||||||
}else{
|
}else{
|
||||||
// set current do command and start it (if not already set)
|
// set current do command and start it (if not already set)
|
||||||
if (!_flags.do_cmd_loaded) {
|
if (!_flags.do_cmd_loaded) {
|
||||||
|
Loading…
Reference in New Issue
Block a user