mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
Mission: bug fix set_current_cmd
If mission had completed desired command index was ignored
This commit is contained in:
parent
3e05baf95c
commit
266a1ce9af
@ -254,8 +254,10 @@ bool AP_Mission::set_current_cmd(uint16_t index)
|
|||||||
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
|
_prev_nav_cmd_index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
// reset the jump tracking to zero
|
// reset the jump tracking to zero
|
||||||
init_jump_tracking();
|
init_jump_tracking();
|
||||||
|
if (index == 0) {
|
||||||
index = 1;
|
index = 1;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// if the mission is stopped or completed move the nav_cmd index to the specified point and set the state to stopped
|
// if the mission is stopped or completed move the nav_cmd index to the specified point and set the state to stopped
|
||||||
// so that if the user resumes the mission it will begin at the specified index
|
// so that if the user resumes the mission it will begin at the specified index
|
||||||
|
Loading…
Reference in New Issue
Block a user