From 6fd20d880bc6a5f7bfc6417bcf3007ee0118f307 Mon Sep 17 00:00:00 2001 From: jphelirc Date: Tue, 21 Dec 2010 03:23:03 +0000 Subject: [PATCH] min throttle fix git-svn-id: https://arducopter.googlecode.com/svn/trunk@1221 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArducopterNG/System.pde | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/ArducopterNG/System.pde b/ArducopterNG/System.pde index a6f1252004..f3a1782331 100644 --- a/ArducopterNG/System.pde +++ b/ArducopterNG/System.pde @@ -55,6 +55,7 @@ void APM_Init() { /* ********************************************************* */ ///////////////////////////////////////////////////////// // Normal Initialization sequence starts from here. + readUserConfig(); // Load user configurable items from EEPROM APM_RC.Init(); // APM Radio initialization @@ -112,7 +113,9 @@ void APM_Init() { flightOrientation = SW_DIP1; // DIP1 off = we are in + mode, DIP1 on = we are in x mode - readUserConfig(); // Load user configurable items from EEPROM + + // readUserConfig moved to up to ensure min throttle is read from eeprom + //readUserConfig(); // Load user configurable items from EEPROM // Safety measure for Channel mids if(roll_mid < 1400 || roll_mid > 1600) roll_mid = 1500; @@ -199,4 +202,4 @@ void APM_Init() { } - +