Throttle check for initial motor startup

git-svn-id: https://arducopter.googlecode.com/svn/trunk@308 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jphelirc 2010-08-24 17:34:26 +00:00
parent aef969bbb6
commit d681c067a1
1 changed files with 4 additions and 2 deletions

View File

@ -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