AP_Arming: always check configured on copter and blimp

This commit is contained in:
Iampete1 2021-08-16 00:09:15 +01:00 committed by Andrew Tridgell
parent 506c21ce48
commit 60e0f47918
2 changed files with 7 additions and 2 deletions

View File

@ -437,7 +437,12 @@ bool AP_Arming::compass_checks(bool report)
return false;
}
// check compass learning is on or offsets have been set
if (!_compass.learn_offsets_enabled()) {
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter) && !APM_BUILD_TYPE(APM_BUILD_Blimp)
// check compass offsets have been set if learning is off
// copter and blimp always require configured compasses
if (!_compass.learn_offsets_enabled())
#endif
{
char failure_msg[50] = {};
if (!_compass.configured(failure_msg, ARRAY_SIZE(failure_msg))) {
check_failed(ARMING_CHECK_COMPASS, report, "%s", failure_msg);

View File

@ -146,7 +146,7 @@ protected:
virtual bool ins_checks(bool report);
virtual bool compass_checks(bool report);
bool compass_checks(bool report);
virtual bool gps_checks(bool report);