mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
Copter: Helicopter, fix so servos move after arming in Acro and Stabilize.
This commit is contained in:
parent
2632a2e348
commit
7ad623dc70
@ -37,7 +37,6 @@ void Copter::heli_acro_run()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||||
attitude_control.relax_bf_rate_controller();
|
|
||||||
attitude_control.set_yaw_target_to_current_heading();
|
attitude_control.set_yaw_target_to_current_heading();
|
||||||
if (motors.rotor_speed_above_critical()) {
|
if (motors.rotor_speed_above_critical()) {
|
||||||
heli_flags.init_targets_on_arming=false;
|
heli_flags.init_targets_on_arming=false;
|
||||||
|
@ -36,7 +36,6 @@ void Copter::heli_stabilize_run()
|
|||||||
}
|
}
|
||||||
|
|
||||||
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
if(motors.armed() && heli_flags.init_targets_on_arming) {
|
||||||
attitude_control.relax_bf_rate_controller();
|
|
||||||
attitude_control.set_yaw_target_to_current_heading();
|
attitude_control.set_yaw_target_to_current_heading();
|
||||||
if (motors.rotor_speed_above_critical()) {
|
if (motors.rotor_speed_above_critical()) {
|
||||||
heli_flags.init_targets_on_arming=false;
|
heli_flags.init_targets_on_arming=false;
|
||||||
|
Loading…
Reference in New Issue
Block a user