From b63e68a5ef43adbd912e93c79e7c08fd9f97a3d5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 21 Sep 2021 02:47:33 +0100 Subject: [PATCH] Plane: fix RC init order to avoid error message --- ArduPlane/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 65124c7d21..fa9fdacefb 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -35,12 +35,12 @@ void Plane::init_ardupilot() pitchController.convert_pid(); // initialise rc channels including setting mode - rc().init(); #if HAL_QUADPLANE_ENABLED rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, (quadplane.enabled() && (quadplane.options & QuadPlane::OPTION_AIRMODE_UNUSED) && (rc().find_channel_for_option(RC_Channel::AUX_FUNC::AIRMODE) == nullptr)) ? RC_Channel::AUX_FUNC::ARMDISARM_AIRMODE : RC_Channel::AUX_FUNC::ARMDISARM); #else rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); #endif + rc().init(); relay.init();