diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index a05d86c8255aec861165578fadc8e2ebeb7091d5..a5f2d06c4bead036732157749f0c35a857940a49 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -1139,7 +1139,12 @@ void Vehicle::_handleWind(mavlink_message_t& message) mavlink_wind_t wind; mavlink_msg_wind_decode(&message, &wind); - _windFactGroup.direction()->setRawValue(wind.direction); + // We don't want negative wind angles + float direction = wind.direction; + if (direction < 0) { + direction += 360; + } + _windFactGroup.direction()->setRawValue(direction); _windFactGroup.speed()->setRawValue(wind.speed); _windFactGroup.verticalSpeed()->setRawValue(wind.speed_z); }