From f7a788dc44b003542f41438fe6fa4f1049f04257 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 30 Aug 2021 16:53:22 +0100 Subject: [PATCH] AP_Arming: add rc_in_calibration_check to manual_transmitter_checks and mandatory_checks --- libraries/AP_Arming/AP_Arming.cpp | 16 +++++++++++++++- libraries/AP_Arming/AP_Arming.h | 4 +++- 2 files changed, 18 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 3cce73d0c0..7650546657 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -686,6 +686,15 @@ bool AP_Arming::rc_calibration_checks(bool report) return check_passed; } +bool AP_Arming::rc_in_calibration_check(bool report) +{ + if (rc().calibrating()) { + check_failed(ARMING_CHECK_RC, report, "RC calibrating"); + return false; + } + return true; +} + bool AP_Arming::manual_transmitter_checks(bool report) { if ((checks_to_perform & ARMING_CHECK_ALL) || @@ -701,7 +710,7 @@ bool AP_Arming::manual_transmitter_checks(bool report) } } - return true; + return rc_in_calibration_check(report); } bool AP_Arming::mission_checks(bool report) @@ -1331,6 +1340,11 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) return true; } +bool AP_Arming::mandatory_checks(bool report) +{ + return rc_in_calibration_check(report); +} + //returns true if arming occurred successfully bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) { diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index d2955d28ed..17ec0aed86 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -158,6 +158,8 @@ protected: virtual bool rc_calibration_checks(bool report); + bool rc_in_calibration_check(bool report); + bool rc_arm_checks(AP_Arming::Method method); bool manual_transmitter_checks(bool report); @@ -195,7 +197,7 @@ protected: bool disarm_switch_checks(bool report) const; // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced - virtual bool mandatory_checks(bool report) { return true; } + virtual bool mandatory_checks(bool report); // returns true if a particular check is enabled bool check_enabled(const enum AP_Arming::ArmingChecks check) const;