From c6c6a98b0b4d43da06b48daccd2019c37ee06d52 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Mon, 14 Nov 2011 12:25:06 -0800 Subject: [PATCH] Fixed typo in notes about timer speed --- ArduCopter/motors_hexa.pde | 2 +- ArduCopter/motors_octa.pde | 2 +- ArduCopter/motors_octa_quad.pde | 2 +- ArduCopter/motors_y6.pde | 3 +-- 4 files changed, 4 insertions(+), 5 deletions(-) diff --git a/ArduCopter/motors_hexa.pde b/ArduCopter/motors_hexa.pde index 1634f48f48..1cb74e8bfd 100644 --- a/ArduCopter/motors_hexa.pde +++ b/ArduCopter/motors_hexa.pde @@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11 + ICR3 = 5000; // 400 hz output CH 7, 8, 11 #endif } diff --git a/ArduCopter/motors_octa.pde b/ArduCopter/motors_octa.pde index dcabe7993d..a0afb2b099 100644 --- a/ArduCopter/motors_octa.pde +++ b/ArduCopter/motors_octa.pde @@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11 + ICR3 = 5000; // 400 hz output CH 7, 8, 11 #endif } diff --git a/ArduCopter/motors_octa_quad.pde b/ArduCopter/motors_octa_quad.pde index dfdd8c9bfd..529c3bcca4 100644 --- a/ArduCopter/motors_octa_quad.pde +++ b/ArduCopter/motors_octa_quad.pde @@ -7,7 +7,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 = 5000; // 50 hz output CH 7, 8, 11 + ICR3 = 5000; // 400 hz output CH 7, 8, 11 #endif } diff --git a/ArduCopter/motors_y6.pde b/ArduCopter/motors_y6.pde index c4d610189b..f41125135d 100644 --- a/ArduCopter/motors_y6.pde +++ b/ArduCopter/motors_y6.pde @@ -4,13 +4,12 @@ #define YAW_DIRECTION 1 - 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; // 50 hz output CH 7, 8, 11 + ICR3 = 5000; // 400 hz output CH 7, 8, 11 #endif }