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:
Nigel Williams 2019-01-17 19:11:08 +11:00 committed by Peter Barker
parent 8710526894
commit b2c5d7f04a
1 changed files with 15 additions and 4 deletions

View File

@ -200,6 +200,10 @@ bool AP_Arming::logging_checks(bool report)
{
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(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()) {
check_failed(ARMING_CHECK_LOGGING, report, "Logging failed");
return false;
@ -722,11 +726,18 @@ bool AP_Arming::arm_checks(ArmingMethod method)
// note that this will prepare AP_Logger to start logging
// so should be the last check to be done before arming
if ((checks_to_perform & ARMING_CHECK_ALL) ||
(checks_to_perform & ARMING_CHECK_LOGGING)) {
AP_Logger *df = AP_Logger::instance();
// Note also that we need to PrepForArming() regardless of whether
// 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();
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");
return false;
}