PreFlightCheck: Check if SD card is present only once and store the result

statfs accesses the file-system and can be blocking for an extended period. Since the SD card check is part of the preflight checks in the main thread of commander, it could block its execution and cause various issues. The SD card is only mounted in rcS during boot so the state will not change after the first check.
This commit is contained in:
Michael Schaeuble
2021-03-29 13:20:06 +02:00
committed by Beat Küng
parent c2350c06c1
commit f9af1bbe2d
4 changed files with 8 additions and 7 deletions

View File

@@ -34,6 +34,7 @@ bool rc_input_blocked # set if RC input should be
bool rc_calibration_valid # set if RC calibration is valid
bool vtol_transition_failure # Set to true if vtol transition failed
bool usb_connected # status of the USB power supply
bool sd_card_detected_once # set to true if the SD card was detected
bool avoidance_system_required # Set to true if avoidance system is enabled via COM_OBS_AVOID parameter
bool avoidance_system_valid # Status of the obstacle avoidance system

View File

@@ -64,7 +64,7 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu
bool failed = false;
failed = failed || !airframeCheck(mavlink_log_pub, status);
failed = failed || !sdcardCheck(mavlink_log_pub, report_failures);
failed = failed || !sdcardCheck(mavlink_log_pub, status_flags.sd_card_detected_once, report_failures);
/* ---- MAG ---- */
{

View File

@@ -119,5 +119,5 @@ private:
static bool manualControlCheck(orb_advert_t *mavlink_log_pub, const bool report_fail);
static bool airframeCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status);
static bool cpuResourceCheck(orb_advert_t *mavlink_log_pub, const bool report_fail);
static bool sdcardCheck(orb_advert_t *mavlink_log_pub, const bool report_fail);
static bool sdcardCheck(orb_advert_t *mavlink_log_pub, bool &sd_card_detected_once, const bool report_fail);
};

View File

@@ -42,7 +42,8 @@
#include <sys/statfs.h>
#endif
bool PreFlightCheck::sdcardCheck(orb_advert_t *mavlink_log_pub, const bool report_fail)
bool PreFlightCheck::sdcardCheck(orb_advert_t *mavlink_log_pub, bool &sd_card_detected_once,
const bool report_fail)
{
bool success = true;
@@ -50,15 +51,14 @@ bool PreFlightCheck::sdcardCheck(orb_advert_t *mavlink_log_pub, const bool repor
param_get(param_find("COM_ARM_SDCARD"), &param_com_arm_sdcard);
if (param_com_arm_sdcard > 0) {
bool sdcard_present{false};
struct statfs statfs_buf;
if (statfs(PX4_STORAGEDIR, &statfs_buf) == 0) {
if (!sd_card_detected_once && 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_present = (statfs_buf.f_blocks > 0) && (statfs_buf.f_bsize > 0);
sd_card_detected_once = (statfs_buf.f_blocks > 0) && (statfs_buf.f_bsize > 0);
}
if (!sdcard_present) {
if (!sd_card_detected_once) {
if (report_fail) {
mavlink_log_critical(mavlink_log_pub, "Warning! Missing FMU SD Card.");
}