mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Soaring: Reduce drift feed-forward by ratio of climb rate to thermal core strength. This is consistent with assumption that each packet of air, rising at core strength, is convected with the ambient wind speed.
This commit is contained in:
parent
15cef55e97
commit
2b40182b34
@ -295,7 +295,7 @@ void SoaringController::update_thermalling()
|
||||
return;
|
||||
}
|
||||
|
||||
Vector3f wind_drift = _ahrs.wind_estimate()*deltaT;
|
||||
Vector3f wind_drift = _ahrs.wind_estimate()*deltaT*_vario.smoothed_climb_rate/_ekf.X[0];
|
||||
|
||||
// update the filter
|
||||
_ekf.update(_vario.reading, current_position.x, current_position.y, wind_drift.x, wind_drift.y);
|
||||
|
Loading…
Reference in New Issue
Block a user