mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_TECS: make TECS aware of LAND_PITCH_CD
this makes the flare a bit smoother
This commit is contained in:
parent
fb4ef0b5c6
commit
500e20b08d
@ -721,6 +721,10 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
|||||||
} else {
|
} else {
|
||||||
_PITCHminf = max(_pitch_min, aparm.pitch_limit_min_cd * 0.01f);
|
_PITCHminf = max(_pitch_min, aparm.pitch_limit_min_cd * 0.01f);
|
||||||
}
|
}
|
||||||
|
if (flight_stage == FLIGHT_LAND_FINAL) {
|
||||||
|
// in flare use min pitch from LAND_PITCH_CD
|
||||||
|
_PITCHminf = max(_PITCHminf, aparm.land_pitch_cd * 0.01f);
|
||||||
|
}
|
||||||
// convert to radians
|
// convert to radians
|
||||||
_PITCHmaxf = radians(_PITCHmaxf);
|
_PITCHmaxf = radians(_PITCHmaxf);
|
||||||
_PITCHminf = radians(_PITCHminf);
|
_PITCHminf = radians(_PITCHminf);
|
||||||
|
Loading…
Reference in New Issue
Block a user