Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Mission: emit jump count even if no limit #27003

Merged
merged 1 commit into from
May 8, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
30 changes: 14 additions & 16 deletions libraries/AP_Mission/AP_Mission.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2153,24 +2153,18 @@ bool AP_Mission::get_next_cmd(uint16_t start_index, Mission_Command& cmd, bool i
jump_index = cmd_index;
}

// check if jump command is 'repeat forever'
if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER) {
// get number of times jump command has already been run
if (temp_cmd.content.jump.num_times == AP_MISSION_JUMP_REPEAT_FOREVER ||
get_jump_times_run(temp_cmd) < temp_cmd.content.jump.num_times) {
// update the record of the number of times run
if (increment_jump_num_times_if_found && !_flags.resuming_mission) {
increment_jump_times_run(temp_cmd, send_gcs_msg);
}
// continue searching from jump target
cmd_index = temp_cmd.content.jump.target;
} else {
// get number of times jump command has already been run
int16_t jump_times_run = get_jump_times_run(temp_cmd);
if (jump_times_run < temp_cmd.content.jump.num_times) {
// update the record of the number of times run
if (increment_jump_num_times_if_found && !_flags.resuming_mission) {
increment_jump_times_run(temp_cmd, send_gcs_msg);
}
// continue searching from jump target
cmd_index = temp_cmd.content.jump.target;
} else {
// jump has been run specified number of times so move search to next command in mission
cmd_index++;
}
// jump has been run specified number of times so move search to next command in mission
cmd_index++;
}
} else {
// this is a non-jump command so return it
Expand Down Expand Up @@ -2306,7 +2300,11 @@ void AP_Mission::increment_jump_times_run(Mission_Command& cmd, bool send_gcs_ms
if (_jump_tracking[i].index == cmd.index) {
_jump_tracking[i].num_times_run++;
if (send_gcs_msg) {
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);
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);
}
}
return;
} else if (_jump_tracking[i].index == AP_MISSION_CMD_INDEX_NONE) {
Expand Down
Loading