Plane: fixed NAV_CONTROLLER_OUTPUT in QRTL

This commit is contained in:
Andrew Tridgell 2021-05-20 12:58:58 +10:00
parent 245ded2f2d
commit 77ee922473
1 changed files with 7 additions and 1 deletions

View File

@ -3690,7 +3690,13 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
// return true if the wp_nav controller is being updated
bool QuadPlane::using_wp_nav(void) const
{
return plane.control_mode == &plane.mode_qloiter || plane.control_mode == &plane.mode_qland || plane.control_mode == &plane.mode_qrtl;
if (plane.control_mode == &plane.mode_qloiter || plane.control_mode == &plane.mode_qland) {
return true;
}
if (plane.control_mode == &plane.mode_qrtl && poscontrol.get_state() >= QPOS_POSITION2) {
return true;
}
return false;
}
/*