From 30c1a040d7296dd427a2a219eb7f8f7558889840 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 4 Sep 2017 13:23:42 +1000 Subject: [PATCH] Copter: prearm baro checks are called in parent class --- ArduCopter/AP_Arming.cpp | 3 +-- ArduCopter/AP_Arming.h | 2 +- libraries/AP_Arming/AP_Arming.h | 2 +- 3 files changed, 3 insertions(+), 4 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 0ee3844326..1986611c31 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -57,8 +57,7 @@ bool AP_Arming_Copter::pre_arm_checks(bool display_failure) return true; } - return barometer_checks(display_failure) - & rc_calibration_checks(display_failure) + return rc_calibration_checks(display_failure) & compass_checks(display_failure) & gps_checks(display_failure) & fence_checks(display_failure) diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index eb897de786..ed6a1723a7 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -34,6 +34,7 @@ protected: bool ins_checks(bool display_failure) override; bool compass_checks(bool display_failure) override; bool gps_checks(bool display_failure) override; + bool barometer_checks(bool display_failure) override; // NOTE! the following check functions *DO NOT* call into AP_Arming! bool fence_checks(bool display_failure); @@ -41,7 +42,6 @@ protected: bool parameter_checks(bool display_failure); bool motor_checks(bool display_failure); bool pilot_throttle_checks(bool display_failure); - bool barometer_checks(bool display_failure); void set_pre_arm_check(bool b); diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 2bbcbd8b93..ff93ec585e 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -83,7 +83,7 @@ protected: uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]; uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]; - bool barometer_checks(bool report); + virtual bool barometer_checks(bool report); bool airspeed_checks(bool report);