From e9375defb03d5aca48dc9b1852bb780b446d2248 Mon Sep 17 00:00:00 2001 From: jasonshort Date: Sat, 5 Feb 2011 06:31:03 +0000 Subject: [PATCH] clean-up only git-svn-id: https://arducopter.googlecode.com/svn/trunk@1592 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/motors.pde | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) diff --git a/ArduCopterMega/motors.pde b/ArduCopterMega/motors.pde index 8b1525a665..1d8e253cc1 100644 --- a/ArduCopterMega/motors.pde +++ b/ArduCopterMega/motors.pde @@ -107,7 +107,6 @@ set_servos_4() motor_out[CH_4] = rc_3.radio_out - rc_2.pwm_out; // servo Yaw - //motor_out[CH_3] = rc_4.radio_out; APM_RC.OutputCh(CH_7, rc_4.radio_out); @@ -140,7 +139,8 @@ set_servos_4() } - + + // limit output so motors don't stop motor_out[CH_1] = constrain(motor_out[CH_1], out_min, rc_3.radio_max); motor_out[CH_2] = constrain(motor_out[CH_2], out_min, rc_3.radio_max); motor_out[CH_3] = constrain(motor_out[CH_3], out_min, rc_3.radio_max); @@ -211,12 +211,7 @@ set_servos_4() } }else{ - num++; - if (num > 10){ - num = 0; - //Serial.print("-"); - } - + // our motor is unarmed, we're on the ground reset_I(); if(rc_3.control_in > 0){