AP_Windvane: add wind direction note

This commit is contained in:
IamPete1 2018-10-05 23:26:18 +01:00 committed by Randy Mackay
parent e31f98157b
commit 67d698fda3
1 changed files with 3 additions and 0 deletions

View File

@ -211,6 +211,9 @@ float AP_WindVane::read_SITL_direction_ef()
const float wind_speed = AP::sitl()->wind_speed_active;
const float wind_dir_rad = radians(AP::sitl()->wind_direction_active);
// Note than the SITL wind direction is defined as the direction the wind is travelling to
// This is accounted for in these calculations
// convert true wind speed and direction into a 2D vector
Vector2f wind_vector_ef(sinf(wind_dir_rad) * wind_speed, cosf(wind_dir_rad) * wind_speed);