Unverified Commit 869f7301 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6747 from DonLakeFlyer/NegativeWind

WIND_COV: Fix negative wind direction
parents 7ea4afbf 6701b08d
......@@ -1259,6 +1259,10 @@ void Vehicle::_handleWindCov(mavlink_message_t& message)
float direction = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
float speed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
if (direction < 0) {
direction += 360;
}
_windFactGroup.direction()->setRawValue(direction);
_windFactGroup.speed()->setRawValue(speed);
_windFactGroup.verticalSpeed()->setRawValue(0);
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment