Copter: fix input_manager init order to resolve compiler warning

This commit is contained in:
Randy Mackay 2015-11-27 15:18:17 +09:00
parent 47b9f6598a
commit 06880e8b04
1 changed files with 4 additions and 3 deletions

View File

@ -32,9 +32,6 @@ Copter::Copter(void) :
control_mode(STABILIZE),
#if FRAME_CONFIG == HELI_FRAME // helicopter constructor requires more arguments
motors(g.rc_7, g.heli_servo_rsc, g.heli_servo_1, g.heli_servo_2, g.heli_servo_3, g.heli_servo_4, MAIN_LOOP_RATE),
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
input_manager(MAIN_LOOP_RATE),
#elif FRAME_CONFIG == TRI_FRAME // tri constructor requires additional rc_7 argument to allow tail servo reversing
motors(MAIN_LOOP_RATE),
#elif FRAME_CONFIG == SINGLE_FRAME // single constructor requires extra servos for flaps
@ -125,6 +122,10 @@ Copter::Copter(void) :
#endif
#if PRECISION_LANDING == ENABLED
precland(ahrs, inertial_nav, g.pi_precland, MAIN_LOOP_SECONDS),
#endif
#if FRAME_CONFIG == HELI_FRAME
// ToDo: Input Manager is only used by Heli for 3.3, but will be used by all frames for 3.4
input_manager(MAIN_LOOP_RATE),
#endif
in_mavlink_delay(false),
gcs_out_of_time(false),