From 85b87b752ab90157eb7cbd826d568f818ff1d4d2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 Nov 2012 07:10:26 +1100 Subject: [PATCH] APM: change WIND direction to match convention Thanks to Leo Hogg for pointing this out --- ArduPlane/GCS_Mavlink.pde | 3 ++- libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml | 2 +- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index fb8f54138f..5e57e2ca0c 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -455,7 +455,8 @@ static void NOINLINE send_wind(mavlink_channel_t chan) Vector3f wind = ahrs.wind_estimate(); mavlink_msg_wind_send( chan, - degrees(atan2(wind.y, wind.x)), + degrees(atan2(-wind.y, -wind.x)), // use negative, to give + // direction wind is coming from sqrt(sq(wind.x)+sq(wind.y)), wind.z); } diff --git a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml index 8ac0b1d523..533b0c51bb 100644 --- a/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml +++ b/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml @@ -306,7 +306,7 @@ Wind estimation - wind direction (degrees) + wind direction that wind is coming from (degrees) wind speed in ground plane (m/s) vertical wind speed (m/s)