AP_NavEKF3: pre_arm_check may skip position checks

This commit is contained in:
Randy Mackay 2021-01-21 12:42:58 +09:00 committed by Andrew Tridgell
parent 8ecac27777
commit f6cb0819ef
2 changed files with 5 additions and 3 deletions

View File

@ -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;
}

View File

@ -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