Browse Source

Plane: use singletons in AP_Arming

master
Peter Barker 7 years ago committed by Peter Barker
parent
commit
3bfa4c8678
  1. 4
      ArduPlane/AP_Arming.cpp
  2. 5
      ArduPlane/AP_Arming.h
  3. 2
      ArduPlane/Plane.h

4
ArduPlane/AP_Arming.cpp

@ -94,8 +94,8 @@ bool AP_Arming_Plane::ins_checks(bool display_failure) @@ -94,8 +94,8 @@ bool AP_Arming_Plane::ins_checks(bool display_failure)
// additional plane 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";
}

5
ArduPlane/AP_Arming.h

@ -8,9 +8,8 @@ @@ -8,9 +8,8 @@
class AP_Arming_Plane : public AP_Arming
{
public:
AP_Arming_Plane(const AP_AHRS &ahrs_ref, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, compass, battery)
AP_Arming_Plane()
: AP_Arming()
{
AP_Param::setup_object_defaults(this, var_info);
}

2
ArduPlane/Plane.h

@ -747,7 +747,7 @@ private: @@ -747,7 +747,7 @@ private:
#endif
// Arming/Disarming mangement class
AP_Arming_Plane arming{ahrs, compass, battery};
AP_Arming_Plane arming;
AP_Param param_loader {var_info};

Loading…
Cancel
Save