mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Plane: cope with Q pitch limit larger than fixed wing limit
prevents tailsitter VTOL transition timeout due to not achieving angle
This commit is contained in:
parent
71fa52d5c6
commit
74da3c74ac
@ -278,7 +278,10 @@ bool QuadPlane::tailsitter_transition_vtol_complete(void) const
|
||||
return true;
|
||||
}
|
||||
}
|
||||
const float trans_angle = get_tailsitter_transition_angle_vtol();
|
||||
// limit completion angle to just below fixed wing pitch limit
|
||||
const float margin_deg = 3;
|
||||
const float trans_angle = MIN(get_tailsitter_transition_angle_vtol(),
|
||||
plane.aparm.pitch_limit_max_cd*0.01-margin_deg);
|
||||
if (labs(plane.ahrs.pitch_sensor) > trans_angle*100) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Transition VTOL done");
|
||||
return true;
|
||||
|
Loading…
Reference in New Issue
Block a user