mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
Plane: fixed EKF fly-forward flag for tailsitters
for tailsitters that are always using the VTOL controllers (forced QAssist) we need a different way to determine the fly-forward flag
This commit is contained in:
parent
8e62385d8d
commit
497a7c9819
@ -430,7 +430,10 @@ void Plane::update_control_mode(void)
|
||||
// ensure we are fly-forward when we are flying as a pure fixed
|
||||
// wing aircraft. This helps the EKF produce better state
|
||||
// estimates as it can make stronger assumptions
|
||||
if (quadplane.in_vtol_mode() ||
|
||||
if (quadplane.available() &&
|
||||
quadplane.tailsitter.is_in_fw_flight()) {
|
||||
ahrs.set_fly_forward(true);
|
||||
} else if (quadplane.in_vtol_mode() ||
|
||||
quadplane.in_assisted_flight()) {
|
||||
ahrs.set_fly_forward(false);
|
||||
} else if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
|
Loading…
Reference in New Issue
Block a user