QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCCameraManager.cc
Go to the documentation of this file.
1#include "QGCCameraManager.h"
2#include "CameraMetaData.h"
3#include "FirmwarePlugin.h"
4#include "Joystick.h"
5#include "JoystickManager.h"
11
12#include <cmath>
14#include "SettingsManager.h"
15#include <numbers>
16
17constexpr double kPi = std::numbers::pi_v<double>;
18
19QGC_LOGGING_CATEGORY(CameraManagerLog, "Camera.QGCCameraManager")
20
21namespace {
22 constexpr int kHeartbeatTickMs = 500;
23 constexpr int kSilentTimeoutMs = 5000;
24 constexpr int kMaxRetryCount = 10;
25}
26
27QVariantList QGCCameraManager::_cameraList;
28
30 void* user,
31 MAV_RESULT result,
33 const mavlink_message_t& message)
34{
35 auto* mgr = static_cast<QGCCameraManager*>(user);
36
37 if (result != MAV_RESULT_ACCEPTED) {
38 qCDebug(CameraManagerLog) << "CAMERA_FOV_STATUS request failed, result:"
39 << result << "failure:" << failureCode;
40 return;
41 }
42
43 if (message.msgid != MAVLINK_MSG_ID_CAMERA_FOV_STATUS) {
44 qCDebug(CameraManagerLog) << "Unexpected msg id:" << message.msgid;
45 return;
46 }
47
48 mavlink_camera_fov_status_t fov{};
49
50 mavlink_msg_camera_fov_status_decode(&message, &fov);
51
52 if (!mgr) return;
53}
54
55/*===========================================================================*/
56
57QGCCameraManager::CameraStruct::CameraStruct(QGCCameraManager *manager_, uint8_t compID_, Vehicle *vehicle_)
58 : compID(compID_)
59 , vehicle(vehicle_)
60 , manager(manager_)
61{
62 qCDebug(CameraManagerLog) << this;
63 backoffTimer.setSingleShot(true);
64}
65
66QGCCameraManager::CameraStruct::~CameraStruct()
67{
68 qCDebug(CameraManagerLog) << this;
69}
70
71/*===========================================================================*/
72
73QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
74 : QObject(vehicle)
75 , _vehicle(vehicle)
76 , _simulatedCameraControl(new SimulatedCameraControl(vehicle, this))
77{
78 qCDebug(CameraManagerLog) << this;
79
80 (void) qRegisterMetaType<CameraMetaData*>("CameraMetaData*");
81
82 _addCameraControlToLists(_simulatedCameraControl);
83
84 (void) connect(_vehicle, &Vehicle::initialConnectComplete, this, &QGCCameraManager::_initialConnectCompleted, Qt::UniqueConnection);
85 (void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady);
87 (void) connect(&_camerasLostHeartbeatTimer, &QTimer::timeout, this, &QGCCameraManager::_checkForLostCameras);
88
89 _camerasLostHeartbeatTimer.setSingleShot(false);
90 _lastZoomChange.start();
91 _lastCameraChange.start();
92 _camerasLostHeartbeatTimer.start(kHeartbeatTickMs);
93}
94
95void QGCCameraManager::_initialConnectCompleted()
96{
97 _initialConnectComplete = true;
98}
99
100QGCCameraManager::~QGCCameraManager()
101{
102 // Stop all camera info request timers and clean up
103 for (auto* cameraInfo : _cameraInfoRequest) {
104 cameraInfo->backoffTimer.stop();
105 QObject::disconnect(&cameraInfo->backoffTimer, nullptr, nullptr, nullptr);
106 }
107 qDeleteAll(_cameraInfoRequest);
108 _cameraInfoRequest.clear();
109
110 // Stop the main heartbeat timer
111 _camerasLostHeartbeatTimer.stop();
112
113 qCDebug(CameraManagerLog) << this;
114}
115
116void QGCCameraManager::setCurrentCamera(int sel)
117{
118 if ((sel != _currentCameraIndex) && (sel >= 0) && (sel < _cameras.count())) {
119 _currentCameraIndex = sel;
121 emit streamChanged();
122 }
123}
124
126{
127 qCDebug(CameraManagerLog) << ready;
128 if (!ready) {
129 return;
130 }
131 if (MultiVehicleManager::instance()->activeVehicle() != _vehicle) {
132 return;
133 }
134
135 _vehicleReadyState = true;
136 _activeJoystickChanged(JoystickManager::instance()->activeJoystick());
137 (void) connect(JoystickManager::instance(), &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged, Qt::UniqueConnection);
138}
139
141{
142 if (!_initialConnectComplete) {
143 return;
144 }
145
146 // Only pay attention to camera components (MAV_COMP_ID_CAMERA..CAMERA6)
147 // and camera-related messages proxied by the autopilot.
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);
154 break;
155 case MAVLINK_MSG_ID_STORAGE_INFORMATION:
156 _handleStorageInformation(message);
157 break;
158 case MAVLINK_MSG_ID_HEARTBEAT:
159 // Autopilot heartbeats should not be treated as camera discovery.
160 // Only actual camera component heartbeats should start CAMERA_INFORMATION requests.
161 if (fromCamera) {
162 _handleHeartbeat(message);
163 }
164 break;
165 case MAVLINK_MSG_ID_CAMERA_INFORMATION:
166 _handleCameraInfo(message);
167 break;
168 case MAVLINK_MSG_ID_CAMERA_SETTINGS:
169 _handleCameraSettings(message);
170 break;
171 case MAVLINK_MSG_ID_PARAM_EXT_ACK:
172 _handleParamExtAck(message);
173 break;
174 case MAVLINK_MSG_ID_PARAM_EXT_VALUE:
175 _handleParamExtValue(message);
176 break;
177 case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION:
178 _handleVideoStreamInformation(message);
179 break;
180 case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS:
181 _handleVideoStreamStatus(message);
182 break;
183 case MAVLINK_MSG_ID_BATTERY_STATUS:
184 _handleBatteryStatus(message);
185 break;
186 case MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS:
187 _handleTrackingImageStatus(message);
188 break;
189 case MAVLINK_MSG_ID_CAMERA_FOV_STATUS:
190 _handleCameraFovStatus(message);
191 break;
192 default:
193 break;
194 }
195 }
196}
197
198void QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
199{
200 const QString sCompID = QString::number(message.compid);
201
202 if (!_cameraInfoRequest.contains(sCompID)) {
203 qCDebug(CameraManagerLog) << "Heartbeat from" << QGCMAVLink::compIdToString(message.compid);
204 CameraStruct *pInfo = new CameraStruct(this, message.compid, _vehicle);
205 pInfo->lastHeartbeat.start();
206 _cameraInfoRequest[sCompID] = pInfo;
207 _requestCameraInfo(pInfo);
208 return;
209 }
210
211 CameraStruct *pInfo = _cameraInfoRequest[sCompID];
212 if (!pInfo) {
213 qCWarning(CameraManagerLog) << sCompID << "is null";
214 return;
215 }
216
217 if (pInfo->infoReceived) {
218 pInfo->lastHeartbeat.start();
219 return;
220 }
221
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);
228 return;
229 }
230
231 pInfo->lastHeartbeat.start();
232}
233
234MavlinkCameraControl *QGCCameraManager::currentCameraInstance()
235{
236 if ((_currentCameraIndex < _cameras.count()) && !_cameras.isEmpty()) {
237 MavlinkCameraControl *pCamera = qobject_cast<MavlinkCameraControl*>(_cameras[_currentCameraIndex]);
238 return pCamera;
239 }
240 return nullptr;
241}
242
243QGCVideoStreamInfo *QGCCameraManager::currentStreamInstance()
244{
245 MavlinkCameraControl *pCamera = currentCameraInstance();
246 if (pCamera) {
247 QGCVideoStreamInfo *pInfo = pCamera->currentStreamInstance();
248 return pInfo;
249 }
250 return nullptr;
251}
252
253QGCVideoStreamInfo *QGCCameraManager::thermalStreamInstance()
254{
255 MavlinkCameraControl *pCamera = currentCameraInstance();
256 if (pCamera) {
257 QGCVideoStreamInfo *pInfo = pCamera->thermalStreamInstance();
258 return pInfo;
259 }
260 return nullptr;
261}
262
263MavlinkCameraControl *QGCCameraManager::_findCamera(int id)
264{
265 for (int i = 0; i < _cameras.count(); i++) {
266 if (!_cameras[i]) {
267 continue;
268 }
269 MavlinkCameraControl *pCamera = qobject_cast<MavlinkCameraControl*>(_cameras[i]);
270 if (!pCamera) {
271 qCCritical(CameraManagerLog) << "Invalid MavlinkCameraControl instance";
272 continue;
273 }
274 if (pCamera->compID() == id) {
275 return pCamera;
276 }
277 }
278
279 // qCWarning(CameraManagerLog) << "Camera component id not found:" << id;
280 return nullptr;
281}
282
283void QGCCameraManager::_addCameraControlToLists(MavlinkCameraControl *cameraControl)
284{
285 if (qobject_cast<SimulatedCameraControl*>(cameraControl)) {
286 qCDebug(CameraManagerLog) << "Adding simulated camera to list";
287 } else {
288 qCDebug(CameraManagerLog) << "Adding real camera to list - simulated camera will be removed if present";
289 }
290
291 _cameras.append(cameraControl);
292 _cameraLabels.append(cameraControl->modelName());
293 emit camerasChanged();
294 emit cameraLabelsChanged();
295
296 // If simulated camera is in list, remove it when a real camera appears
297 if ((_cameras.count() == 2) && (_cameras[0] == _simulatedCameraControl)) {
298 (void) _cameras.removeAt(0);
299 (void) _cameraLabels.removeAt(0);
300 emit camerasChanged();
301 emit cameraLabelsChanged();
303 }
304}
305
306void QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
307{
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);
311 return;
312 }
313 if (_cameraInfoRequest[sCompID]->infoReceived) {
314 qCDebug(CameraManagerLog) << "Ignoring - Already received camera info for component" << QGCMAVLink::compIdToString(message.compid);
315 return;
316 }
317
318 mavlink_camera_information_t info{};
319 mavlink_msg_camera_information_decode(&message, &info);
320 qCDebug(CameraManagerLog) << "Camera information received from" << QGCMAVLink::compIdToString(message.compid)
321 << "Model:" << reinterpret_cast<const char*>(info.model_name);
322 qCDebug(CameraManagerLog) << "Creating MavlinkCameraControl for camera";
323
324 MavlinkCameraControl *pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this);
325 if (pCamera) {
326 _addCameraControlToLists(pCamera);
327
328 _cameraInfoRequest[sCompID]->infoReceived = true;
329 _cameraInfoRequest[sCompID]->retryCount = 0;
330 _cameraInfoRequest[sCompID]->backoffTimer.stop();
331 qCDebug(CameraManagerLog) << "Success for compId" << QGCMAVLink::compIdToString(message.compid) << "- reset retry counter";
332 }
333
334 double aspect = std::numeric_limits<double>::quiet_NaN();
335
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);
340 }
341
342 _aspectByCompId.insert(message.compid, aspect);
343}
344
346{
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());
352 }
353 }
354 if (stale.isEmpty()) {
355 return;
356 }
357
358 bool removedAny = false;
359 for (const QString& key : std::as_const(stale)) {
360 CameraStruct* pInfo = _cameraInfoRequest.take(key);
361 if (!pInfo) {
362 continue;
363 }
364
365 MavlinkCameraControl* pCamera = _findCamera(pInfo->compID);
366 if (pCamera) {
367 const int idx = _cameras.indexOf(pCamera);
368 if (idx >= 0) {
369 qCDebug(CameraManagerLog) << "Removing lost camera" << QGCMAVLink::compIdToString(pInfo->compID);
370 removedAny = true;
371 (void) _cameraLabels.removeAt(idx);
372 (void) _cameras.removeAt(idx);
373 pCamera->deleteLater();
374 }
375 }
376
377 delete pInfo;
378 }
379
380 if (!removedAny) {
381 return;
382 }
383
384 if (_cameras.isEmpty()) {
385 _addCameraControlToLists(_simulatedCameraControl);
386 }
387
388 emit cameraLabelsChanged();
389 emit camerasChanged();
390
391 if (_currentCameraIndex != 0) {
392 _currentCameraIndex = 0;
394 }
395 emit streamChanged();
396}
397
398void QGCCameraManager::_handleCameraCaptureStatus(const mavlink_message_t &message)
399{
400 MavlinkCameraControl *pCamera = _findCamera(message.compid);
401 if (pCamera) {
402 mavlink_camera_capture_status_t cap{};
403 mavlink_msg_camera_capture_status_decode(&message, &cap);
404 pCamera->handleCameraCaptureStatus(cap);
405 }
406}
407
408void QGCCameraManager::_handleStorageInformation(const mavlink_message_t &message)
409{
410 MavlinkCameraControl *pCamera = _findCamera(message.compid);
411 if (pCamera) {
412 mavlink_storage_information_t st{};
413 mavlink_msg_storage_information_decode(&message, &st);
414 pCamera->handleStorageInformation(st);
415 }
416}
417
418void QGCCameraManager::_handleCameraSettings(const mavlink_message_t& message)
419{
420 auto pCamera = _findCamera(message.compid);
421 if (pCamera) {
422 mavlink_camera_settings_t settings{};
423 mavlink_msg_camera_settings_decode(&message, &settings);
424 pCamera->handleCameraSettings(settings);
425
426 const int newZoom = static_cast<int>(settings.zoomLevel);
427 if (QThread::currentThread() == thread()) {
428 _setCurrentZoomLevel(newZoom);
429 } else {
430 QMetaObject::invokeMethod(
431 this,
432 "_setCurrentZoomLevel",
433 Qt::QueuedConnection,
434 Q_ARG(int, newZoom)
435 );
436 }
437
438 requestCameraFovForComp(message.compid);
439 }
440}
441
442void QGCCameraManager::_handleParamExtAck(const mavlink_message_t &message)
443{
444 MavlinkCameraControl *pCamera = _findCamera(message.compid);
445 if (pCamera) {
446 mavlink_param_ext_ack_t ack{};
447 mavlink_msg_param_ext_ack_decode(&message, &ack);
448 pCamera->handleParamExtAck(ack);
449 }
450}
451
452void QGCCameraManager::_handleParamExtValue(const mavlink_message_t &message)
453{
454 MavlinkCameraControl *pCamera = _findCamera(message.compid);
455 if (pCamera) {
456 mavlink_param_ext_value_t value{};
457 mavlink_msg_param_ext_value_decode(&message, &value);
458 pCamera->handleParamExtValue(value);
459 }
460}
461
462void QGCCameraManager::_handleVideoStreamInformation(const mavlink_message_t &message)
463{
464 MavlinkCameraControl *pCamera = _findCamera(message.compid);
465 if (pCamera) {
466 mavlink_video_stream_information_t streamInfo{};
467 mavlink_msg_video_stream_information_decode(&message, &streamInfo);
468 pCamera->handleVideoStreamInformation(streamInfo);
469 emit streamChanged();
470 }
471}
472
473void QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t &message)
474{
475 MavlinkCameraControl *pCamera = _findCamera(message.compid);
476 if (pCamera) {
477 mavlink_video_stream_status_t streamStatus{};
478 mavlink_msg_video_stream_status_decode(&message, &streamStatus);
479 pCamera->handleVideoStreamStatus(streamStatus);
480 }
481}
482
483void QGCCameraManager::_handleBatteryStatus(const mavlink_message_t &message)
484{
485 MavlinkCameraControl *pCamera = _findCamera(message.compid);
486 if (pCamera) {
487 mavlink_battery_status_t batteryStatus{};
488 mavlink_msg_battery_status_decode(&message, &batteryStatus);
489 pCamera->handleBatteryStatus(batteryStatus);
490 }
491}
492
493void QGCCameraManager::_handleTrackingImageStatus(const mavlink_message_t &message)
494{
495 MavlinkCameraControl *pCamera = _findCamera(message.compid);
496 if (pCamera) {
497 mavlink_camera_tracking_image_status_t tis{};
498 mavlink_msg_camera_tracking_image_status_decode(&message, &tis);
499 pCamera->handleTrackingImageStatus(tis);
500 }
501}
502
503static void _handleCameraInfoRetry(QGCCameraManager::CameraStruct *cameraInfo);
504
505static void _requestCameraInfoCommandResultHandler(void *resultHandlerData, int /*compId*/, const mavlink_command_ack_t &ack, Vehicle::MavCmdResultFailureCode_t failureCode)
506{
507 auto *cameraInfo = static_cast<QGCCameraManager::CameraStruct*>(resultHandlerData);
508
509 if (ack.result != MAV_RESULT_ACCEPTED) {
510 qCDebug(CameraManagerLog) << "MAV_CMD_REQUEST_CAMERA_INFORMATION failed. compId" << QGCMAVLink::compIdToString(cameraInfo->compID)
511 << "Result:" << QGCMAVLink::mavResultToString(ack.result)
512 << "FailureCode:" << Vehicle::mavCmdResultFailureCodeToString(failureCode)
513 << "retryCount:" << cameraInfo->retryCount;
514 _handleCameraInfoRetry(cameraInfo);
515 }
516}
517
518static void _requestCameraInfoMessageResultHandler(void *resultHandlerData, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, [[maybe_unused]] const mavlink_message_t &message)
519{
520 auto *cameraInfo = static_cast<QGCCameraManager::CameraStruct*>(resultHandlerData);
521
522 if (result != MAV_RESULT_ACCEPTED) {
523 qCDebug(CameraManagerLog) << "MAV_CMD_REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_INFORMATION failed. compId" << QGCMAVLink::compIdToString(cameraInfo->compID)
524 << "Result:" << QGCMAVLink::mavResultToString(result)
525 << "FailureCode:" << Vehicle::requestMessageResultHandlerFailureCodeToString(failureCode)
526 << "retryCount:" << cameraInfo->retryCount;
527 _handleCameraInfoRetry(cameraInfo);
528 }
529}
530
531static void _requestCameraInfoHelper(QGCCameraManager *manager, QGCCameraManager::CameraStruct *pInfo)
532{
533 // Give up after max attempts
534 if (pInfo->retryCount >= kMaxRetryCount) {
535 qCDebug(CameraManagerLog) << "Giving up requesting camera info after" << pInfo->retryCount << "attempts for compId" << QGCMAVLink::compIdToString(pInfo->compID);
536 return;
537 }
538
539 // Alternate between REQUEST_MESSAGE and REQUEST_CAMERA_INFORMATION
540 if ((pInfo->retryCount % 2) == 0) {
541 qCDebug(CameraManagerLog) << "Using MAV_CMD_REQUEST_MESSAGE:CAMERA_INFORMATION for compId" << QGCMAVLink::compIdToString(pInfo->compID);
542 manager->vehicle()->requestMessage(_requestCameraInfoMessageResultHandler, pInfo, pInfo->compID, MAVLINK_MSG_ID_CAMERA_INFORMATION);
543 } else {
544 qCDebug(CameraManagerLog) << "Using MAV_CMD_REQUEST_CAMERA_INFORMATION for compId" << QGCMAVLink::compIdToString(pInfo->compID);
545
546 Vehicle::MavCmdAckHandlerInfo_t ackHandlerInfo{};
548 ackHandlerInfo.resultHandlerData = pInfo;
549 ackHandlerInfo.progressHandler = nullptr;
550 ackHandlerInfo.progressHandlerData = nullptr;
551
552 pInfo->vehicle->sendMavCommandWithHandler(&ackHandlerInfo, pInfo->compID, MAV_CMD_REQUEST_CAMERA_INFORMATION, 1 /* request camera capabilities */);
553 }
554}
555
556static void _handleCameraInfoRetry(QGCCameraManager::CameraStruct *cameraInfo)
557{
558 if (!cameraInfo) {
559 return;
560 }
561
562 QGCCameraManager *manager = cameraInfo->manager;
563 if (!manager) {
564 qCDebug(CameraManagerLog) << "manager is unavailable for compId" << QGCMAVLink::compIdToString(cameraInfo->compID);
565 return;
566 }
567
568 cameraInfo->retryCount++;
569
570 // For even attempts >= 2, use exponential backoff
571 if ((cameraInfo->retryCount >= 2) && ((cameraInfo->retryCount % 2) == 0)) {
572 const int delaySeconds = 1 << (cameraInfo->retryCount / 2);
573 const int delayMs = delaySeconds * 1000;
574
575 qCDebug(CameraManagerLog) << "Waiting" << delaySeconds << "seconds before retry for compId" << QGCMAVLink::compIdToString(cameraInfo->compID);
576
577 cameraInfo->backoffTimer.stop();
578 (void) QObject::disconnect(&cameraInfo->backoffTimer, nullptr, nullptr, nullptr);
579
580 // Capture compID by value and look up the struct
581 const uint8_t compId = cameraInfo->compID;
582 QPointer<QGCCameraManager> mgrGuard(manager);
583
584 (void) QObject::connect(&cameraInfo->backoffTimer, &QTimer::timeout,
585 &cameraInfo->backoffTimer, // context ensures timer is still alive
586 [mgrGuard, compId]() {
587 if (!mgrGuard) {
588 return;
589 }
590
591 auto* info = mgrGuard->findCameraStruct(compId);
592 if (info) {
593 _requestCameraInfoHelper(mgrGuard.data(), info);
594 }
595 });
596
597 cameraInfo->backoffTimer.start(delayMs);
598 } else {
599 _requestCameraInfoHelper(manager, cameraInfo);
600 }
601}
602
603void QGCCameraManager::_requestCameraInfo(CameraStruct *pInfo)
604{
605 if (!pInfo) {
606 return;
607 }
608 _requestCameraInfoHelper(this, pInfo);
609}
610
612{
613 qCDebug(CameraManagerLog) << "Joystick changed";
614 if (_activeJoystick) {
615 (void) disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
616 (void) disconnect(_activeJoystick, &Joystick::startContinuousZoom, this, &QGCCameraManager::_startZoom);
617 (void) disconnect(_activeJoystick, &Joystick::stopContinuousZoom, this, &QGCCameraManager::_stopZoom);
618 (void) disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
619 (void) disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
620 (void) disconnect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera);
621 (void) disconnect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording);
622 (void) disconnect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording);
623 (void) disconnect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording);
624 }
625
626 _activeJoystick = joystick;
627
628 if (_activeJoystick) {
629 (void) connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom, Qt::UniqueConnection);
630 (void) connect(_activeJoystick, &Joystick::startContinuousZoom, this, &QGCCameraManager::_startZoom, Qt::UniqueConnection);
631 (void) connect(_activeJoystick, &Joystick::stopContinuousZoom, this, &QGCCameraManager::_stopZoom, Qt::UniqueConnection);
632 (void) connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera, Qt::UniqueConnection);
633 (void) connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream, Qt::UniqueConnection);
634 (void) connect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera, Qt::UniqueConnection);
635 (void) connect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording, Qt::UniqueConnection);
636 (void) connect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording, Qt::UniqueConnection);
637 (void) connect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording, Qt::UniqueConnection);
638 }
639}
640
642{
643 MavlinkCameraControl *pCamera = currentCameraInstance();
644 if (pCamera) {
645 pCamera->takePhoto();
646 }
647}
648
650{
651 MavlinkCameraControl *pCamera = currentCameraInstance();
652 if (pCamera) {
653 pCamera->startVideoRecording();
654 }
655}
656
658{
659 MavlinkCameraControl *pCamera = currentCameraInstance();
660 if (pCamera) {
661 pCamera->stopVideoRecording();
662 }
663}
664
666{
667 MavlinkCameraControl *pCamera = currentCameraInstance();
668 if (pCamera) {
669 pCamera->toggleVideoRecording();
670 }
671}
672
674{
675 if (_lastZoomChange.elapsed() > 40) {
676 _lastZoomChange.start();
677 qCDebug(CameraManagerLog) << "Step Camera Zoom" << direction;
678 MavlinkCameraControl *pCamera = currentCameraInstance();
679 if (pCamera) {
680 pCamera->stepZoom(direction);
681 }
682 }
683}
684
686{
687 qCDebug(CameraManagerLog) << "Start Camera Zoom" << direction;
688 MavlinkCameraControl *pCamera = currentCameraInstance();
689 if (pCamera) {
690 pCamera->startZoom(direction);
691 }
692}
693
695{
696 qCDebug(CameraManagerLog) << "Stop Camera Zoom";
697 MavlinkCameraControl *pCamera = currentCameraInstance();
698 if (pCamera) {
699 pCamera->stopZoom();
700 }
701}
702
704{
705 if (_lastCameraChange.elapsed() > 1000) {
706 _lastCameraChange.start();
707 qCDebug(CameraManagerLog) << "Step Camera" << direction;
708 int camera = _currentCameraIndex + direction;
709 if (camera < 0) {
710 camera = _cameras.count() - 1;
711 } else if (camera >= _cameras.count()) {
712 camera = 0;
713 }
714 setCurrentCamera(camera);
715 }
716}
717
719{
720 if (_lastCameraChange.elapsed() > 1000) {
721 _lastCameraChange.start();
722 MavlinkCameraControl *pCamera = currentCameraInstance();
723 if (pCamera) {
724 qCDebug(CameraManagerLog) << "Step Camera Stream" << direction;
725 int stream = pCamera->currentStream() + direction;
726 if (stream < 0) {
727 stream = pCamera->streams()->count() - 1;
728 } else if (stream >= pCamera->streams()->count()) {
729 stream = 0;
730 }
731 pCamera->setCurrentStream(stream);
732 }
733 }
734}
735
736const QVariantList &QGCCameraManager::cameraList() const
737{
738 if (_cameraList.isEmpty()) {
739 const QList<CameraMetaData*> cams = CameraMetaData::parseCameraMetaData();
740 _cameraList.reserve(cams.size());
741
742 for (CameraMetaData *cam : cams) {
743 _cameraList << QVariant::fromValue(cam);
744 }
745 }
746 return _cameraList;
747}
748
749void QGCCameraManager::requestCameraFovForComp(int compId) {
750 if (!_vehicle) {
751 qCWarning(CameraManagerLog) << "requestCameraFovForComp: vehicle is null";
752 return;
753 }
754 _vehicle->requestMessage(_requestFovOnZoom_Handler, /*user*/this,
755 compId, MAVLINK_MSG_ID_CAMERA_FOV_STATUS);
756}
757
758//-----------------------------------------------------------------------------
759double QGCCameraManager::aspectForComp(int compId) const {
760 auto it = _aspectByCompId.constFind(compId);
761 return (it == _aspectByCompId.cend())
762 ? std::numeric_limits<double>::quiet_NaN()
763 : it.value();
764}
765
766double QGCCameraManager::currentCameraAspect(){
767 if (auto* cam = currentCameraInstance()) {
768 return aspectForComp(cam->compID());
769 }
770 return std::numeric_limits<double>::quiet_NaN();
771}
772void QGCCameraManager::_handleCameraFovStatus(const mavlink_message_t& message)
773{
774 mavlink_camera_fov_status_t fov{};
775 mavlink_msg_camera_fov_status_decode(&message, &fov);
776
777 if (!std::isfinite(fov.hfov) || fov.hfov <= 0.0 || fov.hfov >= 180.0) {
778 return;
779 }
780
781 double aspect = aspectForComp(message.compid);
782 if (!std::isfinite(aspect) || aspect <= 0.0) {
783 aspect = 16.0 / 9.0;
784 }
785
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;
789
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;
795 return;
796 }
797
798 auto* settings = SettingsManager::instance()->gimbalControllerSettings();
799 settings->CameraHFov()->setRawValue(fov.hfov);
800 settings->CameraVFov()->setRawValue(vfovDeg);
801}
802
803void QGCCameraManager::_setCurrentZoomLevel(int level)
804{
805 if (_zoomValueCurrent == level) {
806 return;
807 }
808 _zoomValueCurrent = level;
810}
811
812int QGCCameraManager::currentZoomLevel() const
813{
814 return _zoomValueCurrent;
815}
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)
constexpr double kPi
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Set of meta data which describes a camera available on the vehicle.
Fact *CameraHFov READ CameraHFov CONSTANT Fact * CameraHFov()
void activeJoystickChanged(Joystick *joystick)
void triggerCamera()
void startVideoRecord()
void stopVideoRecord()
void stepZoom(int direction)
void startContinuousZoom(int direction)
void stopContinuousZoom()
void stepCamera(int direction)
void stepStream(int direction)
void toggleVideoRecord()
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 &paramExtAck)=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 &paramExtValue)=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)
Camera Manager.
void currentZoomLevelChanged()
void _vehicleReady(bool ready)
void cameraLabelsChanged()
void _stepZoom(int direction)
void _startZoom(int direction)
void _mavlinkMessageReceived(const mavlink_message_t &message)
void currentCameraChanged()
void _stepCamera(int direction)
void _activeJoystickChanged(Joystick *joystick)
void _stepStream(int direction)
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)
Definition Vehicle.cc:4364
void initialConnectComplete()
MavCmdResultFailureCode_t
Definition Vehicle.h:618
void mavlinkMessageReceived(const mavlink_message_t &message)
RequestMessageResultHandlerFailureCode_t
Definition Vehicle.h:668
static QString requestMessageResultHandlerFailureCodeToString(RequestMessageResultHandlerFailureCode_t failureCode)
Definition Vehicle.cc:4345
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)
Definition Vehicle.cc:3099
MavCmdResultHandler resultHandler
Definition Vehicle.h:639