Copter: notify when fence breach has cleared

output fence breach type
when switching mode without a fence action do not go into manual recovery
only recover if there is a fence action
implement auto-takeoff fence options
output user-friendly fence names
auto-enable fences on auto-takeoff
use fence enable_configured()
simplify message printing
This commit is contained in:
Andy Piper 2024-01-02 19:47:43 +00:00 committed by Peter Barker
parent 230269bed8
commit 738586342c
4 changed files with 14 additions and 8 deletions

View File

@ -24,7 +24,7 @@ void Copter::fence_check()
if (new_breaches) {
if (!copter.ap.land_complete) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence Breached");
fence.print_fence_message("breached", new_breaches);
}
// if the user wants some kind of response and motors are armed
@ -81,7 +81,8 @@ void Copter::fence_check()
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
} else if (orig_breaches) {
} else if (orig_breaches && fence.get_breaches() == 0) {
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Fence breach cleared");
// record clearing of breach
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
}

View File

@ -371,10 +371,12 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif
#if AP_FENCE_ENABLED
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
fence.manual_recovery_start();
if (fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY) {
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
fence.manual_recovery_start();
}
#endif
#if AP_CAMERA_ENABLED

View File

@ -791,10 +791,10 @@ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
case MAV_CMD_DO_FENCE_ENABLE:
#if AP_FENCE_ENABLED
if (cmd.p1 == 0) { //disable
copter.fence.enable(false);
copter.fence.enable_configured(false);
gcs().send_text(MAV_SEVERITY_INFO, "Fence Disabled");
} else { //enable fence
copter.fence.enable(true);
copter.fence.enable_configured(true);
gcs().send_text(MAV_SEVERITY_INFO, "Fence Enabled");
}
#endif //AP_FENCE_ENABLED

View File

@ -685,6 +685,9 @@ void ModeGuided::takeoff_run()
auto_takeoff.run();
if (auto_takeoff.complete && !takeoff_complete) {
takeoff_complete = true;
#if AP_FENCE_ENABLED
copter.fence.auto_enable_fence_after_takeoff();
#endif
#if AP_LANDINGGEAR_ENABLED
// optionally retract landing gear
copter.landinggear.retract_after_takeoff();