From 6e815dd45c5443186636cf16363b12c05d3fceb6 Mon Sep 17 00:00:00 2001 From: Robert Lefebvre Date: Sun, 20 Sep 2015 18:39:20 -0400 Subject: [PATCH] Copter: Helicopter, fix so servos move after arming in Acro and Stabilize. --- ArduCopter/heli_control_acro.cpp | 1 - ArduCopter/heli_control_stabilize.cpp | 1 - 2 files changed, 2 deletions(-) diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 9cc9c0a697..9f3c82e942 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -35,7 +35,6 @@ void Copter::heli_acro_run() } if(motors.armed() && heli_flags.init_targets_on_arming) { - attitude_control.relax_bf_rate_controller(); attitude_control.set_yaw_target_to_current_heading(); if (motors.rotor_speed_above_critical()) { heli_flags.init_targets_on_arming=false; diff --git a/ArduCopter/heli_control_stabilize.cpp b/ArduCopter/heli_control_stabilize.cpp index b9ef80977f..bafcce6ddb 100644 --- a/ArduCopter/heli_control_stabilize.cpp +++ b/ArduCopter/heli_control_stabilize.cpp @@ -36,7 +36,6 @@ void Copter::heli_stabilize_run() } if(motors.armed() && heli_flags.init_targets_on_arming) { - attitude_control.relax_bf_rate_controller(); attitude_control.set_yaw_target_to_current_heading(); if (motors.rotor_speed_above_critical()) { heli_flags.init_targets_on_arming=false;