mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed quad yaw assistance during transition timer
This commit is contained in:
parent
9ae4c3ec99
commit
aab98ff757
|
@ -641,6 +641,7 @@ void QuadPlane::update_transition(void)
|
|||
if (throttle_scaled < 0) {
|
||||
throttle_scaled = 0;
|
||||
}
|
||||
assisted_flight = true;
|
||||
hold_stabilize(throttle_scaled);
|
||||
attitude_control->rate_controller_run();
|
||||
motors->output();
|
||||
|
|
Loading…
Reference in New Issue