mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Arming: check pin arming_checks
This commit is contained in:
parent
8660e98b57
commit
f91e995e98
@ -39,6 +39,7 @@
|
||||
#include <AP_GyroFFT/AP_GyroFFT.h>
|
||||
#include <AP_RCMapper/AP_RCMapper.h>
|
||||
#include <AP_VisualOdom/AP_VisualOdom.h>
|
||||
#include <AP_Parachute/AP_Parachute.h>
|
||||
#include <AP_OSD/AP_OSD.h>
|
||||
|
||||
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
|
||||
@ -852,6 +853,27 @@ bool AP_Arming::system_checks(bool report)
|
||||
return false;
|
||||
}
|
||||
|
||||
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
|
||||
auto *rpm = AP::rpm();
|
||||
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1] {};
|
||||
if (rpm && !rpm->arming_checks(sizeof(buffer), buffer)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);
|
||||
return false;
|
||||
}
|
||||
auto *relay = AP::relay();
|
||||
if (relay && !relay->arming_checks(sizeof(buffer), buffer)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);
|
||||
return false;
|
||||
}
|
||||
#if HAL_PARACHUTE_ENABLED
|
||||
auto *chute = AP::parachute();
|
||||
if (chute && !chute->arming_checks(sizeof(buffer), buffer)) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, report, "%s", buffer);
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user