Browse Source

Sub: use singletons in AP_Arming

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
cc46ab3092
  1. 6
      ArduSub/AP_Arming_Sub.cpp
  2. 7
      ArduSub/AP_Arming_Sub.h
  3. 2
      ArduSub/Sub.h

6
ArduSub/AP_Arming_Sub.cpp

@ -28,11 +28,11 @@ bool AP_Arming_Sub::ins_checks(bool display_failure) @@ -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";
}

7
ArduSub/AP_Arming_Sub.h

@ -4,11 +4,8 @@ @@ -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;

2
ArduSub/Sub.h

@ -333,7 +333,7 @@ private: @@ -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…
Cancel
Save