Plane: Quadplane: move disable of assistance in flare to should_assist function

This commit is contained in:
Iampete1 2024-02-24 23:39:11 +00:00 committed by Andrew Tridgell
parent 8196c899e8
commit 20015c60a7
2 changed files with 6 additions and 9 deletions

View File

@ -121,20 +121,11 @@ void RC_Channel_Plane::do_aux_function_flare(AuxSwitchPos ch_flag)
switch(ch_flag) {
case AuxSwitchPos::HIGH:
plane.flare_mode = Plane::FlareMode::ENABLED_PITCH_TARGET;
#if HAL_QUADPLANE_ENABLED
plane.quadplane.assist.set_state(QuadPlane::VTOL_Assist::STATE::ASSIST_DISABLED);
#endif
break;
case AuxSwitchPos::MIDDLE:
plane.flare_mode = Plane::FlareMode::ENABLED_NO_PITCH_TARGET;
#if HAL_QUADPLANE_ENABLED
plane.quadplane.assist.set_state(QuadPlane::VTOL_Assist::STATE::ASSIST_DISABLED);
#endif
break;
case AuxSwitchPos::LOW:
#if HAL_QUADPLANE_ENABLED
plane.quadplane.assist.set_state(QuadPlane::VTOL_Assist::STATE::ASSIST_ENABLED);
#endif
plane.flare_mode = Plane::FlareMode::FLARE_DISABLED;
break;
}

View File

@ -1481,6 +1481,12 @@ bool QuadPlane::VTOL_Assist::should_assist(float aspeed, bool have_airspeed)
return false;
}
if (plane.flare_mode != Plane::FlareMode::FLARE_DISABLED) {
// Never active in fixed wing flare
reset();
return false;
}
if (state == STATE::FORCE_ENABLED) {
// force enabled, no need to check thresholds
reset();