AP_AHRS: pre_arm_check may skip position checks

This commit is contained in:
Randy Mackay 2021-01-21 12:42:19 +09:00 committed by Andrew Tridgell
parent 49e2a0caed
commit 62932f884f
5 changed files with 11 additions and 6 deletions

View File

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

View File

@ -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");

View File

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

View File

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

View File

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