mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mission: prevent infinite loop with linked jump commands
this prevents a "jump loop" from causing a firmware lockup. Thanks to dellarb for reporting this!
This commit is contained in:
parent
0c3f43b2d7
commit
b010556f37
@ -964,7 +964,8 @@ bool AP_Mission::advance_current_nav_cmd()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// search until we find next nav command or reach end of command list
|
// search until we find next nav command or reach end of command list
|
||||||
while (!_flags.nav_cmd_loaded) {
|
uint8_t max_loops = 64;
|
||||||
|
while (!_flags.nav_cmd_loaded && --max_loops) {
|
||||||
// get next command
|
// get next command
|
||||||
if (!get_next_cmd(cmd_index, cmd, true)) {
|
if (!get_next_cmd(cmd_index, cmd, true)) {
|
||||||
return false;
|
return false;
|
||||||
@ -990,6 +991,11 @@ bool AP_Mission::advance_current_nav_cmd()
|
|||||||
cmd_index = cmd.index+1;
|
cmd_index = cmd.index+1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (max_loops == 0) {
|
||||||
|
// the mission is looping
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// if we got this far we must have successfully advanced the nav command
|
// if we got this far we must have successfully advanced the nav command
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@ -1045,6 +1051,7 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i
|
|||||||
uint16_t jump_index = AP_MISSION_CMD_INDEX_NONE;
|
uint16_t jump_index = AP_MISSION_CMD_INDEX_NONE;
|
||||||
|
|
||||||
// search until the end of the mission command list
|
// search until the end of the mission command list
|
||||||
|
uint8_t max_loops = 64;
|
||||||
while(cmd_index < (unsigned)_cmd_total) {
|
while(cmd_index < (unsigned)_cmd_total) {
|
||||||
// load the next command
|
// load the next command
|
||||||
if (!read_cmd_from_storage(cmd_index, temp_cmd)) {
|
if (!read_cmd_from_storage(cmd_index, temp_cmd)) {
|
||||||
@ -1055,6 +1062,10 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i
|
|||||||
// check for do-jump command
|
// check for do-jump command
|
||||||
if (temp_cmd.id == MAV_CMD_DO_JUMP) {
|
if (temp_cmd.id == MAV_CMD_DO_JUMP) {
|
||||||
|
|
||||||
|
if (max_loops-- == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// check for invalid target
|
// check for invalid target
|
||||||
if (temp_cmd.content.jump.target >= (unsigned)_cmd_total) {
|
if (temp_cmd.content.jump.target >= (unsigned)_cmd_total) {
|
||||||
// To-Do: log an error?
|
// To-Do: log an error?
|
||||||
|
Loading…
Reference in New Issue
Block a user