From 62932f884fa4352a31d6ec244db2d4523aede240 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 21 Jan 2021 12:42:19 +0900 Subject: [PATCH] AP_AHRS: pre_arm_check may skip position checks --- libraries/AP_AHRS/AP_AHRS.h | 3 ++- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 3 ++- libraries/AP_AHRS/AP_AHRS_DCM.h | 3 ++- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 5 +++-- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 3 ++- 5 files changed, 11 insertions(+), 6 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 0ffc3b5ee8..bbdcbf7f7e 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -164,7 +164,8 @@ public: virtual void update(bool skip_ins_update=false) = 0; // returns false if we fail arming checks, in which case the buffer will be populated with a failure message - virtual bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const = 0; + // requires_position should be true if horizontal position configuration should be checked + virtual bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const = 0; // check all cores providing consistent attitudes for prearm checks virtual bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const { return true; } diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index ba608027af..9a4db95188 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1152,7 +1152,8 @@ bool AP_AHRS_DCM::get_velocity_NED(Vector3f &vec) const } // returns false if we fail arming checks, in which case the buffer will be populated with a failure message -bool AP_AHRS_DCM::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const +// requires_position should be true if horizontal position configuration should be checked (not used) +bool AP_AHRS_DCM::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const { if (!healthy()) { hal.util->snprintf(failure_msg, failure_msg_len, "Not healthy"); diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 43dfcc990c..c4a2f580e3 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -121,7 +121,8 @@ public: bool get_velocity_NED(Vector3f &vec) const override; // returns false if we fail arming checks, in which case the buffer will be populated with a failure message - bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override; + // requires_position should be true if horizontal position configuration should be checked (not used) + bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const override; private: float _ki; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 9bbf1d2bf3..32746ab58c 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -1668,7 +1668,8 @@ bool AP_AHRS_NavEKF::healthy(void) const } // returns false if we fail arming checks, in which case the buffer will be populated with a failure message -bool AP_AHRS_NavEKF::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const +// requires_position should be true if horizontal position configuration should be checked +bool AP_AHRS_NavEKF::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const { bool ret = true; if (!healthy()) { @@ -1705,7 +1706,7 @@ bool AP_AHRS_NavEKF::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) c hal.util->snprintf(failure_msg, failure_msg_len, "EKF3 not started"); return false; } - return EKF3.pre_arm_check(failure_msg, failure_msg_len) && ret; + return EKF3.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret; #endif } diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index bbbb78d20a..5d0307ceca 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -203,7 +203,8 @@ public: bool healthy() const override; // returns false if we fail arming checks, in which case the buffer will be populated with a failure message - bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override; + // requires_position should be true if horizontal position configuration should be checked + bool pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const override; // true if the AHRS has completed initialisation bool initialised() const override;