Browse Source

APM: change WIND direction to match convention

Thanks to Leo Hogg for pointing this out
mission-4.1.18
Andrew Tridgell 12 years ago
parent
commit
8d1905a40b
  1. 3
      ArduPlane/GCS_Mavlink.pde
  2. 2
      libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml

3
ArduPlane/GCS_Mavlink.pde

@ -455,7 +455,8 @@ static void NOINLINE send_wind(mavlink_channel_t chan) @@ -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);
}

2
libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml

@ -306,7 +306,7 @@ @@ -306,7 +306,7 @@
<message name="WIND" id="168">
<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_z">vertical wind speed (m/s)</field>
</message>

Loading…
Cancel
Save