fix(commander): Remove COM_ARM_SDCARD (#27259)

hardcoding the default warning and respecting boards without SD card with a define.
This commit is contained in:
Matthias Grob
2026-04-30 23:49:47 +02:00
committed by GitHub
parent 1830c27d39
commit a061b8665b
14 changed files with 31 additions and 57 deletions
+6
View File
@@ -202,6 +202,12 @@ menu "File paths"
config BOARD_PARAM_FILE
string "Parameter file"
default "/fs/mtd_params"
config BOARD_NO_SDCARD
bool "Board has no SD card"
default n
help
Disable the SD card arming check for boards without an SD card slot.
endmenu
menu "drivers"
+1
View File
@@ -1,5 +1,6 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_NO_SDCARD=y
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
@@ -7,8 +7,6 @@ param set-default SYS_AUTOSTART 4061
param set-default BAT1_V_DIV 9.0
param set-default COM_ARM_SDCARD 0
param set-default SENS_EXT_I2C_PRB 0
param set-default EV_TSK_STAT_DIS 1
@@ -1,6 +1,7 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROOT_PATH="/fs/flash"
CONFIG_BOARD_NO_SDCARD=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS6"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4"
@@ -19,6 +19,3 @@ param set-default SDLOG_MAX_SIZE 40
# Store missions in RAM
param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
@@ -1,6 +1,7 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROOT_PATH="/fs/flash"
CONFIG_BOARD_NO_SDCARD=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
@@ -29,9 +29,6 @@ param set-default CBRK_BUZZER 782090
param set-default IMU_GYRO_RATEMAX 2000
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# W25N NAND flash with littlefs (128 MB): small log file size so we can keep
# a few recent logs, and fill up to 95%.
param set-default SDLOG_ROTATE 95
@@ -1,6 +1,7 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_ROOT_PATH="/fs/flash"
CONFIG_BOARD_NO_SDCARD=y
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS0"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
@@ -32,9 +32,6 @@ param set-default IMU_GYRO_RATEMAX 2000
# Store missions in RAM
param set-default SYS_DM_BACKEND 1
# Ignore that there is no SD card
param set-default COM_ARM_SDCARD 0
# W25N NAND flash with littlefs (128 MB): small log file size so we can keep
# a few recent logs, and fill up to 95%.
param set-default SDLOG_ROTATE 95
@@ -284,7 +284,6 @@
1 1 COM_ARM_MAG_STR 2 6
1 1 COM_ARM_MIS_REQ 0 6
1 1 COM_ARM_ODID 0 6
1 1 COM_ARM_SDCARD 1 6
1 1 COM_ARM_SWISBTN 0 6
1 1 COM_ARM_WO_GPS 1 6
1 1 COM_CPU_MAX 95.000000000000000000 9
-1
View File
@@ -464,7 +464,6 @@ These parameters can be used to set conditions that prevent arming.
| <a id="COM_ARM_BAT_MIN"></a>[COM_ARM_BAT_MIN](../advanced_config/parameter_reference.md#COM_ARM_BAT_MIN) | Minimum battery level for arming. `0`: Disabled (default). Values: `0`-`0.9`, |
| <a id="COM_ARM_WO_GPS"></a>[COM_ARM_WO_GPS](../advanced_config/parameter_reference.md#COM_ARM_WO_GPS) | Enable arming without GPS. `0`: Disabled, `1`: Enabled (default). |
| <a id="COM_ARM_MIS_REQ"></a>[COM_ARM_MIS_REQ](../advanced_config/parameter_reference.md#COM_ARM_MIS_REQ) | Require valid mission to arm. `0`: Disabled (default), `1`: Enabled . |
| <a id="COM_ARM_SDCARD"></a>[COM_ARM_SDCARD](../advanced_config/parameter_reference.md#COM_ARM_SDCARD) | Require SD card to arm. `0`: Disabled (default), `1`: Warning, `2`: Enabled. |
| <a id="COM_ARM_AUTH_REQ"></a>[COM_ARM_AUTH_REQ](../advanced_config/parameter_reference.md#COM_ARM_AUTH_REQ) | Requires arm authorisation from an external (MAVLink) system. Flag to allow arming (at all). `1`: Enabled, `0`: Disabled (default). Associated configuration parameters are prefixed with `COM_ARM_AUTH_`. |
| <a id="COM_ARM_ODID"></a>[COM_ARM_ODID](../advanced_config/parameter_reference.md#COM_ARM_ODID) | Remote ID arming check and in-flight failsafe. `0`: Disabled (default), `1`: Warning only, `2`: Error only, `3`: Return, `4`: Land, `5`: Terminate. See [Remote ID Failsafe](#remote-id-failsafe). |
@@ -46,41 +46,30 @@ void SdCardChecks::checkAndReport(const Context &context, Report &reporter)
{
#ifdef PX4_STORAGEDIR
if (_param_com_arm_sdcard.get() > 0) {
#ifndef CONFIG_BOARD_NO_SDCARD
struct statfs statfs_buf;
struct statfs statfs_buf;
if (!_sdcard_detected && statfs(PX4_STORAGEDIR, &statfs_buf) == 0) {
// on NuttX we get a data block count f_blocks and byte count per block f_bsize if an SD card is inserted
_sdcard_detected = (statfs_buf.f_blocks > 0) && (statfs_buf.f_bsize > 0);
}
if (!_sdcard_detected && statfs(PX4_STORAGEDIR, &statfs_buf) == 0) {
// on NuttX we get a data block count f_blocks and byte count per block f_bsize if an SD card is inserted
_sdcard_detected = (statfs_buf.f_blocks > 0) && (statfs_buf.f_bsize > 0);
}
if (!_sdcard_detected) {
/* EVENT
* @description
* Insert an SD Card to the autopilot and reboot the system.
*/
reporter.armingCheckFailure(NavModes::None, health_component_t::system,
events::ID("check_missing_fmu_sdcard"),
events::Log::Error, "Missing FMU SD Card");
if (!_sdcard_detected) {
NavModes affected_modes{NavModes::None};
if (_param_com_arm_sdcard.get() == 2) {
// disallow arming without sd card
affected_modes = NavModes::All;
}
/* EVENT
* @description
* Insert an SD Card to the autopilot and reboot the system.
*
* <profile name="dev">
* This check can be configured via <param>COM_ARM_SDCARD</param> parameter.
* </profile>
*/
reporter.armingCheckFailure(affected_modes, health_component_t::system,
events::ID("check_missing_fmu_sdcard"),
events::Log::Error, "Missing FMU SD Card");
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Missing FMU SD Card");
}
if (reporter.mavlink_log_pub()) {
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Missing FMU SD Card");
}
}
#endif // CONFIG_BOARD_NO_SDCARD
#ifdef __PX4_NUTTX
// Check for hardfault files
@@ -45,7 +45,9 @@ public:
private:
#ifdef PX4_STORAGEDIR
#ifndef CONFIG_BOARD_NO_SDCARD
bool _sdcard_detected {false};
#endif // CONFIG_BOARD_NO_SDCARD
#ifdef __PX4_NUTTX
bool _hardfault_checked_once {false};
@@ -53,10 +55,9 @@ private:
bool _watchdog_checked_once {false};
bool _watchdog_file_present {false};
#endif
#endif
#endif // PX4_STORAGEDIR
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
(ParamInt<px4::params::COM_ARM_SDCARD>) _param_com_arm_sdcard,
(ParamBool<px4::params::COM_ARM_HFLT_CHK>) _param_com_arm_hardfault_check
)
};
@@ -564,19 +564,6 @@ parameters:
min: -1.0
max: 5.0
decimal: 3
COM_ARM_SDCARD:
description:
short: Enable FMU SD card detection check
long: |-
This check detects if the FMU SD card is missing.
Depending on the value of the parameter, the check can be
disabled, warn only or deny arming.
type: enum
values:
0: Disabled
1: Warning only
2: Enforce SD card presence
default: 1
COM_ARM_HFLT_CHK:
description:
short: Enable FMU SD card hardfault / watchdog detection check