From 0735c2b62ffb090189c8bcff15fa1431ded7027e Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Wed, 25 Jan 2012 22:30:53 -0800 Subject: [PATCH] Arducopter Motors Hexa: Change ordering of MOT designations in Plus frame * This will change the output order for APM2, but not APM1. --- ArduCopter/motors_hexa.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde index 2befbcb2a4..1efb2f87fd 100644 --- a/ArduCopter/motors_hexa.pde +++ b/ArduCopter/motors_hexa.pde @@ -55,14 +55,14 @@ static void output_motors_armed() pitch_out = g.rc_2.pwm_out / 2; //FRONT SIDE - motor_out[MOT_1] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT RIGHT CCW - motor_out[MOT_2] = g.rc_3.radio_out + g.rc_2.pwm_out; // FRONT CW - motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT LEFT CCW + motor_out[MOT_5] = g.rc_3.radio_out - roll_out + pitch_out; // FRONT RIGHT CCW + motor_out[MOT_6] = g.rc_3.radio_out + g.rc_2.pwm_out; // FRONT CW + motor_out[MOT_1] = g.rc_3.radio_out + roll_out + pitch_out; // FRONT LEFT CCW //BACK SIDE - motor_out[MOT_4] = g.rc_3.radio_out + roll_out - pitch_out; // BACK LEFT CW - motor_out[MOT_5] = g.rc_3.radio_out - g.rc_2.pwm_out; // BACK CCW - motor_out[MOT_6] = g.rc_3.radio_out - roll_out - pitch_out; // BACK RIGHT CW + motor_out[MOT_2] = g.rc_3.radio_out + roll_out - pitch_out; // BACK LEFT CW + motor_out[MOT_3] = g.rc_3.radio_out - g.rc_2.pwm_out; // BACK CCW + motor_out[MOT_4] = g.rc_3.radio_out - roll_out - pitch_out; // BACK RIGHT CW } // Yaw