From f20f05e87c797745f53e51c635b520529cdfae85 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 30 May 2024 19:15:51 +1200 Subject: [PATCH] Camera: allow camera managed by an autopilot By querying autopilot for the CAMERA_INFORMATION message, we allow an autopilot to be a proxy for a MAVLink or non-MAVLink camera. The idea is similar to a gimbal manager implemented by an autopilot. --- src/Camera/QGCCameraManager.cc | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index b2b7bef..98b455d 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -69,7 +69,8 @@ void QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message) { //-- Only pay attention to camera components, as identified by their compId - if(message.sysid == _vehicle->id() && (message.compid >= MAV_COMP_ID_CAMERA && message.compid <= MAV_COMP_ID_CAMERA6)) { + if(message.sysid == _vehicle->id() && (message.compid == MAV_COMP_ID_AUTOPILOT1 || + (message.compid >= MAV_COMP_ID_CAMERA && message.compid <= MAV_COMP_ID_CAMERA6))) { switch (message.msgid) { case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS: _handleCaptureStatus(message);