AP_Mission: added reset() function

This commit is contained in:
Andrew Chapman 2014-04-15 09:56:09 -07:00 committed by Andrew Tridgell
parent a80e72ff82
commit 782fbe1ec5
2 changed files with 20 additions and 8 deletions

View File

@ -48,13 +48,9 @@ void AP_Mission::init()
void AP_Mission::start()
{
_flags.state = MISSION_RUNNING;
_flags.nav_cmd_loaded = false;
_flags.do_cmd_loaded = false;
_flags.do_cmd_all_done = false;
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
init_jump_tracking();
reset(); // reset mission to the first command, resets jump tracking
// advance to the first command
if (!advance_current_nav_cmd()) {
// on failure set mission complete
@ -106,6 +102,7 @@ void AP_Mission::resume()
}
}
/// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
void AP_Mission::start_or_resume()
{
if (_auto_reset) {
@ -115,6 +112,18 @@ void AP_Mission::start_or_resume()
}
}
/// reset - reset mission to the first command
void AP_Mission::reset()
{
_flags.nav_cmd_loaded = false;
_flags.do_cmd_loaded = false;
_flags.do_cmd_all_done = false;
_nav_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_do_cmd.index = AP_MISSION_CMD_INDEX_NONE;
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
init_jump_tracking();
}
/// clear - clears out mission
/// returns true if mission was running so it could not be cleared
bool AP_Mission::clear()

View File

@ -216,6 +216,9 @@ public:
/// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
void start_or_resume();
/// reset - reset mission to the first command
void reset();
/// clear - clears out mission
/// returns true if mission was running so it could not be cleared
bool clear();
@ -359,7 +362,7 @@ private:
// parameters
AP_Int16 _cmd_total; // total number of commands in the mission
AP_Int8 _auto_reset; // when true the mission will reset to the start when initiated
AP_Int8 _auto_reset; // when true the mission will reset to the first command when initiated
// pointer to main program functions
mission_cmd_fn_t _cmd_start_fn; // pointer to function which will be called when a new command is started