mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Plane: fixed tailsitter ANGLE_WAIT transition
we need vtol control during transition from hover to fwd flight
This commit is contained in:
parent
af893ddde7
commit
214434a2d7
@ -31,7 +31,17 @@ bool QuadPlane::is_tailsitter(void)
|
|||||||
*/
|
*/
|
||||||
bool QuadPlane::tailsitter_active(void)
|
bool QuadPlane::tailsitter_active(void)
|
||||||
{
|
{
|
||||||
return is_tailsitter() && in_vtol_mode();
|
if (!is_tailsitter()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (in_vtol_mode()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
// check if we are in ANGLE_WAIT transition
|
||||||
|
if (transition_state == TRANSITION_ANGLE_WAIT) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user