diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index f390c7be57..e9cc426629 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1119,7 +1119,6 @@ void update_throttle_mode(void) // clear the new data flag invalid_throttle = false; - Serial.printf("nt %d\n",nav_throttle); } // apply throttle control at 200 hz diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 516d9b2201..97cebe366c 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -104,8 +104,6 @@ get_nav_throttle(long z_error, int target_speed) float delta_throttle = (float)(timer - throttle_timer)/1000.0; throttle_timer = timer; - Serial.printf("tt %ld, dt %1.4f ", throttle_timer, delta_throttle); - return g.pi_throttle.get_pi(rate_error, delta_throttle); }