Copter: brake - fix call to relax_alt_hold_controller

This commit is contained in:
Randy Mackay 2016-07-12 21:46:08 +09:00
parent 5b277f4fb5
commit aa4661835e
1 changed files with 1 additions and 1 deletions

View File

@ -49,7 +49,7 @@ void Copter::brake_run()
// multicopters do not stabilize roll/pitch/yaw when disarmed
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
#endif
pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(0)-motors.get_throttle_hover());
pos_control.relax_alt_hold_controllers(0.0f);
return;
}