mirror of https://github.com/ArduPilot/ardupilot
Mission: reduce unnecessary search for do-commands
do_cmd_all_done flag is set after all do-commands are complete
This commit is contained in:
parent
0c92d60406
commit
c7ffd2db90
|
@ -31,6 +31,7 @@ void AP_Mission::start()
|
||||||
_flags.state = MISSION_RUNNING;
|
_flags.state = MISSION_RUNNING;
|
||||||
_flags.nav_cmd_loaded = false;
|
_flags.nav_cmd_loaded = false;
|
||||||
_flags.do_cmd_loaded = false;
|
_flags.do_cmd_loaded = false;
|
||||||
|
_flags.do_cmd_all_done = false;
|
||||||
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
|
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
|
@ -627,6 +628,7 @@ bool AP_Mission::advance_current_nav_cmd()
|
||||||
// stop the current running do command
|
// stop the current running do command
|
||||||
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
_flags.do_cmd_loaded = false;
|
_flags.do_cmd_loaded = false;
|
||||||
|
_flags.do_cmd_all_done = false;
|
||||||
|
|
||||||
// get starting point for search
|
// get starting point for search
|
||||||
cmd_index = _nav_cmd.index;
|
cmd_index = _nav_cmd.index;
|
||||||
|
@ -675,8 +677,8 @@ void AP_Mission::advance_current_do_cmd()
|
||||||
Mission_Command cmd;
|
Mission_Command cmd;
|
||||||
uint16_t cmd_index;
|
uint16_t cmd_index;
|
||||||
|
|
||||||
// exit immediately if we're not running
|
// exit immediately if we're not running or we've completed all possible "do" commands
|
||||||
if (_flags.state != MISSION_RUNNING) {
|
if (_flags.state != MISSION_RUNNING || _flags.do_cmd_all_done) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -691,7 +693,8 @@ void AP_Mission::advance_current_do_cmd()
|
||||||
|
|
||||||
// check if we've reached end of mission
|
// check if we've reached end of mission
|
||||||
if (cmd_index >= _cmd_total) {
|
if (cmd_index >= _cmd_total) {
|
||||||
// To-Do: set a flag to stop us from attempting to look for do-commands over and over?
|
// set flag to stop unnecessarily searching for do commands
|
||||||
|
_flags.do_cmd_all_done = true;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -701,8 +704,8 @@ void AP_Mission::advance_current_do_cmd()
|
||||||
_do_cmd = cmd;
|
_do_cmd = cmd;
|
||||||
_cmd_start_fn(_do_cmd);
|
_cmd_start_fn(_do_cmd);
|
||||||
}else{
|
}else{
|
||||||
// To-Do: set a flag to stop us from attempting to look for do-commands over and over?
|
// set flag to stop unnecessarily searching for do commands
|
||||||
// if added this flag should be reset once we advance the nav command
|
_flags.do_cmd_all_done = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -186,6 +186,7 @@ private:
|
||||||
mission_state state;
|
mission_state state;
|
||||||
uint8_t nav_cmd_loaded : 1; // true if a "navigation" command has been loaded into _nav_cmd
|
uint8_t nav_cmd_loaded : 1; // true if a "navigation" command has been loaded into _nav_cmd
|
||||||
uint8_t do_cmd_loaded : 1; // true if a "do"/"conditional" command has been loaded into _do_cmd
|
uint8_t do_cmd_loaded : 1; // true if a "do"/"conditional" command has been loaded into _do_cmd
|
||||||
|
uint8_t do_cmd_all_done : 1; // true if all "do"/"conditional" commands have been completed (stops unnecessary searching through eeprom for do commands)
|
||||||
} _flags;
|
} _flags;
|
||||||
|
|
||||||
///
|
///
|
||||||
|
|
Loading…
Reference in New Issue