mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Plane: don't apply fw pitch limit in VTOL control for tailsitters
tailsitters may have narrow fixed wing limits but need high limits for landing in high wind found this on a HWing which was essentially impossible to auto land
This commit is contained in:
parent
f0bc041b86
commit
570ecdc2e0
@ -2359,25 +2359,27 @@ void QuadPlane::vtol_position_controller(void)
|
|||||||
plane.nav_roll_cd = pos_control->get_roll_cd();
|
plane.nav_roll_cd = pos_control->get_roll_cd();
|
||||||
plane.nav_pitch_cd = pos_control->get_pitch_cd();
|
plane.nav_pitch_cd = pos_control->get_pitch_cd();
|
||||||
|
|
||||||
/*
|
if (!tailsitter.enabled()) {
|
||||||
limit the pitch down with an expanding envelope. This
|
/*
|
||||||
prevents the velocity controller demanding nose down during
|
limit the pitch down with an expanding envelope. This
|
||||||
the initial slowdown if the target velocity curve is higher
|
prevents the velocity controller demanding nose down during
|
||||||
than the actual velocity curve (for a high drag
|
the initial slowdown if the target velocity curve is higher
|
||||||
aircraft). Nose down will cause a lot of downforce on the
|
than the actual velocity curve (for a high drag
|
||||||
wings which will draw a lot of current and also cause the
|
aircraft). Nose down will cause a lot of downforce on the
|
||||||
aircraft to lose altitude rapidly.pitch limit varies also with speed
|
wings which will draw a lot of current and also cause the
|
||||||
to prevent inability to progress to position if moving from a loiter
|
aircraft to lose altitude rapidly.pitch limit varies also with speed
|
||||||
to landing
|
to prevent inability to progress to position if moving from a loiter
|
||||||
*/
|
to landing
|
||||||
float minlimit_cd = linear_interpolate(-300, MAX(-aparm.angle_max,plane.aparm.pitch_limit_min_cd),
|
*/
|
||||||
poscontrol.time_since_state_start_ms(),
|
float minlimit_cd = linear_interpolate(-300, MAX(-aparm.angle_max,plane.aparm.pitch_limit_min_cd),
|
||||||
0, 5000);
|
poscontrol.time_since_state_start_ms(),
|
||||||
if (plane.nav_pitch_cd < minlimit_cd) {
|
0, 5000);
|
||||||
plane.nav_pitch_cd = minlimit_cd;
|
if (plane.nav_pitch_cd < minlimit_cd) {
|
||||||
// tell the pos controller we have limited the pitch to
|
plane.nav_pitch_cd = minlimit_cd;
|
||||||
// stop integrator buildup
|
// tell the pos controller we have limited the pitch to
|
||||||
pos_control->set_externally_limited_xy();
|
// stop integrator buildup
|
||||||
|
pos_control->set_externally_limited_xy();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// call attitude controller
|
// call attitude controller
|
||||||
|
Loading…
Reference in New Issue
Block a user