mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: added TECS_LAND_PMIN for min pitch in flare
this is useful to narrow the range of available pitch after flare
This commit is contained in:
parent
ae49cebeb1
commit
3e72538f07
@ -248,6 +248,14 @@ const AP_Param::GroupInfo AP_TECS::var_info[] = {
|
||||
// @Bitmask: 0:GliderOnly
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("OPTIONS", 28, AP_TECS, _options, 0),
|
||||
|
||||
// @Param: LAND_PMIN
|
||||
// @DisplayName: Minimum 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 range small to avoid stalling or descending too fast. A minimum of -5 degrees is usually good. A value of zero means to use the normal pitch limits.
|
||||
// @Range: -5 5
|
||||
// @Increment: 1
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("LAND_PMIN", 29, AP_TECS, _land_pitch_mindeg, 0),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
@ -1067,6 +1075,16 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
_PITCHminf = MAX(_land_pitch_min, _PITCHminf);
|
||||
}
|
||||
|
||||
if (_landing.is_flaring()) {
|
||||
// ensure we don't violate the limits for flare pitch
|
||||
if (_land_pitch_mindeg != 0) {
|
||||
_PITCHminf = MAX(_land_pitch_mindeg, _PITCHminf);
|
||||
}
|
||||
if (_land_pitch_max != 0) {
|
||||
_PITCHmaxf = MIN(_land_pitch_max, _PITCHmaxf);
|
||||
}
|
||||
}
|
||||
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_TAKEOFF || flight_stage == AP_Vehicle::FixedWing::FLIGHT_ABORT_LAND) {
|
||||
if (!_flags.reached_speed_takeoff && _TAS_state >= _TAS_dem_adj) {
|
||||
// we have reached our target speed in takeoff, allow for
|
||||
|
@ -165,6 +165,7 @@ private:
|
||||
AP_Int8 _pitch_max;
|
||||
AP_Int8 _pitch_min;
|
||||
AP_Int8 _land_pitch_max;
|
||||
AP_Int8 _land_pitch_mindeg;
|
||||
AP_Float _maxSinkRate_approach;
|
||||
AP_Int32 _options;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user