mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
AP_Arming: added arming check for storage health
This commit is contained in:
parent
63a9b903ba
commit
bf1bca6820
@ -538,6 +538,19 @@ bool AP_Arming::board_voltage_checks(bool report)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
check base system operations
|
||||||
|
*/
|
||||||
|
bool AP_Arming::system_checks(bool report)
|
||||||
|
{
|
||||||
|
if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_SYSTEM)) {
|
||||||
|
if (!hal.storage->healthy()) {
|
||||||
|
check_failed(ARMING_CHECK_SYSTEM, report, "Param storage failed");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
bool AP_Arming::pre_arm_checks(bool report)
|
bool AP_Arming::pre_arm_checks(bool report)
|
||||||
{
|
{
|
||||||
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
|
||||||
@ -557,7 +570,8 @@ bool AP_Arming::pre_arm_checks(bool report)
|
|||||||
& logging_checks(report)
|
& logging_checks(report)
|
||||||
& manual_transmitter_checks(report)
|
& manual_transmitter_checks(report)
|
||||||
& servo_checks(report)
|
& servo_checks(report)
|
||||||
& board_voltage_checks(report);
|
& board_voltage_checks(report)
|
||||||
|
& system_checks(report);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_Arming::arm_checks(ArmingMethod method)
|
bool AP_Arming::arm_checks(ArmingMethod method)
|
||||||
@ -570,6 +584,14 @@ bool AP_Arming::arm_checks(ArmingMethod method)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check system health on arm as well as prearm
|
||||||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
|
(checks_to_perform & ARMING_CHECK_SYSTEM)) {
|
||||||
|
if (!system_checks(true)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// note that this will prepare DataFlash to start logging
|
// note that this will prepare DataFlash to start logging
|
||||||
// so should be the last check to be done before arming
|
// so should be the last check to be done before arming
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
|
@ -31,6 +31,7 @@ public:
|
|||||||
ARMING_CHECK_LOGGING = 0x0400,
|
ARMING_CHECK_LOGGING = 0x0400,
|
||||||
ARMING_CHECK_SWITCH = 0x0800,
|
ARMING_CHECK_SWITCH = 0x0800,
|
||||||
ARMING_CHECK_GPS_CONFIG = 0x1000,
|
ARMING_CHECK_GPS_CONFIG = 0x1000,
|
||||||
|
ARMING_CHECK_SYSTEM = 0x2000,
|
||||||
};
|
};
|
||||||
|
|
||||||
enum ArmingMethod {
|
enum ArmingMethod {
|
||||||
@ -105,6 +106,8 @@ protected:
|
|||||||
|
|
||||||
bool manual_transmitter_checks(bool report);
|
bool manual_transmitter_checks(bool report);
|
||||||
|
|
||||||
|
virtual bool system_checks(bool report);
|
||||||
|
|
||||||
bool servo_checks(bool report) const;
|
bool servo_checks(bool report) const;
|
||||||
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max = true) const;
|
bool rc_checks_copter_sub(bool display_failure, const RC_Channel *channels[4], const bool check_min_max = true) const;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user