mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
SITL: fixed sense of wind direction
wind direction is where wind is coming from, not going to
This commit is contained in:
parent
66073413a8
commit
52caf8419e
@ -429,7 +429,7 @@ void Aircraft::update_dynamics(const Vector3f &rot_accel)
|
|||||||
position += velocity_ef * delta_time;
|
position += velocity_ef * delta_time;
|
||||||
|
|
||||||
// velocity relative to air mass, in earth frame
|
// 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 relative to airmass in body frame
|
||||||
velocity_air_bf = dcm.transposed() * velocity_air_ef;
|
velocity_air_bf = dcm.transposed() * velocity_air_ef;
|
||||||
|
@ -343,7 +343,7 @@ failed:
|
|||||||
// new velocity and position vectors
|
// new velocity and position vectors
|
||||||
velocity_ef += accel_earth * delta_time;
|
velocity_ef += accel_earth * delta_time;
|
||||||
position += velocity_ef * 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;
|
velocity_air_bf = dcm.transposed() * velocity_air_ef;
|
||||||
|
|
||||||
update_position();
|
update_position();
|
||||||
|
Loading…
Reference in New Issue
Block a user