Browse Source

Sub: fix RC init order to avoid error message

gps-1.3.1
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
adb58a9b60
  1. 3
      ArduSub/system.cpp

3
ArduSub/system.cpp

@ -62,8 +62,9 @@ void Sub::init_ardupilot() @@ -62,8 +62,9 @@ void Sub::init_ardupilot()
#endif
// initialise rc channels including setting mode
rc().init();
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
rc().init();
init_rc_in(); // sets up rc channels from radio
init_rc_out(); // sets up motors and output to escs

Loading…
Cancel
Save