mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: fix RC init order to avoid error message
This commit is contained in:
parent
85638cf4fa
commit
b63e68a5ef
@ -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();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user