SITL: fixed sense of wind direction

wind direction is where wind is coming from, not going to
This commit is contained in:
Andrew Tridgell 2016-09-16 10:59:27 +10:00
parent 66073413a8
commit 52caf8419e
2 changed files with 2 additions and 2 deletions

View File

@ -429,7 +429,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
position += velocity_ef * delta_time;
// velocity relative to air mass, in earth frame
velocity_air_ef = velocity_ef - wind_ef;
velocity_air_ef = velocity_ef + wind_ef;
// velocity relative to airmass in body frame
velocity_air_bf = dcm.transposed() * velocity_air_ef;

View File

@ -343,7 +343,7 @@ failed:
// new velocity and position vectors
velocity_ef += accel_earth * delta_time;
position += velocity_ef * delta_time;
velocity_air_ef = velocity_ef - wind_ef;
velocity_air_ef = velocity_ef + wind_ef;
velocity_air_bf = dcm.transposed() * velocity_air_ef;
update_position();