mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: Make logging check consider "turned off" as valid
When ARMING_CHECKS has ARMING_CHECK_LOGGING, consider having no logging backend to be valid.
This commit is contained in:
parent
8710526894
commit
b2c5d7f04a
|
@ -200,6 +200,10 @@ bool AP_Arming::logging_checks(bool report)
|
||||||
{
|
{
|
||||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
(checks_to_perform & ARMING_CHECK_LOGGING)) {
|
(checks_to_perform & ARMING_CHECK_LOGGING)) {
|
||||||
|
if (!AP::logger().logging_present()) {
|
||||||
|
// Logging is disabled, so nothing to check.
|
||||||
|
return true;
|
||||||
|
}
|
||||||
if (AP::logger().logging_failed()) {
|
if (AP::logger().logging_failed()) {
|
||||||
check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
|
check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
|
||||||
return false;
|
return false;
|
||||||
|
@ -722,11 +726,18 @@ bool AP_Arming::arm_checks(ArmingMethod method)
|
||||||
|
|
||||||
// note that this will prepare AP_Logger to start logging
|
// note that this will prepare AP_Logger 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) ||
|
|
||||||
(checks_to_perform & ARMING_CHECK_LOGGING)) {
|
// Note also that we need to PrepForArming() regardless of whether
|
||||||
AP_Logger *df = AP_Logger::instance();
|
// the arming check flag is set - disabling the arming check
|
||||||
|
// should not stop logging from working.
|
||||||
|
|
||||||
|
AP_Logger *df = AP_Logger::instance();
|
||||||
|
if (df->logging_present()) {
|
||||||
|
// If we're configured to log, prep it
|
||||||
df->PrepForArming();
|
df->PrepForArming();
|
||||||
if (!df->logging_started()) {
|
if (!df->logging_started() &&
|
||||||
|
((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||||
|
(checks_to_perform & ARMING_CHECK_LOGGING))) {
|
||||||
check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
|
check_failed(ARMING_CHECK_LOGGING, true, "Logging not started");
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue