Commit 34dc935a authored by Daniel Agar's avatar Daniel Agar

mavlink WIND_COV -> windFactGroup

parent 32d572be
......@@ -443,6 +443,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
_handleAutopilotVersion(message);
break;
case MAVLINK_MSG_ID_WIND_COV:
_handleWindCov(message);
break;
// Following are ArduPilot dialect messages
......@@ -542,6 +545,19 @@ void Vehicle::_handleVibration(mavlink_message_t& message)
_vibrationFactGroup.clipCount3()->setRawValue(vibration.clipping_2);
}
void Vehicle::_handleWindCov(mavlink_message_t& message)
{
mavlink_wind_cov_t wind;
mavlink_msg_wind_cov_decode(&message, &wind);
float direction = qRadiansToDegrees(qAtan2(wind.wind_y, wind.wind_x));
float speed = qSqrt(qPow(wind.wind_x, 2) + qPow(wind.wind_y, 2));
_windFactGroup.direction()->setRawValue(direction);
_windFactGroup.speed()->setRawValue(speed);
_windFactGroup.verticalSpeed()->setRawValue(0);
}
void Vehicle::_handleWind(mavlink_message_t& message)
{
mavlink_wind_t wind;
......
......@@ -639,6 +639,7 @@ private:
void _handleRCChannelsRaw(mavlink_message_t& message);
void _handleBatteryStatus(mavlink_message_t& message);
void _handleSysStatus(mavlink_message_t& message);
void _handleWindCov(mavlink_message_t& message);
void _handleWind(mavlink_message_t& message);
void _handleVibration(mavlink_message_t& message);
void _handleExtendedSysState(mavlink_message_t& message);
......
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