|
|
|
@ -674,9 +674,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -674,9 +674,6 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
|
|
|
|
|
case MAVLINK_MSG_ID_SCALED_PRESSURE3: |
|
|
|
|
_handleScaledPressure3(message); |
|
|
|
|
break;
|
|
|
|
|
case MAVLINK_MSG_ID_CAMERA_FEEDBACK: |
|
|
|
|
_handleCameraFeedback(message); |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED: |
|
|
|
|
_handleCameraImageCaptured(message); |
|
|
|
|
break; |
|
|
|
@ -691,11 +688,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -691,11 +688,16 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
|
|
|
|
|
emit mavlinkSerialControl(ser.device, ser.flags, ser.timeout, ser.baudrate, QByteArray(reinterpret_cast<const char*>(ser.data), ser.count)); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
// Following are ArduPilot dialect messages
|
|
|
|
|
|
|
|
|
|
// Following are ArduPilot dialect messages
|
|
|
|
|
#if !defined(NO_ARDUPILOT_DIALECT) |
|
|
|
|
case MAVLINK_MSG_ID_CAMERA_FEEDBACK: |
|
|
|
|
_handleCameraFeedback(message); |
|
|
|
|
break; |
|
|
|
|
case MAVLINK_MSG_ID_WIND: |
|
|
|
|
_handleWind(message); |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// This must be emitted after the vehicle processes the message. This way the vehicle state is up to date when anyone else
|
|
|
|
@ -706,6 +708,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
@@ -706,6 +708,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if !defined(NO_ARDUPILOT_DIALECT) |
|
|
|
|
void Vehicle::_handleCameraFeedback(const mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
|
mavlink_camera_feedback_t feedback; |
|
|
|
@ -716,6 +719,7 @@ void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
@@ -716,6 +719,7 @@ void Vehicle::_handleCameraFeedback(const mavlink_message_t& message)
|
|
|
|
|
qCDebug(VehicleLog) << "_handleCameraFeedback coord:index" << imageCoordinate << feedback.img_idx; |
|
|
|
|
_cameraTriggerPoints.append(new QGCQGeoCoordinate(imageCoordinate, this)); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
void Vehicle::_handleCameraImageCaptured(const mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
@ -1014,6 +1018,7 @@ void Vehicle::_handleWindCov(mavlink_message_t& message)
@@ -1014,6 +1018,7 @@ void Vehicle::_handleWindCov(mavlink_message_t& message)
|
|
|
|
|
_windFactGroup.verticalSpeed()->setRawValue(0); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
#if !defined(NO_ARDUPILOT_DIALECT) |
|
|
|
|
void Vehicle::_handleWind(mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
|
mavlink_wind_t wind; |
|
|
|
@ -1023,6 +1028,7 @@ void Vehicle::_handleWind(mavlink_message_t& message)
@@ -1023,6 +1028,7 @@ void Vehicle::_handleWind(mavlink_message_t& message)
|
|
|
|
|
_windFactGroup.speed()->setRawValue(wind.speed); |
|
|
|
|
_windFactGroup.verticalSpeed()->setRawValue(wind.speed_z); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
void Vehicle::_handleSysStatus(mavlink_message_t& message) |
|
|
|
|
{ |
|
|
|
|