From d681c067a10b2f8cdb4fafa4cda781b1dc5699a8 Mon Sep 17 00:00:00 2001 From: jphelirc Date: Tue, 24 Aug 2010 17:34:26 +0000 Subject: [PATCH] Throttle check for initial motor startup git-svn-id: https://arducopter.googlecode.com/svn/trunk@308 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- Arducopter/Arducopter.pde | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Arducopter/Arducopter.pde b/Arducopter/Arducopter.pde index a800c4b97e..2bcb51153b 100644 --- a/Arducopter/Arducopter.pde +++ b/Arducopter/Arducopter.pde @@ -53,7 +53,7 @@ //#define IsNEWMTEK// Do we have MTEK with new firmware #define IsMAG // Do we have a Magnetometer connected, if have remember to activate it from Configurator //#define IsTEL // Do we have a telemetry connected, eg. XBee connected on Telemetry port -//#define IsAM // Do we have motormount LED's. AM = Atraction Mode +#define IsAM // Do we have motormount LED's. AM = Atraction Mode #define CONFIGURATOR // Do se use Configurator or normal text output over serial link @@ -631,8 +631,10 @@ void loop(){ command_rx_yaw_diff = 0; if (ch_yaw < 1200) { if (Arming_counter > ARM_DELAY){ + if(ch_throttle > 800) { motorArmed = 1; minThrottle = 1100; + } } else Arming_counter++; @@ -737,4 +739,4 @@ void loop(){ // END of Arducopter.pde - +