AP_Mission: emit jump count even if no limit

previously if there was a jump limit we informed the user we were jumping and provided the current count and the limit.

This changes things so that if there's no limit we emit the same message, with the count and "unlimited" in place of the limit number
This commit is contained in:
Peter Barker 2024-05-07 13:58:07 +10:00 committed by Randy Mackay
parent 579eb4fb24
commit b9a84baafa

View File

@ -2138,14 +2138,9 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i
jump_index = cmd_index; jump_index = cmd_index;
} }
// check if jump command is 'repeat forever'
if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) {
// continue searching from jump target
cmd_index = temp_cmd.content.jump.target;
} else {
// get number of times jump command has already been run // get number of times jump command has already been run
int16_t jump_times_run = get_jump_times_run(temp_cmd); if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER ||
if (jump_times_run < temp_cmd.content.jump.num_times) { get_jump_times_run(temp_cmd) < temp_cmd.content.jump.num_times) {
// update the record of the number of times run // update the record of the number of times run
if (increment_jump_num_times_if_found && !_flags.resuming_mission) { if (increment_jump_num_times_if_found && !_flags.resuming_mission) {
increment_jump_times_run(temp_cmd, send_gcs_msg); increment_jump_times_run(temp_cmd, send_gcs_msg);
@ -2156,7 +2151,6 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i
// jump has been run specified number of times so move search to next command in mission // jump has been run specified number of times so move search to next command in mission
cmd_index++; cmd_index++;
} }
}
} else { } else {
// this is a non-jump command so return it // this is a non-jump command so return it
cmd = temp_cmd; cmd = temp_cmd;
@ -2291,8 +2285,12 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd, bool send_gcs_ms
if (_jump_tracking[i].index == cmd.index) { if (_jump_tracking[i].index == cmd.index) {
_jump_tracking[i].num_times_run++; _jump_tracking[i].num_times_run++;
if (send_gcs_msg) { if (send_gcs_msg) {
if (cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/unlimited", _jump_tracking[i].index, _jump_tracking[i].num_times_run);
} else {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Mission: %u Jump %i/%i", _jump_tracking[i].index, _jump_tracking[i].num_times_run, cmd.content.jump.num_times);
} }
}
return; return;
} else if (_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) { } else if (_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
// we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array // we've searched through all known jump commands and haven't found it so allocate new space in _jump_tracking array