mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
SITL: Make thermal drift relative to 100m alt to avoid so much change with wind speed and direction."
This commit is contained in:
parent
8072f6b858
commit
15cef55e97
@ -832,8 +832,8 @@ float Aircraft::get_local_updraft(Vector3f currentPos)
|
||||
}
|
||||
|
||||
// Wind drift at this altitude
|
||||
float driftX = sitl->wind_speed * currentPos.z * cosf(sitl->wind_direction * DEG_TO_RAD);
|
||||
float driftY = sitl->wind_speed * currentPos.z * sinf(sitl->wind_direction * DEG_TO_RAD);
|
||||
float driftX = sitl->wind_speed * (currentPos.z+100) * cosf(sitl->wind_direction * DEG_TO_RAD);
|
||||
float driftY = sitl->wind_speed * (currentPos.z+100) * sinf(sitl->wind_direction * DEG_TO_RAD);
|
||||
|
||||
int iThermal;
|
||||
float w = 0.0f;
|
||||
|
Loading…
Reference in New Issue
Block a user