mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: use singletons in AP_Arming
This commit is contained in:
parent
ea12f6caec
commit
cc46ab3092
@ -28,11 +28,11 @@ bool AP_Arming_Sub::ins_checks(bool display_failure)
|
||||
return false;
|
||||
}
|
||||
|
||||
// additional plane specific checks
|
||||
// additional sub-specific checks
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_INS)) {
|
||||
if (!ahrs.healthy()) {
|
||||
const char *reason = ahrs.prearm_failure_reason();
|
||||
if (!AP::ahrs().healthy()) {
|
||||
const char *reason = AP::ahrs().prearm_failure_reason();
|
||||
if (reason == nullptr) {
|
||||
reason = "AHRS not healthy";
|
||||
}
|
||||
|
@ -4,11 +4,8 @@
|
||||
|
||||
class AP_Arming_Sub : public AP_Arming {
|
||||
public:
|
||||
AP_Arming_Sub(const AP_AHRS &ahrs_ref, Compass &compass,
|
||||
const AP_BattMonitor &battery)
|
||||
: AP_Arming(ahrs_ref, compass, battery)
|
||||
{
|
||||
}
|
||||
|
||||
AP_Arming_Sub() : AP_Arming() { }
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_Arming_Sub(const AP_Arming_Sub &other) = delete;
|
||||
|
@ -333,7 +333,7 @@ private:
|
||||
FUNCTOR_BIND_MEMBER(&Sub::handle_battery_failsafe, void, const char*, const int8_t),
|
||||
_failsafe_priorities};
|
||||
|
||||
AP_Arming_Sub arming{ahrs, compass, battery};
|
||||
AP_Arming_Sub arming;
|
||||
|
||||
// Altitude
|
||||
// The cm/s we are moving up or down based on filtered data - Positive = UP
|
||||
|
Loading…
Reference in New Issue
Block a user