From ed65aaf0f4ed8d23d79d01700cce531bdca09bff Mon Sep 17 00:00:00 2001 From: Lokesh-Ramina Date: Mon, 22 Apr 2024 23:00:04 -0700 Subject: [PATCH] AP_Arming: force user to ack crashdump or get prearm failure SW-148 --- libraries/AP_Arming/AP_Arming.cpp | 47 +++++++++++++++++++++++++++++++ libraries/AP_Arming/AP_Arming.h | 8 ++++++ 2 files changed, 55 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 1788d01c32..97b578e8e9 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -144,6 +144,13 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = { // @User: Advanced AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0), + // @Param: CRSDP_IGN + // @DisplayName: Disable CrashDump Arming check + // @Description: Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details. + // @Values: 0:Crash Dump arming check active, 1:Crash Dump arming check deactivated + // @User: Advanced + AP_GROUPINFO("CRSDP_IGN", 11, AP_Arming, crashdump_ack.acked, 0), + AP_GROUPEND }; @@ -165,6 +172,11 @@ AP_Arming::AP_Arming() // performs pre-arm checks. expects to be called at 1hz. void AP_Arming::update(void) { + // if we boot with no crashdump data present, reset the "ignore" + // parameter so the user will need to acknowledge future crashes + // too: + crashdump_ack.check_reset(); + const uint32_t now_ms = AP_HAL::millis(); // perform pre-arm checks & display failures every 30 seconds bool display_fail = false; @@ -180,6 +192,17 @@ void AP_Arming::update(void) pre_arm_checks(display_fail); } +void AP_Arming::CrashDump::check_reset() +{ + // if there is no crash dump data then clear the crash dump ack. + // This means on subsequent crash-dumps appearing the user must + // re-acknowledge. + if (hal.util->last_crash_dump_size() == 0) { + // no crash dump data + acked.set_and_save_ifchanged(0); + } +} + uint16_t AP_Arming::compass_magfield_expected() const { return AP_ARMING_COMPASS_MAGFIELD_EXPECTED; @@ -1459,6 +1482,7 @@ bool AP_Arming::pre_arm_checks(bool report) & disarm_switch_checks(report) & fence_checks(report) & opendroneid_checks(report) + & crashdump_checks(report) & serial_protocol_checks(report); } @@ -1500,6 +1524,29 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) return true; } + +bool AP_Arming::crashdump_checks(bool report) +{ + if (hal.util->last_crash_dump_size() == 0) { + // no crash dump data + return true; + } + + // see if the user has acknowledged the failure and wants to fly anyway: + if (crashdump_ack.acked) { + // they may have acked the problem, that doesn't mean we don't + // continue to warn them they're on thin ice: + if (report) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "CrashDump data detected"); + } + return true; + } + + check_failed(ARMING_CHECK_PARAMETERS, true, "CrashDump data detected"); + + return false; +} + bool AP_Arming::mandatory_checks(bool report) { bool ret = true; diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 19af52eef3..619714af23 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -204,6 +204,8 @@ class AP_Arming { bool serial_protocol_checks(bool display_failure); + bool crashdump_checks(bool report); + virtual bool system_checks(bool report); bool can_checks(bool report); @@ -270,6 +272,12 @@ class AP_Arming { uint32_t last_prearm_display_ms; // last time we send statustexts for prearm failures bool running_arming_checks; // true if the arming checks currently being performed are being done because the vehicle is trying to arm the vehicle + + struct CrashDump { + void check_reset(); + AP_Int8 acked; + } crashdump_ack; + }; namespace AP {