mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed throttle slew rate in manual for quadplanes
This commit is contained in:
parent
8432c5fb4a
commit
0445b51143
|
@ -958,6 +958,7 @@ void QuadPlane::update_transition(void)
|
|||
motors->output();
|
||||
}
|
||||
transition_state = TRANSITION_DONE;
|
||||
assisted_flight = false;
|
||||
return;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue