AP_AdvancedFailsafe: option to continue the mission even after data link is recovered

This feature is useful when the landing sequence is part of the flight plan. New parameter AFS_OPTIONS was added.

Update libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp

Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
Update libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h

Co-authored-by: Peter Barker <pb-gh@barker.dropbear.id.au>
enum convention changed
This commit is contained in:
Ep Pravitra 2023-09-04 15:29:57 +07:00 committed by Peter Barker
parent 6bb5723b18
commit 1372e48515
2 changed files with 19 additions and 0 deletions

View File

@ -162,6 +162,12 @@ const AP_Param::GroupInfo AP_AdvancedFailsafe::var_info[] = {
// @User: Advanced // @User: Advanced
// @Units: km // @Units: km
AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0), AP_GROUPINFO("MAX_RANGE", 20, AP_AdvancedFailsafe, _max_range_km, 0),
// @Param: OPTIONS
// @DisplayName: AFS options
// @Description: See description for each bitmask bit description
// @Bitmask: 0: Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)
AP_GROUPINFO("OPTIONS", 21, AP_AdvancedFailsafe, options, 0),
AP_GROUPEND AP_GROUPEND
}; };
@ -277,6 +283,11 @@ AP_AdvancedFailsafe::check(uint32_t last_valid_rc_ms)
} else if (gcs_link_ok) { } else if (gcs_link_ok) {
_state = STATE_AUTO; _state = STATE_AUTO;
gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK"); gcs().send_text(MAV_SEVERITY_DEBUG, "AFS State: AFS_AUTO, GCS now OK");
if (option_is_set(Option::CONTINUE_AFTER_RECOVERED)) {
break;
}
// we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS // we only return to the mission if we have not exceeded AFS_MAX_COM_LOSS
if (_saved_wp != 0 && if (_saved_wp != 0 &&
(_max_comms_loss <= 0 || (_max_comms_loss <= 0 ||

View File

@ -162,6 +162,14 @@ private:
// update maximum range check // update maximum range check
void max_range_update(); void max_range_update();
AP_Int16 options;
enum class Option {
CONTINUE_AFTER_RECOVERED = (1U<<0),
};
bool option_is_set(Option option) const {
return (options.get() & int16_t(option)) != 0;
}
}; };
namespace AP { namespace AP {