APM: change WIND direction to match convention

Thanks to Leo Hogg for pointing this out
This commit is contained in:
Andrew Tridgell 2012-11-19 07:10:26 +11:00
parent ae76145374
commit 85b87b752a
2 changed files with 3 additions and 2 deletions

View File

@ -455,7 +455,8 @@ static void NOINLINE send_wind(mavlink_channel_t chan)
Vector3f wind = ahrs.wind_estimate(); Vector3f wind = ahrs.wind_estimate();
mavlink_msg_wind_send( mavlink_msg_wind_send(
chan, 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)), sqrt(sq(wind.x)+sq(wind.y)),
wind.z); wind.z);
} }

View File

@ -306,7 +306,7 @@
<message name="WIND" id="168"> <message name="WIND" id="168">
<description>Wind estimation</description> <description>Wind estimation</description>
<field type="float" name="direction">wind direction (degrees)</field> <field type="float" name="direction">wind direction that wind is coming from (degrees)</field>
<field type="float" name="speed">wind speed in ground plane (m/s)</field> <field type="float" name="speed">wind speed in ground plane (m/s)</field>
<field type="float" name="speed_z">vertical wind speed (m/s)</field> <field type="float" name="speed_z">vertical wind speed (m/s)</field>
</message> </message>