From 6dfa53bcb138072cf576995bf5e505e4d29abb31 Mon Sep 17 00:00:00 2001 From: Olivier ADLER Date: Sun, 11 Sep 2011 23:32:04 +0200 Subject: [PATCH] Signed-off-by: Olivier ADLER slightly upped motor out values for motor test. Was too low for some ESCs. --- ArduCopter/motors_hexa.pde | 36 ++++++++++++++++++------------------ ArduCopter/motors_octa.pde | 16 ++++++++-------- ArduCopter/motors_quad.pde | 24 ++++++++++++------------ ArduCopter/motors_tri.pde | 6 +++--- ArduCopter/motors_y6.pde | 12 ++++++------ 5 files changed, 47 insertions(+), 47 deletions(-) diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde index d1dde00eee..066e7c2d17 100644 --- a/ArduCopter/motors_hexa.pde +++ b/ArduCopter/motors_hexa.pde @@ -138,21 +138,21 @@ static void output_motor_test() // 31 // 24 if(g.rc_1.control_in > 3000){ // right - motor_out[CH_1] += 50; + motor_out[CH_1] += 100; } if(g.rc_1.control_in < -3000){ // left - motor_out[CH_2] += 50; + motor_out[CH_2] += 100; } if(g.rc_2.control_in > 3000){ // back - motor_out[CH_8] += 50; - motor_out[CH_4] += 50; + motor_out[CH_8] += 100; + motor_out[CH_4] += 100; } if(g.rc_2.control_in < -3000){ // front - motor_out[CH_7] += 50; - motor_out[CH_3] += 50; + motor_out[CH_7] += 100; + motor_out[CH_3] += 100; } }else{ @@ -160,21 +160,21 @@ static void output_motor_test() // 2 1 // 4 if(g.rc_1.control_in > 3000){ // right - motor_out[CH_4] += 50; - motor_out[CH_8] += 50; + motor_out[CH_4] += 100; + motor_out[CH_8] += 100; } if(g.rc_1.control_in < -3000){ // left - motor_out[CH_7] += 50; - motor_out[CH_3] += 50; + motor_out[CH_7] += 100; + motor_out[CH_3] += 100; } if(g.rc_2.control_in > 3000){ // back - motor_out[CH_2] += 50; + motor_out[CH_2] += 100; } if(g.rc_2.control_in < -3000){ // front - motor_out[CH_1] += 50; + motor_out[CH_1] += 100; } } @@ -189,27 +189,27 @@ static void output_motor_test() /* APM_RC.OutputCh(CH_2, g.rc_3.radio_min); - APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_3, g.rc_3.radio_min); - APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_7, g.rc_3.radio_min); - APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_1, g.rc_3.radio_min); - APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_4, g.rc_3.radio_min); - APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_8, g.rc_3.radio_min); - APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100); delay(1000); } */ diff --git a/ArduCopter/motors_octa.pde b/ArduCopter/motors_octa.pde index c798014c16..d195b8ad61 100644 --- a/ArduCopter/motors_octa.pde +++ b/ArduCopter/motors_octa.pde @@ -183,35 +183,35 @@ static void output_motors_disarmed() static void output_motor_test() { APM_RC.OutputCh(CH_7, g.rc_3.radio_min); - APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_1, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_1, g.rc_3.radio_min); - APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_3, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_3, g.rc_3.radio_min); - APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_11, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_11, g.rc_3.radio_min); - APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_4, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_4, g.rc_3.radio_min); - APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_2, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_2, g.rc_3.radio_min); - APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_8, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_8, g.rc_3.radio_min); - APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_10, g.rc_3.radio_min + 100); delay(1000); APM_RC.OutputCh(CH_10, g.rc_3.radio_min); - APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 50); + APM_RC.OutputCh(CH_7, g.rc_3.radio_min + 100); delay(1000); } diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde index dc6b36ee06..d5af159ad4 100644 --- a/ArduCopter/motors_quad.pde +++ b/ArduCopter/motors_quad.pde @@ -139,23 +139,23 @@ static void output_motor_test() // 31 // 24 if(g.rc_1.control_in > 3000){ - motor_out[CH_1] += 50; - motor_out[CH_4] += 50; + motor_out[CH_1] += 100; + motor_out[CH_4] += 100; } if(g.rc_1.control_in < -3000){ - motor_out[CH_2] += 50; - motor_out[CH_3] += 50; + motor_out[CH_2] += 100; + motor_out[CH_3] += 100; } if(g.rc_2.control_in > 3000){ - motor_out[CH_2] += 50; - motor_out[CH_4] += 50; + motor_out[CH_2] += 100; + motor_out[CH_4] += 100; } if(g.rc_2.control_in < -3000){ - motor_out[CH_1] += 50; - motor_out[CH_3] += 50; + motor_out[CH_1] += 100; + motor_out[CH_3] += 100; } }else{ @@ -163,16 +163,16 @@ static void output_motor_test() // 2 1 // 4 if(g.rc_1.control_in > 3000) - motor_out[CH_1] += 50; + motor_out[CH_1] += 100; if(g.rc_1.control_in < -3000) - motor_out[CH_2] += 50; + motor_out[CH_2] += 100; if(g.rc_2.control_in > 3000) - motor_out[CH_4] += 50; + motor_out[CH_4] += 100; if(g.rc_2.control_in < -3000) - motor_out[CH_3] += 50; + motor_out[CH_3] += 100; } APM_RC.OutputCh(CH_1, motor_out[CH_1]); diff --git a/ArduCopter/motors_tri.pde b/ArduCopter/motors_tri.pde index 0fbff12ab7..ec9c747b41 100644 --- a/ArduCopter/motors_tri.pde +++ b/ArduCopter/motors_tri.pde @@ -96,15 +96,15 @@ static void output_motor_test() if(g.rc_1.control_in > 3000){ // right - motor_out[CH_1] += 50; + motor_out[CH_1] += 100; } if(g.rc_1.control_in < -3000){ // left - motor_out[CH_2] += 50; + motor_out[CH_2] += 100; } if(g.rc_2.control_in > 3000){ // back - motor_out[CH_4] += 50; + motor_out[CH_4] += 100; } APM_RC.OutputCh(CH_1, motor_out[CH_1]); diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde index ede41a0fba..23f51218a2 100644 --- a/ArduCopter/motors_y6.pde +++ b/ArduCopter/motors_y6.pde @@ -144,18 +144,18 @@ static void output_motor_test() if(g.rc_1.control_in > 3000){ // right - motor_out[CH_1] += 50; - motor_out[CH_7] += 50; + motor_out[CH_1] += 100; + motor_out[CH_7] += 100; } if(g.rc_1.control_in < -3000){ // left - motor_out[CH_2] += 50; - motor_out[CH_3] += 50; + motor_out[CH_2] += 100; + motor_out[CH_3] += 100; } if(g.rc_2.control_in > 3000){ // back - motor_out[CH_8] += 50; - motor_out[CH_4] += 50; + motor_out[CH_8] += 100; + motor_out[CH_4] += 100; } APM_RC.OutputCh(CH_1, motor_out[CH_1]);