From 3a9eef658c48057f5bc157760de2624989de8c0e Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 24 Nov 2021 13:22:14 +0100 Subject: [PATCH] Commander: remove preflight check for transition switch This check enforced setting a VTOL transition switch if an RC as used on a VTOL. It comes from a time when the only way to transtion was through the RC switch, whereas now we have also a mavlink message in place for it, so enforcing it is no longer needed. Signed-off-by: Silvan Fuhrer --- .../Arming/PreFlightCheck/PreFlightCheck.cpp | 2 +- .../Arming/PreFlightCheck/PreFlightCheck.hpp | 2 +- .../checks/rcCalibrationCheck.cpp | 25 +------------------ 3 files changed, 3 insertions(+), 26 deletions(-) diff --git a/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp b/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp index 63dec5b82b..259af6b878 100644 --- a/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp +++ b/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.cpp @@ -201,7 +201,7 @@ bool PreFlightCheck::preflightCheck(orb_advert_t *mavlink_log_pub, vehicle_statu param_get(param_find("COM_RC_IN_MODE"), &com_rc_in_mode); if (com_rc_in_mode == 0) { - if (rcCalibrationCheck(mavlink_log_pub, report_failures, status.is_vtol) != OK) { + if (rcCalibrationCheck(mavlink_log_pub, report_failures) != OK) { if (report_failures) { mavlink_log_critical(mavlink_log_pub, "RC calibration check failed"); } diff --git a/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp b/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp index 0110e1ef58..315b483e45 100644 --- a/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp +++ b/src/modules/commander/Arming/PreFlightCheck/PreFlightCheck.hpp @@ -106,7 +106,7 @@ private: static bool imuConsistencyCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool report_status); static bool airspeedCheck(orb_advert_t *mavlink_log_pub, vehicle_status_s &status, const bool optional, const bool report_fail, const bool prearm, const bool max_airspeed_check_en, const float arming_max_airspeed_allowed); - static int rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL); + static int rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool report_fail); static bool powerCheck(orb_advert_t *mavlink_log_pub, const vehicle_status_s &status, const bool report_fail, const bool prearm); static bool ekf2Check(orb_advert_t *mavlink_log_pub, vehicle_status_s &vehicle_status, const bool optional, diff --git a/src/modules/commander/Arming/PreFlightCheck/checks/rcCalibrationCheck.cpp b/src/modules/commander/Arming/PreFlightCheck/checks/rcCalibrationCheck.cpp index 9c144b47cf..0272dc1b58 100644 --- a/src/modules/commander/Arming/PreFlightCheck/checks/rcCalibrationCheck.cpp +++ b/src/modules/commander/Arming/PreFlightCheck/checks/rcCalibrationCheck.cpp @@ -52,7 +52,7 @@ */ #define RC_INPUT_HIGHEST_MAX_US 3500 -int PreFlightCheck::rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool report_fail, bool isVTOL) +int PreFlightCheck::rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool report_fail) { char nbuf[20]; param_t _parameter_handles_min, _parameter_handles_trim, _parameter_handles_max, @@ -67,29 +67,6 @@ int PreFlightCheck::rcCalibrationCheck(orb_advert_t *mavlink_log_pub, bool repor unsigned j = 0; - /* if VTOL, check transition switch mapping */ - if (isVTOL) { - param_t trans_parm = param_find("RC_MAP_TRANS_SW"); - - if (trans_parm == PARAM_INVALID) { - if (report_fail) { mavlink_log_critical(mavlink_log_pub, "RC_MAP_TRANS_SW PARAMETER MISSING."); } - - /* give system time to flush error message in case there are more */ - px4_usleep(100000); - map_fail_count++; - - } else { - int32_t transition_switch; - param_get(trans_parm, &transition_switch); - - if (transition_switch < 1) { - if (report_fail) { mavlink_log_critical(mavlink_log_pub, "Transition switch RC_MAP_TRANS_SW not set."); } - - map_fail_count++; - } - } - } - /* first check channel mappings */ while (rc_map_mandatory[j] != nullptr) {