From 9f9531a79044d05b91736cbad7bb116bb32c8942 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 23 Apr 2019 12:58:51 +1000 Subject: [PATCH] Copter: AP_Arming: correct overriding of arm_checks method This makes the arbitrary decision that arming checks always report failures to the GCS. Fixes: In file included from ../../ArduCopter/events.cpp:1: In file included from ../../ArduCopter/Copter.h:91: ../../ArduCopter/AP_Arming.h:33:69: fatal error: non-virtual member function marked 'override' hides virtual member function bool arm_checks(bool display_failure, AP_Arming::Method method) override; ^ ../../libraries/AP_Arming/AP_Arming.h:64:18: note: hidden overloaded virtual function 'AP_Arming::arm_checks' declared here: different number of parameters (1 vs 2) virtual bool arm_checks(AP_Arming::Method method); ^ 1 error generated. --- ArduCopter/AP_Arming.cpp | 26 +++++++++++++------------- ArduCopter/AP_Arming.h | 2 +- Tools/ardupilotwaf/boards.py | 2 +- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index e14909ee15..a13abfea1a 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -20,7 +20,7 @@ bool AP_Arming_Copter::all_checks_passing(AP_Arming::Method method) { set_pre_arm_check(pre_arm_checks(true)); - return copter.ap.pre_arm_check && arm_checks(true, method); + return copter.ap.pre_arm_check && arm_checks(method); } // perform pre-arm checks @@ -439,13 +439,13 @@ bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure) // arm_checks - perform final checks before arming // always called just before arming. Return true if ok to arm // has side-effect that logging is started -bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method) +bool AP_Arming_Copter::arm_checks(AP_Arming::Method method) { const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf(); // always check if inertial nav has started and is ready if (!ahrs.healthy()) { - check_failed(ARMING_CHECK_NONE, display_failure, "AHRS not healthy"); + check_failed(ARMING_CHECK_NONE, true, "AHRS not healthy"); return false; } @@ -453,7 +453,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method const Compass &_compass = AP::compass(); // check compass health if (!_compass.healthy()) { - check_failed(ARMING_CHECK_NONE, display_failure, "Compass not healthy"); + check_failed(ARMING_CHECK_NONE, true, "Compass not healthy"); return false; } #endif @@ -462,19 +462,19 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method // always check if the current mode allows arming if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) { - check_failed(ARMING_CHECK_NONE, display_failure, "Mode not armable"); + check_failed(ARMING_CHECK_NONE, true, "Mode not armable"); return false; } // always check motors - if (!motor_checks(display_failure)) { + if (!motor_checks(true)) { return false; } // if we are using motor interlock switch and it's enabled, fail to arm // skip check in Throw mode which takes control of the motor interlock if (copter.ap.using_interlock && copter.ap.motor_interlock_switch) { - check_failed(ARMING_CHECK_NONE, display_failure, "Motor Interlock Enabled"); + check_failed(ARMING_CHECK_NONE, true, "Motor Interlock Enabled"); return false; } @@ -496,7 +496,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method // check lean angle if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_INS)) { if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > copter.aparm.angle_max) { - check_failed(ARMING_CHECK_INS, display_failure, "Leaning"); + check_failed(ARMING_CHECK_INS, true, "Leaning"); return false; } } @@ -505,7 +505,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method #if ADSB_ENABLED == ENABLE if ((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS)) { if (copter.failsafe.adsb) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, "ADSB threat detected"); + check_failed(ARMING_CHECK_PARAMETERS, true, "ADSB threat detected"); return false; } } @@ -520,7 +520,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method #endif // check throttle is not too low - must be above failsafe throttle if (copter.g.failsafe_throttle != FS_THR_DISABLED && copter.channel_throttle->get_radio_in() < copter.g.failsafe_throttle_value) { - check_failed(ARMING_CHECK_RC, display_failure, "%s below failsafe", rc_item); + check_failed(ARMING_CHECK_RC, true, "%s below failsafe", rc_item); return false; } @@ -528,13 +528,13 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method if (!(method == AP_Arming::Method::MAVLINK && (control_mode == GUIDED || control_mode == GUIDED_NOGPS))) { // above top of deadband is too always high if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) { - check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item); + check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); return false; } // in manual modes throttle must be at zero #if FRAME_CONFIG != HELI_FRAME if ((copter.flightmode->has_manual_throttle() || control_mode == DRIFT) && copter.channel_throttle->get_control_in() > 0) { - check_failed(ARMING_CHECK_RC, display_failure, "%s too high", rc_item); + check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item); return false; } #endif @@ -543,7 +543,7 @@ bool AP_Arming_Copter::arm_checks(bool display_failure, AP_Arming::Method method // check if safety switch has been pushed if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) { - check_failed(ARMING_CHECK_NONE, display_failure, "Safety Switch"); + check_failed(ARMING_CHECK_NONE, true, "Safety Switch"); return false; } diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index 88da4160bf..18d9229f12 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -30,7 +30,7 @@ protected: bool pre_arm_ekf_attitude_check(); bool pre_arm_terrain_check(bool display_failure); bool pre_arm_proximity_check(bool display_failure); - bool arm_checks(bool display_failure, AP_Arming::Method method); + bool arm_checks(AP_Arming::Method method) override; // NOTE! the following check functions *DO* call into AP_Arming: bool ins_checks(bool display_failure) override; diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index d99e5e2eaa..cede803af8 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -332,7 +332,7 @@ class sitl(Board): ) env.CXXFLAGS += [ - '-Werror=float-equal', + '-Werror=float-equal' ] if not cfg.env.DEBUG: