From 5c13aa33be79ece794659eed225aeca18d7986e5 Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Tue, 15 Nov 2011 20:59:06 -0800 Subject: [PATCH] Arducopter: each motors_ pde uses APM_RC.SetFastOutputChannels --- ArduCopter/heli.pde | 4 +--- ArduCopter/motors_hexa.pde | 5 ++--- ArduCopter/motors_octa.pde | 5 ++--- ArduCopter/motors_octa_quad.pde | 5 ++--- ArduCopter/motors_quad.pde | 4 +--- ArduCopter/motors_tri.pde | 4 +--- ArduCopter/motors_y6.pde | 5 ++--- 7 files changed, 11 insertions(+), 21 deletions(-) diff --git a/ArduCopter/heli.pde b/ArduCopter/heli.pde index c0d7c03367..ba5fa855f0 100644 --- a/ArduCopter/heli.pde +++ b/ArduCopter/heli.pde @@ -207,9 +207,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 8000; // 250 hz output CH 1, 2, 9 - ICR1 = 8000; // 250 hz output CH 3, 4, 10 - ICR3 = 40000; // 50 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 ); #endif } diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde index 1cb74e8bfd..06a0b2d24a 100644 --- a/ArduCopter/motors_hexa.pde +++ b/ArduCopter/motors_hexa.pde @@ -5,9 +5,8 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 5000; // 400 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 + | MSK_CH_7 | MSK_CH_8 ); #endif } diff --git a/ArduCopter/motors_octa.pde b/ArduCopter/motors_octa.pde index a0afb2b099..207ad26e58 100644 --- a/ArduCopter/motors_octa.pde +++ b/ArduCopter/motors_octa.pde @@ -5,9 +5,8 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 5000; // 400 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 + | MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 ); #endif } diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde index 529c3bcca4..5a77c1a406 100644 --- a/ArduCopter/motors_octa_quad.pde +++ b/ArduCopter/motors_octa_quad.pde @@ -5,9 +5,8 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 5000; // 400 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 + | MSK_CH_7 | MSK_CH_8 | MSK_CH_10 | MSK_CH_11 ); #endif } diff --git a/ArduCopter/motors_quad.pde b/ArduCopter/motors_quad.pde index 1100cc3085..887b10675d 100644 --- a/ArduCopter/motors_quad.pde +++ b/ArduCopter/motors_quad.pde @@ -5,9 +5,7 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 40000; // 50 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 ); #endif } diff --git a/ArduCopter/motors_tri.pde b/ArduCopter/motors_tri.pde index 2590eea1e6..b50088f743 100644 --- a/ArduCopter/motors_tri.pde +++ b/ArduCopter/motors_tri.pde @@ -4,9 +4,7 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 40000; // 50 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_4 ); #endif } diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde index f41125135d..cbe0ba81d1 100644 --- a/ArduCopter/motors_y6.pde +++ b/ArduCopter/motors_y6.pde @@ -7,9 +7,8 @@ static void init_motors_out() { #if INSTANT_PWM == 0 - ICR5 = 5000; // 400 hz output CH 1, 2, 9 - ICR1 = 5000; // 400 hz output CH 3, 4, 10 - ICR3 = 5000; // 400 hz output CH 7, 8, 11 + APM_RC.SetFastOutputChannels( MSK_CH_1 | MSK_CH_2 | MSK_CH_3 | MSK_CH_4 + | MSK_CH_7 | MSK_CH_8 ); #endif }