mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: bring in flare sink rate more slowly
this should reduce pitch overshoot in the flare
This commit is contained in:
parent
5af4cefff3
commit
6c1eed0a20
@ -375,7 +375,8 @@ void AP_TECS::_update_height_demand(void)
|
|||||||
if (_flare_counter == 0) {
|
if (_flare_counter == 0) {
|
||||||
_hgt_rate_dem = _climb_rate;
|
_hgt_rate_dem = _climb_rate;
|
||||||
}
|
}
|
||||||
if (_flare_counter < 5) {
|
// bring it in over 1s to prevent overshoot
|
||||||
|
if (_flare_counter < 10) {
|
||||||
_hgt_rate_dem = _hgt_rate_dem * 0.8f - 0.2f * _land_sink;
|
_hgt_rate_dem = _hgt_rate_dem * 0.8f - 0.2f * _land_sink;
|
||||||
_flare_counter++;
|
_flare_counter++;
|
||||||
} else {
|
} else {
|
||||||
|
Loading…
Reference in New Issue
Block a user