From c0edb56fef123aeb888cebb5162f4dfb89538015 Mon Sep 17 00:00:00 2001 From: CaranchoEngineering Date: Wed, 14 Jul 2010 08:22:46 +0000 Subject: [PATCH] fixed throttle range for motor arming, removed negative sign for roll in acro mode now that APM orientation is decided git-svn-id: https://arducopter.googlecode.com/svn/trunk@43 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- Arducopter/Arducopter.pde | 19 ++++++------------- 1 file changed, 6 insertions(+), 13 deletions(-) diff --git a/Arducopter/Arducopter.pde b/Arducopter/Arducopter.pde index 6d4d9f80b4..cc20b01c84 100644 --- a/Arducopter/Arducopter.pde +++ b/Arducopter/Arducopter.pde @@ -323,14 +323,7 @@ void Rate_control() float currentRollRate, currentPitchRate, currentYawRate; // ROLL CONTROL - - // NOTE: We need to test THIS !! Plaese CHECK - #ifdef FLIGHT_MODE_+ - currentRollRate = read_adc(0); // I need a positive sign here - #endif - #ifdef FLIGHT_MODE_X - currentRollRate = -read_adc(0); // Original from Ted - #endif + currentRollRate = read_adc(0); // I need a positive sign here err_roll = ((ch_roll-1500) * xmitFactor) - currentRollRate; @@ -699,7 +692,7 @@ void loop(){ command_rx_yaw_diff = 0; } // Arm motor output - if (ch_throttle < 1100) { + if (ch_throttle < 1200) { control_yaw = 0; if (ch_yaw > 1800) motorArmed = 1; @@ -719,10 +712,10 @@ void loop(){ backMotor = ch_throttle - control_pitch + control_yaw; #endif #ifdef FLIGHT_MODE_X - frontMotor = ch_throttle + control_roll - control_pitch - control_yaw; // front left motor - rightMotor = ch_throttle - control_roll - control_pitch + control_yaw; // front right motor - leftMotor = ch_throttle + control_roll + control_pitch + control_yaw; // rear left motor - backMotor = ch_throttle - control_roll + control_pitch - control_yaw; // rear right motor + frontMotor = ch_throttle + control_roll + control_pitch - control_yaw; // front left motor + rightMotor = ch_throttle - control_roll + control_pitch + control_yaw; // front right motor + leftMotor = ch_throttle + control_roll - control_pitch + control_yaw; // rear left motor + backMotor = ch_throttle - control_roll - control_pitch - control_yaw; // rear right motor #endif } if (motorArmed == 0) {