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_Arming: force user to ack crashdump or get prearm failure #30

Merged
merged 2 commits into from
Apr 28, 2024
Merged
Show file tree
Hide file tree
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
3 changes: 3 additions & 0 deletions Tools/AP_Bootloader/board_types.txt
Original file line number Diff line number Diff line change
Expand Up @@ -264,6 +264,9 @@ AP_HW_BotBloxSwitch 1148
AP_HW_MatekH7A3 1149
AP_HW_MicoAir405v2 1150
AP_HW_ORAQF405PRO 1155
AP_HW_FOXEERF405_V2 1157
AP_HW_BlitzF7Mini 1163
AP_HW_BlitzF7 1164

AP_HW_ESP32_PERIPH 1205
AP_HW_ESP32S3_PERIPH 1206
Expand Down
56 changes: 56 additions & 0 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -154,6 +154,15 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
// @User: Advanced
AP_GROUPINFO("MAGTHRESH", 10, AP_Arming, magfield_error_threshold, AP_ARMING_MAGFIELD_ERROR_THRESHOLD),

#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 @@ -180,6 +189,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 @@ -197,6 +213,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 @@ -1637,6 +1666,9 @@ bool AP_Arming::pre_arm_checks(bool report)
#endif
#if AP_OPENDRONEID_ENABLED
& opendroneid_checks(report)
#endif
#if AP_ARMING_CRASHDUMP_ACK_ENABLED
& crashdump_checks(report)
#endif
& serial_protocol_checks(report)
& estop_checks(report);
Expand Down Expand Up @@ -1689,6 +1721,30 @@ 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
13 changes: 13 additions & 0 deletions libraries/AP_Arming/AP_Arming.h
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
#include <AP_HAL/AP_HAL_Boards.h>
#include <AP_HAL/Semaphores.h>
#include <AP_Param/AP_Param.h>
#include <AP_BoardConfig/AP_BoardConfig_config.h>

#include "AP_Arming_config.h"
#include "AP_InertialSensor/AP_InertialSensor_config.h"
Expand Down Expand Up @@ -230,6 +231,10 @@ class AP_Arming {

bool estop_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 @@ -309,6 +314,14 @@ class AP_Arming {
bool report_immediately; // set to true when check goes from true to false, to trigger immediate report

void update_arm_gpio();

#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
4 changes: 4 additions & 0 deletions libraries/AP_Arming/AP_Arming_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,3 +5,7 @@
#ifndef AP_ARMING_AUX_AUTH_ENABLED
#define AP_ARMING_AUX_AUTH_ENABLED AP_SCRIPTING_ENABLED
#endif

#ifndef AP_ARMING_CRASHDUMP_ACK_ENABLED
#define AP_ARMING_CRASHDUMP_ACK_ENABLED AP_CRASHDUMP_ENABLED
#endif
Loading