From cfb74406b6069d740168f5913dce41342a3daeac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Jan 2016 13:48:10 +1100 Subject: [PATCH] Plane: fixed call to motors->Init() for quadplane --- ArduPlane/quadplane.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 18ae48c47c..eb93de4c97 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -366,9 +366,7 @@ void QuadPlane::setup(void) } AP_Param::load_object_from_eeprom(wp_nav, wp_nav->var_info); - // for some strange reason we need to call wrong frame first, or - // setup_motors() doesn't run - motors->set_frame_orientation(AP_MOTORS_PLUS_FRAME); + motors->Init(); motors->set_frame_orientation(AP_MOTORS_X_FRAME); motors->set_throttle_range(0, thr_min_pwm, thr_max_pwm); motors->set_hover_throttle(500);