mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: use baro arming checks call
This commit is contained in:
parent
52e1be74a2
commit
0c3be8b782
|
@ -264,8 +264,9 @@ bool AP_Arming::barometer_checks(bool report)
|
|||
#endif
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_BARO)) {
|
||||
if (!AP::baro().all_healthy()) {
|
||||
check_failed(ARMING_CHECK_BARO, report, "Barometer not healthy");
|
||||
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
||||
if (!AP::baro().arming_checks(sizeof(buffer), buffer)) {
|
||||
check_failed(ARMING_CHECK_BARO, report, "Baro: %s", buffer);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue