mirror of https://github.com/ArduPilot/ardupilot
Blimp: fix RC init order to avoid error message
This commit is contained in:
parent
adb58a9b60
commit
085cb72fb5
|
@ -48,8 +48,8 @@ void Blimp::init_ardupilot()
|
|||
allocate_motors();
|
||||
|
||||
// initialise rc channels including setting mode
|
||||
rc().init();
|
||||
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
||||
rc().init();
|
||||
|
||||
// sets up motors and output to escs
|
||||
init_rc_out();
|
||||
|
|
Loading…
Reference in New Issue