Browse Source

Copter: Helicopter, fix so servos move after arming in Acro and Stabilize.

master
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
7ad623dc70
  1. 1
      ArduCopter/heli_control_acro.cpp
  2. 1
      ArduCopter/heli_control_stabilize.cpp

1
ArduCopter/heli_control_acro.cpp

@ -37,7 +37,6 @@ void Copter::heli_acro_run() @@ -37,7 +37,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;

1
ArduCopter/heli_control_stabilize.cpp

@ -36,7 +36,6 @@ void Copter::heli_stabilize_run() @@ -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;

Loading…
Cancel
Save