Plane: tailsitter: don't relax attitude control in transision to VTOL, rely on check_attitude_relax to do the right thing
This commit is contained in:
parent
a91c0f4b12
commit
fb8fb34cfc
@ -444,8 +444,6 @@ bool Tailsitter::transition_vtol_complete(void) const
|
|||||||
gcs().send_text(MAV_SEVERITY_WARNING, "Transition VTOL done, timeout");
|
gcs().send_text(MAV_SEVERITY_WARNING, "Transition VTOL done, timeout");
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
// still waiting
|
|
||||||
quadplane.attitude_control->reset_rate_controller_I_terms();
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user