From b84137ae42b3f6d672438d085d190dc15d425f51 Mon Sep 17 00:00:00 2001 From: "levinemax@gmail.com" Date: Fri, 1 Apr 2011 14:45:35 +0000 Subject: [PATCH] Y6 frame, motors changed to All TOP CCW / BOTTOM CW git-svn-id: https://arducopter.googlecode.com/svn/trunk@1833 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/motors.pde | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduCopterMega/motors.pde b/ArduCopterMega/motors.pde index 9e90d3fa50..3e235eb32a 100644 --- a/ArduCopterMega/motors.pde +++ b/ArduCopterMega/motors.pde @@ -155,17 +155,17 @@ set_servos_4() motor_out[CH_1] = g.rc_3.radio_out - roll_out + pitch_out; // CW //back - motor_out[CH_8] = ((g.rc_3.radio_out * 0.92) - g.rc_2.pwm_out); // CW TOP - motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out; // CCW + motor_out[CH_8] = ((g.rc_3.radio_out * 0.92) - g.rc_2.pwm_out); // CCW TOP + motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out; // CW //yaw motor_out[CH_2] += g.rc_4.pwm_out; // CCW motor_out[CH_7] += g.rc_4.pwm_out; // CCW - motor_out[CH_4] += g.rc_4.pwm_out; // CCW + motor_out[CH_8] += g.rc_4.pwm_out; // CCW motor_out[CH_3] -= g.rc_4.pwm_out; // CW motor_out[CH_1] -= g.rc_4.pwm_out; // CW - motor_out[CH_8] -= g.rc_4.pwm_out; // CW + motor_out[CH_4] -= g.rc_4.pwm_out; // CW }else{