diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 61afe233a7..cc61d6447a 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1060,10 +1060,11 @@ bool NavEKF3::healthy(void) const } // returns false if we fail arming checks, in which case the buffer will be populated with a failure message -bool NavEKF3::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 NavEKF3::pre_arm_check(bool requires_position, char *failure_msg, uint8_t failure_msg_len) const { // check source configuration - if (!sources.pre_arm_check(failure_msg, failure_msg_len)) { + if (!sources.pre_arm_check(requires_position, failure_msg, failure_msg_len)) { return false; } diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 94e474f3d8..1b3c750a77 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -56,7 +56,8 @@ public: bool healthy(void) const; // 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; + // 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; // returns the index of the primary core // return -1 if no primary core selected