From ee78818f5ac02980682a1c8009683370be504f53 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 12 Jun 2012 13:57:31 -0700 Subject: [PATCH] Raised the Max throttle to 1000, min to 200. Worked good in SIM with Tridge's motor safety patch. --- ArduCopter/config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 1e7d376b3c..6db23de257 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -441,10 +441,10 @@ # define THROTTLE_FAILSAFE_ACTION 2 #endif #ifndef MINIMUM_THROTTLE -# define MINIMUM_THROTTLE 130 +# define MINIMUM_THROTTLE 200 #endif #ifndef MAXIMUM_THROTTLE -# define MAXIMUM_THROTTLE 850 +# define MAXIMUM_THROTTLE 1000 #endif #ifndef AUTO_LAND_TIME