From 7b4f311f287feb0443d08bd00eb48d5c458bda36 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Thu, 13 Dec 2012 20:30:23 +0900 Subject: [PATCH] ArduCopter: remove throttle limit of 800 for quads, hexas and octacopters Note: Y6 and OctaQuads still have the 800 limit because they do not have the latest stability patch --- ArduCopter/motors.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 4c4d6be7b5..a05326ae39 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -210,7 +210,7 @@ static void init_disarm_motors() static void set_servos_4() { -#if FRAME_CONFIG != HELI_FRAME +#if FRAME_CONFIG != HELI_FRAME || FRAME_CONFIG != QUAD_FRAME || FRAME_CONFIG != HEXA_FRAME || FRAME_CONFIG != OCTA_FRAME // temp fix for bad attitude g.rc_3.servo_out = min(g.rc_3.servo_out, 800); #endif