mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Plane: initialise target height correctly on quadplane transition
this fixes a bug where a plane in QSTABILIZE would drop suddenly if switched to FBWA when the target altitude had not been initialised
This commit is contained in:
parent
1a781f44cc
commit
af97a3974b
@ -1112,6 +1112,12 @@ void QuadPlane::update_transition(void)
|
||||
}
|
||||
transition_state = TRANSITION_AIRSPEED_WAIT;
|
||||
transition_start_ms = millis();
|
||||
if (!assisted_flight) {
|
||||
// set alt target to current height on transition. This
|
||||
// starts the Z controller off with the right values
|
||||
pos_control->set_alt_target(inertial_nav.get_altitude());
|
||||
pos_control->set_desired_velocity_z(inertial_nav.get_velocity_z());
|
||||
}
|
||||
assisted_flight = true;
|
||||
} else {
|
||||
assisted_flight = false;
|
||||
|
Loading…
Reference in New Issue
Block a user