|
|
|
@ -443,6 +443,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -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)
@@ -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; |
|
|
|
|