AP_Mission: Added force resume for when MIS_RESTART=1

This commit is contained in:
Andrew Tridgell 2020-07-07 11:28:51 +10:00
parent eabe320cee
commit db364257d8
2 changed files with 7 additions and 1 deletions

View File

@ -163,10 +163,11 @@ bool AP_Mission::starts_with_takeoff_cmd()
/// start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()
void AP_Mission::start_or_resume()
{
if (_restart) {
if (_restart == 1 && !_force_resume) {
start();
} else {
resume();
_force_resume = false;
}
}

View File

@ -303,6 +303,7 @@ public:
_flags.state = MISSION_STOPPED;
_flags.nav_cmd_loaded = false;
_flags.do_cmd_loaded = false;
_force_resume = false;
}
// get singleton instance
@ -471,6 +472,9 @@ public:
// jumps the mission to the closest landing abort that is planned, returns false if unable to find a valid abort
bool jump_to_abort_landing_sequence(void);
// force mission to resume when start_or_resume() is called
void set_force_resume(bool force_resume) { _force_resume = force_resume; }
// get a reference to the AP_Mission semaphore, allowing an external caller to lock the
// storage while working with multiple waypoints
HAL_Semaphore_Recursive &get_semaphore(void) {
@ -570,6 +574,7 @@ private:
uint16_t _prev_nav_cmd_id; // id of the previous "navigation" command. (WAYPOINT, LOITER_TO_ALT, ect etc)
uint16_t _prev_nav_cmd_index; // index of the previous "navigation" command. Rarely used which is why we don't store the whole command
uint16_t _prev_nav_cmd_wp_index; // index of the previous "navigation" command that contains a waypoint. Rarely used which is why we don't store the whole command
bool _force_resume; // when set true it forces mission to resume irrespective of MIS_RESTART param.
// jump related variables
struct jump_tracking_struct {