diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 19501c68e6d5963cf502734466567a6dcd6170a9..d30332de3cf385af6523437852d0b465293d9d9c 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -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);