Skip to content

Commit

Permalink
AP_Arming: force user to ack crashdump or get prearm failure
Browse files Browse the repository at this point in the history
SW-148
  • Loading branch information
loki077 committed Apr 29, 2024
1 parent 47894c7 commit 698d73c
Show file tree
Hide file tree
Showing 2 changed files with 74 additions and 0 deletions.
58 changes: 58 additions & 0 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,16 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @User: Advanced
AP_GROUPINFO("OPTIONS", 9, AP_Arming, _arming_options, 0),


#if AP_ARMING_CRASHDUMP_ACK_ENABLED
// @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),
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED

AP_GROUPEND
};

Expand All @@ -165,6 +175,13 @@ AP_Arming::AP_Arming()
// performs pre-arm checks. expects to be called at 1hz.
void AP_Arming::update(void)
{
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
// 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();
#endif

const uint32_t now_ms = AP_HAL::millis();
// perform pre-arm checks & display failures every 30 seconds
bool display_fail = false;
Expand All @@ -180,6 +197,19 @@ void AP_Arming::update(void)
pre_arm_checks(display_fail);
}

#if AP_ARMING_CRASHDUMP_ACK_ENABLED
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);
}
}
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED

uint16_t AP_Arming::compass_magfield_expected() const
{
return AP_ARMING_COMPASS_MAGFIELD_EXPECTED;
Expand Down Expand Up @@ -1459,6 +1489,9 @@ bool AP_Arming::pre_arm_checks(bool report)
& disarm_switch_checks(report)
& fence_checks(report)
& opendroneid_checks(report)
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
& crashdump_checks(report)
#endif
& serial_protocol_checks(report);
}

Expand Down Expand Up @@ -1500,6 +1533,31 @@ bool AP_Arming::arm_checks(AP_Arming::Method method)
return true;
}


#if AP_ARMING_CRASHDUMP_ACK_ENABLED
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;
}
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED

bool AP_Arming::mandatory_checks(bool report)
{
bool ret = true;
Expand Down
16 changes: 16 additions & 0 deletions libraries/AP_Arming/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,10 @@
#include <AP_Param/AP_Param.h>
#include <GCS_MAVLink/GCS_MAVLink.h>

#ifndef AP_ARMING_CRASHDUMP_ACK_ENABLED
#define AP_ARMING_CRASHDUMP_ACK_ENABLED AP_CRASHDUMP_ENABLED
#endif

class AP_Arming {
public:

Expand Down Expand Up @@ -204,6 +208,10 @@ class AP_Arming {

bool serial_protocol_checks(bool display_failure);

#if AP_ARMING_CRASHDUMP_ACK_ENABLED
bool crashdump_checks(bool report);
#endif

virtual bool system_checks(bool report);

bool can_checks(bool report);
Expand Down Expand Up @@ -270,6 +278,14 @@ 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

#if AP_ARMING_CRASHDUMP_ACK_ENABLED
struct CrashDump {
void check_reset();
AP_Int8 acked;
} crashdump_ack;
#endif // AP_ARMING_CRASHDUMP_ACK_ENABLED

};

namespace AP {
Expand Down

0 comments on commit 698d73c

Please sign in to comment.