mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: tell TECS to use synthetic airspeed during transition
This commit is contained in:
parent
2fab15dcd5
commit
cb61840ad2
@ -993,6 +993,12 @@ void QuadPlane::update_transition(void)
|
||||
} else if (transition_state < TRANSITION_DONE) {
|
||||
plane.TECS_controller.set_pitch_max_limit((transition_pitch_max+1)*2);
|
||||
}
|
||||
if (transition_state < TRANSITION_DONE) {
|
||||
// during transition we ask TECS to use a synthetic
|
||||
// airspeed. Otherwise the pitch limits will throw off the
|
||||
// throttle calculation which is driven by pitch
|
||||
plane.TECS_controller.use_synthetic_airspeed();
|
||||
}
|
||||
|
||||
switch (transition_state) {
|
||||
case TRANSITION_AIRSPEED_WAIT: {
|
||||
|
Loading…
Reference in New Issue
Block a user