Plane: avoid calling quadplane methods if quadplane not available

one block was guarded, the second not
This commit is contained in:
Peter Barker 2024-09-24 18:43:31 +10:00 committed by Andrew Tridgell
parent 68003a5eb4
commit 96f7d8a969
1 changed files with 14 additions and 9 deletions

View File

@ -514,16 +514,21 @@ void Plane::update_fly_forward(void)
// wing aircraft. This helps the EKF produce better state
// estimates as it can make stronger assumptions
#if HAL_QUADPLANE_ENABLED
if (quadplane.available() &&
quadplane.tailsitter.is_in_fw_flight()) {
ahrs.set_fly_forward(true);
return;
}
if (quadplane.available()) {
if (quadplane.tailsitter.is_in_fw_flight()) {
ahrs.set_fly_forward(true);
return;
}
if (quadplane.in_vtol_mode() ||
quadplane.in_assisted_flight()) {
ahrs.set_fly_forward(false);
return;
if (quadplane.in_vtol_mode()) {
ahrs.set_fly_forward(false);
return;
}
if (quadplane.in_assisted_flight()) {
ahrs.set_fly_forward(false);
return;
}
}
#endif