From eca6ca2100c4ce09a82190ae94ec3b4f6ccba9ac Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Fri, 25 Jan 2013 11:34:48 +0900
Subject: [PATCH] Copter: set update rate to 50hz during esc calibration

Also modified some comments in the code re the esc calibration
---
 ArduCopter/radio.pde | 4 ++--
 ArduCopter/setup.pde | 2 ++
 2 files changed, 4 insertions(+), 2 deletions(-)

diff --git a/ArduCopter/radio.pde b/ArduCopter/radio.pde
index e057ff99b..3d8423a63 100644
--- a/ArduCopter/radio.pde
+++ b/ArduCopter/radio.pde
@@ -86,7 +86,7 @@ static void init_rc_out()
         if(g.esc_calibrate == 0) {
             // we will enter esc_calibrate mode on next reboot
             g.esc_calibrate.set_and_save(1);
-            // send miinimum throttle out to ESC
+            // send minimum throttle out to ESC
             motors.output_min();
             // display message on console
             cliSerial->printf_P(PSTR("Entering ESC Calibration: please restart APM.\n"));
@@ -99,7 +99,7 @@ static void init_rc_out()
             cliSerial->printf_P(PSTR("ESC Calibration active: passing throttle through to ESCs.\n"));
             // clear esc flag
             g.esc_calibrate.set_and_save(0);
-            // block until we restart
+            // pass through user throttle to escs
             init_esc();
         }
     }else{
diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde
index e11253f4c..e1c414fe1 100644
--- a/ArduCopter/setup.pde
+++ b/ArduCopter/setup.pde
@@ -1095,6 +1095,8 @@ static void print_enabled(bool b)
 static void
 init_esc()
 {
+    // reduce update rate to motors to 50Hz
+    motors.set_update_rate(50);
     motors.enable();
     motors.armed(true);
     while(1) {
-- 
GitLab