mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_TECS: added TECS_LAND_PMAX
this limits maximum pitch during the flare, which both reduces integrator windup and prevents too high pitch which can cause a stall
This commit is contained in:
parent
8b78e6f2c0
commit
5a4ed85588
@ -176,6 +176,14 @@ const AP_Param::GroupInfo AP_TECS::var_info[] PROGMEM = {
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LAND_DAMP", 19, AP_TECS, _landDamp, 0.5f),
|
||||
|
||||
// @Param: LAND_PMAX
|
||||
// @DisplayName: Maximum pitch during final stage of landing
|
||||
// @Description: This limits the pitch used during the final stage of automatic landing. During the final landing stage most planes need to keep their pitch small to avoid stalling. A maximum of 10 degrees is usually good. A value of zero means to use the normal pitch limits.
|
||||
// @Range: 0 40
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LAND_PMAX", 20, AP_TECS, _land_pitch_max, 10),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
@ -802,6 +810,11 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
// in flare use min pitch from LAND_PITCH_CD
|
||||
_PITCHminf = max(_PITCHminf, aparm.land_pitch_cd * 0.01f);
|
||||
|
||||
// and use max pitch from TECS_LAND_PMAX
|
||||
if (_land_pitch_max > 0) {
|
||||
_PITCHmaxf = min(_PITCHmaxf, _land_pitch_max);
|
||||
}
|
||||
|
||||
// and allow zero throttle
|
||||
_THRminf = 0;
|
||||
} else if (flight_stage == FLIGHT_LAND_APPROACH && (-_climb_rate) > _land_sink) {
|
||||
@ -824,6 +837,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
_PITCHminf = max(_PITCHminf, pitch_limit_cd*0.01f);
|
||||
}
|
||||
}
|
||||
|
||||
// convert to radians
|
||||
_PITCHmaxf = radians(_PITCHmaxf);
|
||||
_PITCHminf = radians(_PITCHminf);
|
||||
|
@ -132,6 +132,7 @@ private:
|
||||
AP_Float _land_sink;
|
||||
AP_Int8 _pitch_max;
|
||||
AP_Int8 _pitch_min;
|
||||
AP_Int8 _land_pitch_max;
|
||||
|
||||
// throttle demand in the range from 0.0 to 1.0
|
||||
float _throttle_dem;
|
||||
|
Loading…
Reference in New Issue
Block a user