mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: call hal GPIO check
This commit is contained in:
parent
67bb7417ec
commit
88f645afc2
|
@ -1027,6 +1027,11 @@ bool AP_Arming::system_checks(bool report)
|
|||
return false;
|
||||
}
|
||||
|
||||
if (!hal.gpio->arming_checks(sizeof(buffer), buffer)) {
|
||||
check_failed(report, "%s", buffer);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
|
||||
#if AP_RPM_ENABLED
|
||||
auto *rpm = AP::rpm();
|
||||
|
|
Loading…
Reference in New Issue