Plane: fixed stick mixing with land reposition in quadplanes

prevent stick mixing overriding landing control
This commit is contained in:
Andrew Tridgell 2021-06-08 16:00:54 +10:00
parent c544f3dd01
commit 06cd077c36
3 changed files with 26 additions and 0 deletions

View File

@ -64,6 +64,15 @@ bool Plane::stick_mixing_enabled(void)
#else
const bool stickmixing = true;
#endif
if (control_mode == &mode_qrtl &&
quadplane.poscontrol.get_state() >= QuadPlane::QPOS_POSITION1) {
// user may be repositioning
return false;
}
if (quadplane.in_vtol_land_poscontrol()) {
// user may be repositioning
return false;
}
if (control_mode->does_auto_throttle() && plane.control_mode->does_auto_navigation()) {
// we're in an auto mode. Check the stick mixing flag
if (g.stick_mixing != STICK_MIXING_DISABLED &&

View File

@ -3938,6 +3938,18 @@ bool QuadPlane::in_vtol_land_sequence(void) const
return in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final();
}
/*
see if we are in the VTOL position control phase of a landing
*/
bool QuadPlane::in_vtol_land_poscontrol(void) const
{
if (in_vtol_auto() && is_vtol_land(plane.mission.get_current_nav_cmd().id) &&
poscontrol.get_state() >= QPOS_POSITION1) {
return true;
}
return false;
}
// return true if we should show VTOL view
bool QuadPlane::show_vtol_view() const
{

View File

@ -687,6 +687,11 @@ private:
*/
bool in_vtol_land_sequence(void) const;
/*
see if we are in the VTOL position control phase of a landing
*/
bool in_vtol_land_poscontrol(void) const;
// Q assist state, can be enabled, disabled or force. Default to enabled
Q_ASSIST_STATE_ENUM q_assist_state = Q_ASSIST_STATE_ENUM::Q_ASSIST_ENABLED;