From 21f9b7e531600a45871429a88ea0a78690619ea9 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Fri, 17 Aug 2012 23:58:57 -0700 Subject: [PATCH] ACM : temp fix for throttle output limit I had a bad crash when I lost authority. The logs showed the throttle pegged at 1000 which killed my control. We went round and round on this and somehow settled on no limit. That wasn't a good idea. This should really be hard coded into the Motors Library, but for now I'm just sticking it here. --- ArduCopter/motors.pde | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 998d973e3a..cb2e6ee824 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -192,6 +192,9 @@ static void init_disarm_motors() static void set_servos_4() { + // temp fix for bad attitude + g.rc_3.servo_out = min(g.rc_3.servo_out, 800); + motors.output(); }