17constexpr double kPi = std::numbers::pi_v<double>;
22 constexpr int kHeartbeatTickMs = 500;
23 constexpr int kSilentTimeoutMs = 5000;
24 constexpr int kMaxRetryCount = 10;
27QVariantList QGCCameraManager::_cameraList;
37 if (result != MAV_RESULT_ACCEPTED) {
38 qCDebug(CameraManagerLog) <<
"CAMERA_FOV_STATUS request failed, result:"
39 << result <<
"failure:" << failureCode;
43 if (message.msgid != MAVLINK_MSG_ID_CAMERA_FOV_STATUS) {
44 qCDebug(CameraManagerLog) <<
"Unexpected msg id:" << message.msgid;
48 mavlink_camera_fov_status_t fov{};
50 mavlink_msg_camera_fov_status_decode(&message, &fov);
62 qCDebug(CameraManagerLog) <<
this;
63 backoffTimer.setSingleShot(
true);
66QGCCameraManager::CameraStruct::~CameraStruct()
68 qCDebug(CameraManagerLog) <<
this;
73QGCCameraManager::QGCCameraManager(
Vehicle *vehicle)
78 qCDebug(CameraManagerLog) <<
this;
80 (void) qRegisterMetaType<CameraMetaData*>(
"CameraMetaData*");
82 _addCameraControlToLists(_simulatedCameraControl);
89 _camerasLostHeartbeatTimer.setSingleShot(
false);
90 _lastZoomChange.start();
91 _lastCameraChange.start();
92 _camerasLostHeartbeatTimer.start(kHeartbeatTickMs);
95void QGCCameraManager::_initialConnectCompleted()
97 _initialConnectComplete =
true;
100QGCCameraManager::~QGCCameraManager()
103 for (
auto* cameraInfo : _cameraInfoRequest) {
104 cameraInfo->backoffTimer.stop();
105 QObject::disconnect(&cameraInfo->backoffTimer,
nullptr,
nullptr,
nullptr);
107 qDeleteAll(_cameraInfoRequest);
108 _cameraInfoRequest.clear();
111 _camerasLostHeartbeatTimer.stop();
113 qCDebug(CameraManagerLog) <<
this;
116void QGCCameraManager::setCurrentCamera(
int sel)
118 if ((sel != _currentCameraIndex) && (sel >= 0) && (sel < _cameras.
count())) {
119 _currentCameraIndex = sel;
127 qCDebug(CameraManagerLog) << ready;
131 if (MultiVehicleManager::instance()->activeVehicle() != _vehicle) {
135 _vehicleReadyState =
true;
142 if (!_initialConnectComplete) {
148 const bool fromAutopilot = message.compid == MAV_COMP_ID_AUTOPILOT1;
149 const bool fromCamera = (message.compid >= MAV_COMP_ID_CAMERA) && (message.compid <= MAV_COMP_ID_CAMERA6);
150 if ((message.sysid == _vehicle->id()) && (fromAutopilot || fromCamera)) {
151 switch (message.msgid) {
152 case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS:
153 _handleCameraCaptureStatus(message);
155 case MAVLINK_MSG_ID_STORAGE_INFORMATION:
156 _handleStorageInformation(message);
158 case MAVLINK_MSG_ID_HEARTBEAT:
162 _handleHeartbeat(message);
165 case MAVLINK_MSG_ID_CAMERA_INFORMATION:
166 _handleCameraInfo(message);
168 case MAVLINK_MSG_ID_CAMERA_SETTINGS:
169 _handleCameraSettings(message);
171 case MAVLINK_MSG_ID_PARAM_EXT_ACK:
172 _handleParamExtAck(message);
174 case MAVLINK_MSG_ID_PARAM_EXT_VALUE:
175 _handleParamExtValue(message);
177 case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:
178 _handleVideoStreamInformation(message);
180 case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
181 _handleVideoStreamStatus(message);
183 case MAVLINK_MSG_ID_BATTERY_STATUS:
184 _handleBatteryStatus(message);
186 case MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS:
187 _handleTrackingImageStatus(message);
189 case MAVLINK_MSG_ID_CAMERA_FOV_STATUS:
190 _handleCameraFovStatus(message);
200 const QString sCompID = QString::number(message.compid);
202 if (!_cameraInfoRequest.contains(sCompID)) {
204 CameraStruct *pInfo =
new CameraStruct(
this, message.compid, _vehicle);
205 pInfo->lastHeartbeat.start();
206 _cameraInfoRequest[sCompID] = pInfo;
207 _requestCameraInfo(pInfo);
211 CameraStruct *pInfo = _cameraInfoRequest[sCompID];
213 qCWarning(CameraManagerLog) << sCompID <<
"is null";
217 if (pInfo->infoReceived) {
218 pInfo->lastHeartbeat.start();
222 if (pInfo->lastHeartbeat.elapsed() > kSilentTimeoutMs) {
223 qCDebug(CameraManagerLog) <<
"Camera" <<
QGCMAVLink::compIdToString(message.compid) <<
"reappeared after being silent. Resetting retry count and requesting info.";
224 pInfo->retryCount = 0;
225 pInfo->backoffTimer.stop();
226 pInfo->lastHeartbeat.start();
227 _requestCameraInfo(pInfo);
231 pInfo->lastHeartbeat.start();
236 if ((_currentCameraIndex < _cameras.
count()) && !_cameras.
isEmpty()) {
237 MavlinkCameraControl *pCamera = qobject_cast<MavlinkCameraControl*>(_cameras[_currentCameraIndex]);
265 for (
int i = 0; i < _cameras.
count(); i++) {
271 qCCritical(CameraManagerLog) <<
"Invalid MavlinkCameraControl instance";
274 if (pCamera->
compID() ==
id) {
285 if (qobject_cast<SimulatedCameraControl*>(cameraControl)) {
286 qCDebug(CameraManagerLog) <<
"Adding simulated camera to list";
288 qCDebug(CameraManagerLog) <<
"Adding real camera to list - simulated camera will be removed if present";
291 _cameras.
append(cameraControl);
292 _cameraLabels.append(cameraControl->
modelName());
297 if ((_cameras.
count() == 2) && (_cameras[0] == _simulatedCameraControl)) {
299 (void) _cameraLabels.removeAt(0);
308 const QString sCompID = QString::number(message.compid);
309 if (!_cameraInfoRequest.contains(sCompID)) {
310 qCDebug(CameraManagerLog) <<
"Ignoring - Camera info not requested for component" <<
QGCMAVLink::compIdToString(message.compid);
313 if (_cameraInfoRequest[sCompID]->infoReceived) {
314 qCDebug(CameraManagerLog) <<
"Ignoring - Already received camera info for component" <<
QGCMAVLink::compIdToString(message.compid);
318 mavlink_camera_information_t info{};
319 mavlink_msg_camera_information_decode(&message, &info);
321 <<
"Model:" <<
reinterpret_cast<const char*
>(info.model_name);
322 qCDebug(CameraManagerLog) <<
"Creating MavlinkCameraControl for camera";
324 MavlinkCameraControl *pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid,
this);
326 _addCameraControlToLists(pCamera);
328 _cameraInfoRequest[sCompID]->infoReceived =
true;
329 _cameraInfoRequest[sCompID]->retryCount = 0;
330 _cameraInfoRequest[sCompID]->backoffTimer.stop();
334 double aspect = std::numeric_limits<double>::quiet_NaN();
336 if (info.resolution_h > 0 && info.resolution_v > 0) {
337 aspect = double(info.resolution_v) / double(info.resolution_h);
338 }
else if (info.sensor_size_h > 0.f && info.sensor_size_v > 0.f) {
339 aspect = double(info.sensor_size_v) / double(info.sensor_size_h);
342 _aspectByCompId.insert(message.compid, aspect);
347 QList<QString> stale;
348 for (
auto it = _cameraInfoRequest.cbegin(), end = _cameraInfoRequest.cend(); it != end; ++it) {
349 const auto *info = it.value();
350 if (info && info->infoReceived && (info->lastHeartbeat.elapsed() > kSilentTimeoutMs)) {
351 stale.push_back(it.key());
354 if (stale.isEmpty()) {
358 bool removedAny =
false;
359 for (
const QString& key : std::as_const(stale)) {
360 CameraStruct* pInfo = _cameraInfoRequest.take(key);
367 const int idx = _cameras.
indexOf(pCamera);
371 (void) _cameraLabels.removeAt(idx);
373 pCamera->deleteLater();
385 _addCameraControlToLists(_simulatedCameraControl);
391 if (_currentCameraIndex != 0) {
392 _currentCameraIndex = 0;
398void QGCCameraManager::_handleCameraCaptureStatus(
const mavlink_message_t &message)
402 mavlink_camera_capture_status_t cap{};
403 mavlink_msg_camera_capture_status_decode(&message, &cap);
408void QGCCameraManager::_handleStorageInformation(
const mavlink_message_t &message)
412 mavlink_storage_information_t st{};
413 mavlink_msg_storage_information_decode(&message, &st);
420 auto pCamera = _findCamera(message.compid);
422 mavlink_camera_settings_t settings{};
423 mavlink_msg_camera_settings_decode(&message, &settings);
426 const int newZoom =
static_cast<int>(settings.zoomLevel);
427 if (QThread::currentThread() == thread()) {
428 _setCurrentZoomLevel(newZoom);
430 QMetaObject::invokeMethod(
432 "_setCurrentZoomLevel",
433 Qt::QueuedConnection,
438 requestCameraFovForComp(message.compid);
446 mavlink_param_ext_ack_t ack{};
447 mavlink_msg_param_ext_ack_decode(&message, &ack);
456 mavlink_param_ext_value_t value{};
457 mavlink_msg_param_ext_value_decode(&message, &value);
462void QGCCameraManager::_handleVideoStreamInformation(
const mavlink_message_t &message)
466 mavlink_video_stream_information_t streamInfo{};
467 mavlink_msg_video_stream_information_decode(&message, &streamInfo);
477 mavlink_video_stream_status_t streamStatus{};
478 mavlink_msg_video_stream_status_decode(&message, &streamStatus);
487 mavlink_battery_status_t batteryStatus{};
488 mavlink_msg_battery_status_decode(&message, &batteryStatus);
493void QGCCameraManager::_handleTrackingImageStatus(
const mavlink_message_t &message)
497 mavlink_camera_tracking_image_status_t tis{};
498 mavlink_msg_camera_tracking_image_status_decode(&message, &tis);
507 auto *cameraInfo =
static_cast<QGCCameraManager::CameraStruct*
>(resultHandlerData);
509 if (ack.result != MAV_RESULT_ACCEPTED) {
510 qCDebug(CameraManagerLog) <<
"MAV_CMD_REQUEST_CAMERA_INFORMATION failed. compId" <<
QGCMAVLink::compIdToString(cameraInfo->compID)
513 <<
"retryCount:" << cameraInfo->retryCount;
520 auto *cameraInfo =
static_cast<QGCCameraManager::CameraStruct*
>(resultHandlerData);
522 if (result != MAV_RESULT_ACCEPTED) {
523 qCDebug(CameraManagerLog) <<
"MAV_CMD_REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_INFORMATION failed. compId" <<
QGCMAVLink::compIdToString(cameraInfo->compID)
526 <<
"retryCount:" << cameraInfo->retryCount;
534 if (pInfo->retryCount >= kMaxRetryCount) {
535 qCDebug(CameraManagerLog) <<
"Giving up requesting camera info after" << pInfo->retryCount <<
"attempts for compId" <<
QGCMAVLink::compIdToString(pInfo->compID);
540 if ((pInfo->retryCount % 2) == 0) {
541 qCDebug(CameraManagerLog) <<
"Using MAV_CMD_REQUEST_MESSAGE:CAMERA_INFORMATION for compId" <<
QGCMAVLink::compIdToString(pInfo->compID);
544 qCDebug(CameraManagerLog) <<
"Using MAV_CMD_REQUEST_CAMERA_INFORMATION for compId" <<
QGCMAVLink::compIdToString(pInfo->compID);
548 ackHandlerInfo.resultHandlerData = pInfo;
549 ackHandlerInfo.progressHandler =
nullptr;
550 ackHandlerInfo.progressHandlerData =
nullptr;
552 pInfo->vehicle->sendMavCommandWithHandler(&ackHandlerInfo, pInfo->compID, MAV_CMD_REQUEST_CAMERA_INFORMATION, 1 );
568 cameraInfo->retryCount++;
571 if ((cameraInfo->retryCount >= 2) && ((cameraInfo->retryCount % 2) == 0)) {
572 const int delaySeconds = 1 << (cameraInfo->retryCount / 2);
573 const int delayMs = delaySeconds * 1000;
575 qCDebug(CameraManagerLog) <<
"Waiting" << delaySeconds <<
"seconds before retry for compId" <<
QGCMAVLink::compIdToString(cameraInfo->compID);
577 cameraInfo->backoffTimer.stop();
578 (void) QObject::disconnect(&cameraInfo->backoffTimer,
nullptr,
nullptr,
nullptr);
581 const uint8_t compId = cameraInfo->compID;
582 QPointer<QGCCameraManager> mgrGuard(manager);
584 (void) QObject::connect(&cameraInfo->backoffTimer, &QTimer::timeout,
585 &cameraInfo->backoffTimer,
586 [mgrGuard, compId]() {
591 auto* info = mgrGuard->findCameraStruct(compId);
597 cameraInfo->backoffTimer.start(delayMs);
603void QGCCameraManager::_requestCameraInfo(CameraStruct *pInfo)
613 qCDebug(CameraManagerLog) <<
"Joystick changed";
614 if (_activeJoystick) {
626 _activeJoystick = joystick;
628 if (_activeJoystick) {
675 if (_lastZoomChange.elapsed() > 40) {
676 _lastZoomChange.start();
677 qCDebug(CameraManagerLog) <<
"Step Camera Zoom" << direction;
687 qCDebug(CameraManagerLog) <<
"Start Camera Zoom" << direction;
696 qCDebug(CameraManagerLog) <<
"Stop Camera Zoom";
705 if (_lastCameraChange.elapsed() > 1000) {
706 _lastCameraChange.start();
707 qCDebug(CameraManagerLog) <<
"Step Camera" << direction;
708 int camera = _currentCameraIndex + direction;
710 camera = _cameras.
count() - 1;
711 }
else if (camera >= _cameras.
count()) {
714 setCurrentCamera(camera);
720 if (_lastCameraChange.elapsed() > 1000) {
721 _lastCameraChange.start();
724 qCDebug(CameraManagerLog) <<
"Step Camera Stream" << direction;
736const QVariantList &QGCCameraManager::cameraList()
const
738 if (_cameraList.isEmpty()) {
739 const QList<CameraMetaData*> cams = CameraMetaData::parseCameraMetaData();
740 _cameraList.reserve(cams.size());
743 _cameraList << QVariant::fromValue(cam);
749void QGCCameraManager::requestCameraFovForComp(
int compId) {
751 qCWarning(CameraManagerLog) <<
"requestCameraFovForComp: vehicle is null";
755 compId, MAVLINK_MSG_ID_CAMERA_FOV_STATUS);
759double QGCCameraManager::aspectForComp(
int compId)
const {
760 auto it = _aspectByCompId.constFind(compId);
761 return (it == _aspectByCompId.cend())
762 ? std::numeric_limits<double>::quiet_NaN()
766double QGCCameraManager::currentCameraAspect(){
767 if (
auto* cam = currentCameraInstance()) {
768 return aspectForComp(cam->compID());
770 return std::numeric_limits<double>::quiet_NaN();
774 mavlink_camera_fov_status_t fov{};
775 mavlink_msg_camera_fov_status_decode(&message, &fov);
777 if (!std::isfinite(fov.hfov) || fov.hfov <= 0.0 || fov.hfov >= 180.0) {
781 double aspect = aspectForComp(message.compid);
782 if (!std::isfinite(aspect) || aspect <= 0.0) {
786 const double hfovRad = fov.hfov *
kPi / 180.0;
787 const double vfovRad = 2.0 * std::atan(std::tan(hfovRad * 0.5) * aspect);
788 const double vfovDeg = vfovRad * 180.0 /
kPi;
790 if (!std::isfinite(vfovDeg) || vfovDeg <= 0.0 || vfovDeg >= 180.0) {
791 qCWarning(CameraManagerLog) <<
"Invalid calculated VFOV:" << vfovDeg
792 <<
"hfov:" << fov.hfov
793 <<
"aspect:" << aspect
794 <<
"compId:" << message.compid;
798 auto* settings = SettingsManager::instance()->gimbalControllerSettings();
799 settings->
CameraHFov()->setRawValue(fov.hfov);
800 settings->CameraVFov()->setRawValue(vfovDeg);
803void QGCCameraManager::_setCurrentZoomLevel(
int level)
805 if (_zoomValueCurrent == level) {
808 _zoomValueCurrent = level;
812int QGCCameraManager::currentZoomLevel()
const
814 return _zoomValueCurrent;
static void _requestFovOnZoom_Handler(void *user, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message)
static void _handleCameraInfoRetry(QGCCameraManager::CameraStruct *cameraInfo)
static void _requestCameraInfoMessageResultHandler(void *resultHandlerData, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message)
static void _requestCameraInfoCommandResultHandler(void *resultHandlerData, int, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
static void _requestCameraInfoHelper(QGCCameraManager *manager, QGCCameraManager::CameraStruct *pInfo)
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Fact *CameraHFov READ CameraHFov CONSTANT Fact * CameraHFov()
void activeJoystickChanged(Joystick *joystick)
void stepZoom(int direction)
void startContinuousZoom(int direction)
void stopContinuousZoom()
void stepCamera(int direction)
void stepStream(int direction)
Abstract base class for all camera controls: real and simulated.
virtual void startZoom(int direction)=0
virtual void stepZoom(int direction)=0
virtual int currentStream() const =0
virtual QGCVideoStreamInfo * currentStreamInstance()=0
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)=0
virtual QGCVideoStreamInfo * thermalStreamInstance()=0
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)=0
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)=0
virtual void stopZoom()=0
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)=0
virtual QmlObjectListModel * streams()=0
virtual void handleParamExtAck(const mavlink_param_ext_ack_t ¶mExtAck)=0
virtual int compID() const =0
virtual void setCurrentStream(int stream)=0
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)=0
virtual QString modelName() const =0
virtual void handleParamExtValue(const mavlink_param_ext_value_t ¶mExtValue)=0
virtual bool stopVideoRecording()=0
virtual bool takePhoto()=0
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)=0
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)=0
virtual bool toggleVideoRecording()=0
virtual bool startVideoRecording()=0
void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable)
void currentZoomLevelChanged()
void _vehicleReady(bool ready)
void _checkForLostCameras()
void cameraLabelsChanged()
void _stepZoom(int direction)
void _startZoom(int direction)
void _startVideoRecording()
void _toggleVideoRecording()
void _mavlinkMessageReceived(const mavlink_message_t &message)
void currentCameraChanged()
void _stepCamera(int direction)
void _activeJoystickChanged(Joystick *joystick)
void _stepStream(int direction)
void _stopVideoRecording()
static QString compIdToString(uint8_t compId)
static QString mavResultToString(uint8_t result)
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
bool isEmpty() const override final
QObject * removeAt(int index)
int count() const override final
int indexOf(const QObject *object)
static QString mavCmdResultFailureCodeToString(MavCmdResultFailureCode_t failureCode)
void initialConnectComplete()
MavCmdResultFailureCode_t
void mavlinkMessageReceived(const mavlink_message_t &message)
RequestMessageResultHandlerFailureCode_t
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
void requestMessage(RequestMessageResultHandler resultHandler, void *resultHandlerData, int compId, int messageId, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f)
MavCmdResultHandler resultHandler