QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleCameraControl.cc
Go to the documentation of this file.
2#include "QGCCameraIO.h"
3#include "QGCApplication.h"
4#include "SettingsManager.h"
5#include "AppSettings.h"
6#include "VideoManager.h"
7#include "QGCCameraManager.h"
8#include "FTPManager.h"
9#include "QGCCompression.h"
10#include "QGCCorePlugin.h"
11#include "QGCFileHelper.h"
12#include "Vehicle.h"
13#include "LinkInterface.h"
14#include "MAVLinkProtocol.h"
15#include "QGCVideoStreamInfo.h"
16#include "MissionCommandTree.h"
17
18#include <QtNetwork/QNetworkAccessManager>
19#include <QtCore/QDir>
20#include <QtCore/QSettings>
21#include <QtXml/QDomDocument>
22#include <QtXml/QDomNodeList>
23#include <QtQml/QQmlEngine>
24#include <QtNetwork/QNetworkReply>
25
26#include "QGCNetworkHelper.h"
27
28QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_)
29 : QObject(parent)
30 , param(param_)
31 , value(value_)
32 , exclusions(exclusions_)
33{
34}
35
36QGCCameraOptionRange::QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
37 : QObject(parent)
38 , param(param_)
39 , value(value_)
40 , targetParam(targetParam_)
41 , condition(condition_)
42 , optNames(optNames_)
43 , optValues(optValues_)
44{
45}
46
47static bool read_attribute(QDomNode& node, const char* tagName, bool& target)
48{
49 QDomNamedNodeMap attrs = node.attributes();
50 if(!attrs.count()) {
51 return false;
52 }
53 QDomNode subNode = attrs.namedItem(tagName);
54 if(subNode.isNull()) {
55 return false;
56 }
57 target = subNode.nodeValue() != "0";
58 return true;
59}
60
61static bool read_attribute(QDomNode& node, const char* tagName, int& target)
62{
63 QDomNamedNodeMap attrs = node.attributes();
64 if(!attrs.count()) {
65 return false;
66 }
67 QDomNode subNode = attrs.namedItem(tagName);
68 if(subNode.isNull()) {
69 return false;
70 }
71 target = subNode.nodeValue().toInt();
72 return true;
73}
74
75static bool read_attribute(QDomNode& node, const char* tagName, QString& target)
76{
77 QDomNamedNodeMap attrs = node.attributes();
78 if(!attrs.count()) {
79 return false;
80 }
81 QDomNode subNode = attrs.namedItem(tagName);
82 if(subNode.isNull()) {
83 return false;
84 }
85 target = subNode.nodeValue();
86 return true;
87}
88
89static bool read_value(QDomNode& element, const char* tagName, QString& target)
90{
91 QDomElement de = element.firstChildElement(tagName);
92 if(de.isNull()) {
93 return false;
94 }
95 target = de.text();
96 return true;
97}
98
99VehicleCameraControl::VehicleCameraControl(const mavlink_camera_information_t *info, Vehicle* vehicle, int compID, QObject* parent)
100 : MavlinkCameraControl(vehicle, parent)
101 , _compID(compID)
102{
103 QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
104
105 memcpy(&_mavlinkCameraInfo, info, sizeof(mavlink_camera_information_t));
106
107 _vendor = QString(reinterpret_cast<const char*>(info->vendor_name));
108 _modelName = QString(reinterpret_cast<const char*>(info->model_name));
109 _cacheFile = QString::asprintf("%s/%s_%s_%03d.xml",
110 SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
111 _vendor.toStdString().c_str(),
112 _modelName.toStdString().c_str(),
113 static_cast<int>(_mavlinkCameraInfo.cam_definition_version));
114
115 if(info->cam_definition_uri[0] != 0) {
116 //-- Process camera definition file
117 _handleDefinitionFile(info->cam_definition_uri);
118 } else {
120 }
121
122 QSettings settings;
123 _photoCaptureMode = static_cast<PhotoCaptureMode>(settings.value(kPhotoMode, static_cast<int>(PHOTO_CAPTURE_SINGLE)).toInt());
124 _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble();
125 _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt();
126 _thermalOpacity = settings.value(kThermalOpacity, 85.0).toDouble();
127 _thermalMode = static_cast<ThermalViewMode>(settings.value(kThermalMode, static_cast<uint32_t>(THERMAL_BLEND)).toUInt());
128
129 _videoRecordTimeUpdateTimer.setSingleShot(false);
130 _videoRecordTimeUpdateTimer.setInterval(333);
132
133 //-- Tracking
134 if(_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE) {
137 }
138 if(_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_TRACKING_POINT) {
141 }
142
144
145 qCDebug(CameraControlLog) << "Camera Info:";
146 qCDebug(CameraControlLog) << " vendor:" << vendor();
147 qCDebug(CameraControlLog) << " model:" << modelName();
148 qCDebug(CameraControlLog) << " version:" << version();
149 qCDebug(CameraControlLog) << " firmware:" << firmwareVersion();
150 qCDebug(CameraControlLog) << " focal length:" << focalLength();
151 qCDebug(CameraControlLog) << " sensor size:" << sensorSize();
152 qCDebug(CameraControlLog) << " resolution:" << resolution();
153 qCDebug(CameraControlLog) << " captures video:" << capturesVideo();
154 qCDebug(CameraControlLog) << " captures photos:" << capturesPhotos();
155 qCDebug(CameraControlLog) << " has modes:" << hasModes();
156 qCDebug(CameraControlLog) << " has zoom:" << hasZoom();
157 qCDebug(CameraControlLog) << " has focus:" << hasFocus();
158 qCDebug(CameraControlLog) << " has tracking:" << hasTracking();
159 qCDebug(CameraControlLog) << " has video stream:" << hasVideoStream();
160 qCDebug(CameraControlLog) << " photos in video mode:" << photosInVideoMode();
161 qCDebug(CameraControlLog) << " video in photo mode:" << videoInPhotoMode();
162}
163
165{
166 // Stop all timers to prevent them from firing during or after destruction
167 _captureStatusTimer.stop();
169 _streamInfoTimer.stop();
170 _streamStatusTimer.stop();
172 _storageInfoTimer.stop();
173
174 delete _netManager;
175 _netManager = nullptr;
176}
177
179{
180 qCDebug(CameraControlLog) << "_initWhenReady()";
181 if(isBasic()) {
182 qCDebug(CameraControlLog) << "Basic, MAVLink only messages, no parameters.";
183 //-- Basic cameras have no parameters
184 _paramComplete = true;
185 emit parametersReady();
186 } else {
188 }
189
190 QTimer::singleShot(500, this, &VehicleCameraControl::_requestCameraSettings);
191 connect(&_cameraSettingsTimer, &QTimer::timeout, this, &VehicleCameraControl::_cameraSettingsTimeout);
192
193 QTimer::singleShot(1000, this, &VehicleCameraControl::_checkForVideoStreams);
194
196
197 connect(&_captureStatusTimer, &QTimer::timeout, this, &VehicleCameraControl::_requestCaptureStatus);
198 _captureStatusTimer.setSingleShot(true);
199 _captureStatusTimer.start(1500);
200
201 connect(&_storageInfoTimer, &QTimer::timeout, this, &VehicleCameraControl::_storageInfoTimeout);
202 QTimer::singleShot(2000, this, &VehicleCameraControl::_requestStorageInfo);
203
204 connect(VideoManager::instance(), &VideoManager::recordingChanged, this, &VehicleCameraControl::captureVideoStateChanged);
211
212 emit infoChanged();
213
214 delete _netManager;
215 _netManager = nullptr;
216}
217
219{
220 // Even if the camera itself does not report video capture capability
221 // we can always save locally from a video stream, or use onboard recording
222 // if the camera reports video capture capability.
223 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_VIDEO | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
224}
225
227{
228 // If we have a video stream we can always screen grab from it,
229 //even if the camera itself does not report still capture capability.
230 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_IMAGE | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
231}
232
234{
235 if (_videoCaptureStatus() == VIDEO_CAPTURE_STATUS_RUNNING || VideoManager::instance()->recording()) {
237 } else if (_photoCaptureStatus() != PHOTO_CAPTURE_IDLE) {
240 // The ui is not set up to support recording video while in photo/survey mode, even if the camera technically supports it.
242 } else if (_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM || _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO) {
244 }
245
247}
248
250{
255 } else if (_photoCaptureStatus() == PHOTO_CAPTURE_IDLE) {
256 // We can always do at least a screen grab from the video stream, even if camera doesn't report still capture capability
257 if (_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM || _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE) {
259 }
260 }
261
263}
264
266{
267 int major = (_mavlinkCameraInfo.firmware_version >> 24) & 0xFF;
268 int minor = (_mavlinkCameraInfo.firmware_version >> 16) & 0xFF;
269 int build = _mavlinkCameraInfo.firmware_version & 0xFFFF;
270 return QString::asprintf("%d.%d.%d", major, minor, build);
271}
272
274{
275 return QTime(0, 0).addMSecs(static_cast<int>(recordTime())).toString("hh:mm:ss");
276}
277
279{
280 return qgcApp()->bigSizeMBToString(static_cast<quint64>(_storageFree));
281}
282
284{
285 if(_batteryRemaining >= 0) {
286 return qgcApp()->numberToString(static_cast<quint64>(_batteryRemaining)) + " %";
287 }
288 return "";
289}
290
292{
293 if (_resetting) {
294 return;
295 }
296 if (!hasModes()) {
297 qCWarning(CameraControlLog) << "Camera does not support modes";
298 return;
299 }
300
301 qCDebug(CameraControlLog) << "Camera set to video mode";
303}
304
306{
307 if (_resetting) {
308 return;
309 }
310 if (!hasModes()) {
311 qCWarning(CameraControlLog) << "Camera does not support modes";
312 return;
313 }
314
315 qCDebug(CameraControlLog) << "Camera set to photo mode";
317}
318
320{
321 if (_resetting) {
322 return;
323 }
324 if (!hasModes()) {
325 qCWarning(CameraControlLog) << "Camera does not support modes";
326 return;
327 }
329 qCWarning(CameraControlLog) << "Invalid camera mode" << cameraMode;
330 return;
331 }
332 if (_cameraMode == cameraMode) {
333 return;
334 }
335
336 qCDebug(CameraControlLog) << "Camera mode set to" << cameraModeToStr(cameraMode);
337
338 //-- Does it have a mode parameter?
339 Fact* pMode = mode();
340 if(pMode) {
341 pMode->setRawValue(cameraMode);
343 } else {
344 //-- Use MAVLink Command
346 _compID, // Target component
347 MAV_CMD_SET_CAMERA_MODE, // Command id
348 true, // ShowError
349 0, // Reserved (Set to 0)
350 cameraMode); // Camera mode (0: photo, 1: video)
352 }
353}
354
356{
357 if(!_resetting) {
359 QSettings settings;
360 settings.setValue(kPhotoMode, static_cast<int>(mode));
362 }
363}
364
366{
367 _photoLapse = interval;
368 QSettings settings;
369 settings.setValue(kPhotoLapse, interval);
370 emit photoLapseChanged();
371}
372
374{
375 _photoLapseCount = count;
376 QSettings settings;
377 settings.setValue(kPhotoLapseCount, count);
379}
380
382{
383 if(_cameraMode != mode) {
385 emit cameraModeChanged();
386 //-- Update stream status
387 _streamStatusTimer.start(1000);
388 }
389}
390
401
403{
404 if(_resetting) {
405 return false;
406 }
407
409 return stopVideoRecording();
410 } else {
411 return startVideoRecording();
412 }
413
414 return false;
415}
416
418{
419 if (_resetting) {
420 return false;
421 }
423 qCWarning(CameraControlLog) << "Take photo denied - photo capture is disabled";
424 return false;
425 }
427 qCWarning(CameraControlLog) << "Take photo denied - already capturing";
428 return false;
429 }
430
431 qCDebug(CameraControlLog) << "takePhoto()";
432
433 const bool canUseMavlinkImageCapture =
434 (_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE) &&
436
437 if (canUseMavlinkImageCapture) {
439 _compID,
440 MAV_CMD_IMAGE_START_CAPTURE,
441 true, // ShowError
442 0, // All cameras
443 static_cast<float>(_photoCaptureMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image)
444 _photoCaptureMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture
447 return true;
448 } else {
450 VideoManager::instance()->grabImage();
452 QTimer::singleShot(500, this, [this]() {
454 });
455 return true;
456 } else {
457 qgcApp()->showAppMessage(tr("Timelapse photo capture is not supported on cameras without still capture capability"));
458 }
459 }
460
461 return false;
462}
463
465{
466 if (_resetting) {
467 return false;
468 }
470 qCWarning(CameraControlLog) << "Stop taking photos requested - not currently capturing multiple photos";
471 return false;
472 }
473
474 qCDebug(CameraControlLog) << "Camera stop taking photos";
475
476 // Interval capture is only supported directly by cameras
478 _compID, // Target component
479 MAV_CMD_IMAGE_STOP_CAPTURE,
480 true, // ShowError
481 0); // All cameras
484
485 return true;
486}
487
489{
490 if (_resetting) {
491 return false;
492 }
494 qCWarning(CameraControlLog) << "Start video denied - already recording";
495 return false;
496 }
498 qCWarning(CameraControlLog) << "Start video denied - video capture is disabled";
499 return false;
500 }
501
502 bool useMavlinkCommand = _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
503
504 qCDebug(CameraControlLog) << "Start video recording:" << (useMavlinkCommand ? "MAVLink command" : "VideoManager");
505
506 if (useMavlinkCommand) {
508 _compID, // Target component
509 MAV_CMD_VIDEO_START_CAPTURE,
510 true, // Show error on failure
511 0, // All streams
512 0, // CAMERA_CAPTURE_STATUS streaming frequency
513 0); // All cameras
514 } else {
515 VideoManager::instance()->startRecording();
516 }
517
518 return true;
519}
520
522{
523 if (_resetting) {
524 return false;
525 }
527 qCWarning(CameraControlLog) << "Stop video recording requested - already idle";
528 return true;
529 }
530
531 bool useMavlinkCommand = _mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
532
533 qCDebug(CameraControlLog) << "Camera stop video recording" << (useMavlinkCommand ? "MAVLink command" : "VideoManager");
534
535 if (useMavlinkCommand) {
537 _compID, // Target component
538 MAV_CMD_VIDEO_STOP_CAPTURE,
539 true, // Show error on failure
540 0, // All streams
541 0); // All cameras
542 } else {
543 VideoManager::instance()->stopRecording();
544 }
545
546 return true;
547}
548
550{
551 QSettings settings;
552 settings.setValue(kThermalMode, static_cast<uint32_t>(mode));
554 emit thermalModeChanged();
555}
556
558{
559 if(val < 0.0) val = 0.0;
560 if(val > 100.0) val = 100.0;
561 if(fabs(_thermalOpacity - val) > 0.1) {
562 _thermalOpacity = val;
563 QSettings settings;
564 settings.setValue(kThermalOpacity, val);
566 }
567}
568
570{
571 qCDebug(CameraControlLog) << "Camera set zoom level to" << level;
572 if(hasZoom()) {
573 //-- Limit
574 level = std::min(std::max(level, 0.0), 100.0);
575 if(_vehicle) {
577 _compID, // Target component
578 MAV_CMD_SET_CAMERA_ZOOM, // Command id
579 false, // ShowError
580 ZOOM_TYPE_RANGE, // Zoom type
581 static_cast<float>(level)); // Level
582 }
583 }
584}
585
587{
588 qCDebug(CameraControlLog) << "Camera set focus level to" << level;
589 if(hasFocus()) {
590 //-- Limit
591 level = std::min(std::max(level, 0.0), 100.0);
592 if(_vehicle) {
594 _compID, // Target component
595 MAV_CMD_SET_CAMERA_FOCUS, // Command id
596 false, // ShowError
597 FOCUS_TYPE_RANGE, // Focus type
598 static_cast<float>(level)); // Level
599 }
600 }
601}
602
604{
605 if(!_resetting) {
606 qCDebug(CameraControlLog) << "resetSettings()";
607 _resetting = true;
609 _compID, // Target component
610 MAV_CMD_RESET_CAMERA_SETTINGS, // Command id
611 true, // ShowError
612 1); // Do Reset
613 }
614}
615
617{
618 if(!_resetting) {
619 qCDebug(CameraControlLog) << "formatCard()";
620 if(_vehicle) {
622 _compID, // Target component
623 MAV_CMD_STORAGE_FORMAT, // Command id
624 true, // ShowError
625 id, // Storage ID (1 for first, 2 for second, etc.)
626 1); // Do Format
627 }
628 }
629}
630
632{
633 qCDebug(CameraControlLog) << "Camera step zoom" << direction;
634 if(_vehicle && hasZoom()) {
636 _compID, // Target component
637 MAV_CMD_SET_CAMERA_ZOOM, // Command id
638 false, // ShowError
639 ZOOM_TYPE_STEP, // Zoom type
640 direction); // Direction (-1 wide, 1 tele)
641 }
642}
643
645{
646 qCDebug(CameraControlLog) << "Camera start zoom" << direction;
647 if(_vehicle && hasZoom()) {
649 _compID, // Target component
650 MAV_CMD_SET_CAMERA_ZOOM, // Command id
651 false, // ShowError
652 ZOOM_TYPE_CONTINUOUS, // Zoom type
653 direction); // Direction (-1 wide, 1 tele)
654 }
655}
656
658{
659 qCDebug(CameraControlLog) << "Camera stop zoom";
660 if(_vehicle && hasZoom()) {
662 _compID, // Target component
663 MAV_CMD_SET_CAMERA_ZOOM, // Command id
664 false, // ShowError
665 ZOOM_TYPE_CONTINUOUS, // Zoom type
666 0); // Direction (-1 wide, 1 tele)
667 }
668}
669
671{
672 qCDebug(CameraControlLog) << "Camera request capture status - retries:" << _cameraCaptureStatusRetries;
673
674 if(_cameraCaptureStatusRetries++ % 2 == 0) {
675 qCDebug(CameraControlLog) << " Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS";
677 _compID, // target component
678 MAV_CMD_REQUEST_MESSAGE, // command id
679 false, // showError
680 MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS); // msgid
681 } else {
682 qCDebug(CameraControlLog) << " Sending MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (legacy)";
684 _compID, // target component
685 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, // command id
686 false, // showError
687 1); // Do Request
688 }
689}
690
692{
693 _updateActiveList();
694 _updateRanges(pFact);
695}
696
697void VehicleCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
698{
699 Q_UNUSED(failureCode);
700
701 //-- Is this ours?
702 if (_vehicle->id() != vehicleId || compID() != component) {
703 return;
704 }
705 if (result == MAV_RESULT_IN_PROGRESS) {
706 //-- Do Nothing
707 qCDebug(CameraControlLog) << "In progress response for" << command;
708 } else if(result == MAV_RESULT_ACCEPTED) {
709 switch(command) {
710 case MAV_CMD_RESET_CAMERA_SETTINGS:
711 _resetting = false;
712 if(isBasic()) {
714 } else {
715 QTimer::singleShot(500, this, &VehicleCameraControl::_requestAllParameters);
716 QTimer::singleShot(2500, this, &VehicleCameraControl::_requestCameraSettings);
717 }
718 break;
719 case MAV_CMD_VIDEO_START_CAPTURE:
721 _captureStatusTimer.start(1000);
722 break;
723 case MAV_CMD_VIDEO_STOP_CAPTURE:
725 _captureStatusTimer.start(1000);
726 break;
727 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
729 break;
730 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
732 break;
733 case MAV_CMD_IMAGE_START_CAPTURE:
734 _captureStatusTimer.start(1000);
735 break;
736 }
737 } else {
738 QString commandStr = MissionCommandTree::instance()->rawName(static_cast<MAV_CMD>(command));
739 if ((result == MAV_RESULT_TEMPORARILY_REJECTED) || (result == MAV_RESULT_FAILED)) {
740 if (result == MAV_RESULT_TEMPORARILY_REJECTED) {
741 qCDebug(CameraControlLog) << "Command temporarily rejected (MAV_RESULT_TEMPORARILY_REJECTED) for" << commandStr;
742 } else {
743 qCDebug(CameraControlLog) << "Command failed (MAV_RESULT_FAILED) for" << commandStr;
744 }
745 switch(command) {
746 case MAV_CMD_RESET_CAMERA_SETTINGS:
747 _resetting = false;
748 qCDebug(CameraControlLog) << "Failed to reset camera settings";
749 break;
750 case MAV_CMD_IMAGE_START_CAPTURE:
751 case MAV_CMD_IMAGE_STOP_CAPTURE:
752 if(++_captureInfoRetries <= 5) {
753 _captureStatusTimer.start(1000);
754 } else {
755 qCDebug(CameraControlLog) << "Giving up start/stop image capture";
757 }
758 break;
759 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
760 if(++_cameraCaptureStatusRetries <= 5) {
761 _captureStatusTimer.start(1000);
762 } else {
763 qCDebug(CameraControlLog) << "Giving up requesting capture status";
764 }
765 break;
766 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
767 if(++_storageInfoRetries <= 5) {
768 QTimer::singleShot(1000, this, &VehicleCameraControl::_requestStorageInfo);
769 } else {
770 qCDebug(CameraControlLog) << "Giving up requesting storage status";
771 }
772 break;
773 }
774 } else {
775 qCDebug(CameraControlLog) << "Bad response for" << commandStr << QGCMAVLink::mavResultToString(result);
776 }
777 }
778}
779
781{
782 if(_videoCaptureStatusValue != captureStatus) {
783 _videoCaptureStatusValue = captureStatus;
785 if(captureStatus == VIDEO_CAPTURE_STATUS_RUNNING) {
786 _recordTime = 0;
787 _recTime = QTime::currentTime();
789 } else {
791 _recordTime = 0;
792 emit recordTimeChanged();
793 }
794 }
795}
796
798{
799 _recordTime = static_cast<uint32_t>(_recTime.msecsTo(QTime::currentTime()));
800 emit recordTimeChanged();
801}
802
804{
805 // Only track time here when not using MAVLink video capture (to avoid double-tracking)
807 return;
808 }
809
810 if (recording) {
811 _recordTime = 0;
812 _recTime = QTime::currentTime();
814 } else {
816 _recordTime = 0;
817 emit recordTimeChanged();
818 }
819}
820
822{
823 if(_photoCaptureStatusValue != captureStatus) {
824 qCDebug(CameraControlLog) << "Set Photo Status:" << captureStatus;
825 _photoCaptureStatusValue = captureStatus;
827 }
828}
829
830bool VehicleCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
831{
832 QByteArray originalData(bytes);
833 //-- Handle localization
834 if(!_handleLocalization(bytes)) {
835 return false;
836 }
837
838 QDomDocument doc;
839 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
840 if (!result) {
841 qCCritical(CameraControlLog) << "Unable to parse camera definition file on line:" << result.errorLine;
842 qCCritical(CameraControlLog) << result.errorMessage;
843 return false;
844 }
845 //-- Load camera constants
846 QDomNodeList defElements = doc.elementsByTagName(kDefnition);
847 if(!defElements.size() || !_loadConstants(defElements)) {
848 qCWarning(CameraControlLog) << "Unable to load camera constants from camera definition";
849 return false;
850 }
851 //-- Load camera parameters
852 QDomNodeList paramElements = doc.elementsByTagName(kParameters);
853 if(!paramElements.size()) {
854 qCDebug(CameraControlLog) << "No parameters to load from camera";
855 return false;
856 }
857 if(!_loadSettings(paramElements)) {
858 qCWarning(CameraControlLog) << "Unable to load camera parameters from camera definition";
859 return false;
860 }
861 //-- If this is new, cache it
862 if(!_cached) {
863 qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
864 QFile file(_cacheFile);
865 if (!file.open(QIODevice::WriteOnly)) {
866 qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
867 } else {
868 file.write(originalData);
869 }
870 }
871 return true;
872}
873
874bool VehicleCameraControl::_loadConstants(const QDomNodeList nodeList)
875{
876 QDomNode node = nodeList.item(0);
877 if(!read_attribute(node, kVersion, _version)) {
878 return false;
879 }
880 if(!read_value(node, kModel, _modelName)) {
881 return false;
882 }
883 if(!read_value(node, kVendor, _vendor)) {
884 return false;
885 }
886 return true;
887}
888
889bool VehicleCameraControl::_loadSettings(const QDomNodeList nodeList)
890{
891 QDomNode node = nodeList.item(0);
892 QDomElement elem = node.toElement();
893 QDomNodeList parameters = elem.elementsByTagName(kParameter);
894 //-- Pre-process settings (maintain order and skip non-controls)
895 for(int i = 0; i < parameters.size(); i++) {
896 QDomNode parameterNode = parameters.item(i);
897 QString name;
898 if(read_attribute(parameterNode, kName, name)) {
899 bool control = true;
900 read_attribute(parameterNode, kControl, control);
901 if(control) {
902 _settings << name;
903 }
904 } else {
905 qCritical() << "Parameter entry missing parameter name";
906 return false;
907 }
908 }
909 //-- Load parameters
910 for(int i = 0; i < parameters.size(); i++) {
911 QDomNode parameterNode = parameters.item(i);
912 QString factName;
913 read_attribute(parameterNode, kName, factName);
914 QString type;
915 if(!read_attribute(parameterNode, kType, type)) {
916 qCritical() << QString("Parameter %1 missing parameter type").arg(factName);
917 return false;
918 }
919 //-- Does it have a control?
920 bool control = true;
921 read_attribute(parameterNode, kControl, control);
922 //-- Is it read only?
923 bool readOnly = false;
924 read_attribute(parameterNode, kReadOnly, readOnly);
925 //-- Is it write only?
926 bool writeOnly = false;
927 read_attribute(parameterNode, kWriteOnly, writeOnly);
928 //-- It can't be both
929 if(readOnly && writeOnly) {
930 qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName);
931 }
932 //-- Param type
933 bool unknownType;
934 FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
935 if (unknownType) {
936 qCritical() << QString("Unknown type for parameter %1").arg(factName);
937 return false;
938 }
939 //-- By definition, custom types do not have control
940 if(factType == FactMetaData::valueTypeCustom) {
941 control = false;
942 }
943 //-- Description
944 QString description;
945 if(!read_value(parameterNode, kDescription, description)) {
946 qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
947 return false;
948 }
949 //-- Check for updates
950 QStringList updates = _loadUpdates(parameterNode);
951 if(updates.size()) {
952 qCDebug(CameraControlVerboseLog) << "Parameter" << factName << "requires updates for:" << updates;
953 _requestUpdates[factName] = updates;
954 }
955 //-- Build metadata
956 FactMetaData* metaData = new FactMetaData(factType, factName, this);
957 QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
958 metaData->setShortDescription(description);
959 metaData->setLongDescription(description);
960 metaData->setHasControl(control);
961 metaData->setReadOnly(readOnly);
962 metaData->setWriteOnly(writeOnly);
963 //-- Options (enums)
964 QDomElement optionElem = parameterNode.toElement();
965 QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
966 if(optionsRoot.size()) {
967 //-- Iterate options
968 QDomNode optionsNode = optionsRoot.item(0);
969 QDomElement optionsElem = optionsNode.toElement();
970 QDomNodeList options = optionsElem.elementsByTagName(kOption);
971 for(int optionIndex = 0; optionIndex < options.size(); optionIndex++) {
972 QDomNode option = options.item(optionIndex);
973 QString optName;
974 QString optValue;
975 QVariant optVariant;
976 if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
977 delete metaData;
978 return false;
979 }
980 metaData->addEnumInfo(optName, optVariant);
981 _originalOptNames[factName] << optName;
982 _originalOptValues[factName] << optVariant;
983 //-- Check for exclusions
984 QStringList exclusions = _loadExclusions(option);
985 if(exclusions.size()) {
986 qCDebug(CameraControlVerboseLog) << "New exclusions:" << factName << optValue << exclusions;
987 QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions);
988 QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
989 _valueExclusions.append(pExc);
990 }
991 //-- Check for range rules
992 if(!_loadRanges(option, factName, optValue)) {
993 delete metaData;
994 return false;
995 }
996 }
997 }
998 QString defaultValue;
999 if(read_attribute(parameterNode, kDefault, defaultValue)) {
1000 QVariant defaultVariant;
1001 QString errorString;
1002 if (metaData->convertAndValidateRaw(defaultValue, false, defaultVariant, errorString)) {
1003 metaData->setRawDefaultValue(defaultVariant);
1004 } else {
1005 qWarning() << "Invalid default value for" << factName
1006 << " type:" << metaData->type()
1007 << " value:" << defaultValue
1008 << " error:" << errorString;
1009 }
1010 }
1011 //-- Set metadata and Fact
1012 if (_nameToFactMetaDataMap.contains(factName)) {
1013 qWarning() << QStringLiteral("Duplicate fact name:") << factName;
1014 delete metaData;
1015 } else {
1016 {
1017 //-- Check for Min Value
1018 QString attr;
1019 if(read_attribute(parameterNode, kMin, attr)) {
1020 QVariant typedValue;
1021 QString errorString;
1022 if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
1023 metaData->setRawMin(typedValue);
1024 } else {
1025 qWarning() << "Invalid min value for" << factName
1026 << " type:" << metaData->type()
1027 << " value:" << attr
1028 << " error:" << errorString;
1029 }
1030 }
1031 }
1032 {
1033 //-- Check for Max Value
1034 QString attr;
1035 if(read_attribute(parameterNode, kMax, attr)) {
1036 QVariant typedValue;
1037 QString errorString;
1038 if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
1039 metaData->setRawMax(typedValue);
1040 } else {
1041 qWarning() << "Invalid max value for" << factName
1042 << " type:" << metaData->type()
1043 << " value:" << attr
1044 << " error:" << errorString;
1045 }
1046 }
1047 }
1048 {
1049 //-- Check for Step Value
1050 QString attr;
1051 if(read_attribute(parameterNode, kStep, attr)) {
1052 QVariant typedValue;
1053 QString errorString;
1054 if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
1055 metaData->setRawIncrement(typedValue.toDouble());
1056 } else {
1057 qWarning() << "Invalid step value for" << factName
1058 << " type:" << metaData->type()
1059 << " value:" << attr
1060 << " error:" << errorString;
1061 }
1062 }
1063 }
1064 {
1065 //-- Check for Decimal Places
1066 QString attr;
1067 if(read_attribute(parameterNode, kDecimalPlaces, attr)) {
1068 QVariant typedValue;
1069 QString errorString;
1070 if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
1071 metaData->setDecimalPlaces(typedValue.toInt());
1072 } else {
1073 qWarning() << "Invalid decimal places value for" << factName
1074 << " type:" << metaData->type()
1075 << " value:" << attr
1076 << " error:" << errorString;
1077 }
1078 }
1079 }
1080 {
1081 //-- Check for Units
1082 QString attr;
1083 if(read_attribute(parameterNode, kUnit, attr)) {
1084 metaData->setRawUnits(attr);
1085 }
1086 }
1087 qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable");
1088 _nameToFactMetaDataMap[factName] = metaData;
1089 Fact* pFact = new Fact(_compID, factName, factType, this);
1090 QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
1091 pFact->setMetaData(metaData);
1092 pFact->containerSetRawValue(metaData->rawDefaultValue());
1093 QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle);
1094 QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
1095 _paramIO[factName] = pIO;
1096 _addFact(pFact, factName);
1097 }
1098 }
1099 if(_nameToFactMetaDataMap.size() > 0) {
1100 _addFactGroup(this, "camera");
1101 _processRanges();
1103 emit activeSettingsChanged();
1104 return true;
1105 }
1106 return false;
1107}
1108
1109bool VehicleCameraControl::_handleLocalization(QByteArray& bytes)
1110{
1111 QDomDocument doc;
1112 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
1113 if (!result) {
1114 qCritical() << "Unable to parse camera definition file on line:" << result.errorLine;
1115 qCritical() << result.errorMessage;
1116 return false;
1117 }
1118 //-- Find out where we are
1119 QLocale locale = QLocale::system();
1120#if defined (Q_OS_MACOS)
1121 locale = QLocale(locale.name());
1122#endif
1123 QString localeName = locale.name().toLower().replace("-", "_");
1124 qCDebug(CameraControlLog) << "Current locale:" << localeName;
1125 if(localeName == "en_us") {
1126 // Nothing to do
1127 return true;
1128 }
1129 QDomNodeList locRoot = doc.elementsByTagName(kLocalization);
1130 if(!locRoot.size()) {
1131 // Nothing to do
1132 return true;
1133 }
1134 //-- Iterate locales
1135 QDomNode node = locRoot.item(0);
1136 QDomElement elem = node.toElement();
1137 QDomNodeList locales = elem.elementsByTagName(kLocale);
1138 for(int i = 0; i < locales.size(); i++) {
1139 QDomNode localeNode = locales.item(i);
1140 QString name;
1141 if(!read_attribute(localeNode, kName, name)) {
1142 qWarning() << "Localization entry is missing its name attribute";
1143 continue;
1144 }
1145 // If we found a direct match, deal with it now
1146 if(localeName == name.toLower().replace("-", "_")) {
1147 return _replaceLocaleStrings(localeNode, bytes);
1148 }
1149 }
1150 //-- No direct match. Pick first matching language (if any)
1151 localeName = localeName.left(3);
1152 for(int i = 0; i < locales.size(); i++) {
1153 QDomNode localeNode = locales.item(i);
1154 QString name;
1155 read_attribute(localeNode, kName, name);
1156 if(name.toLower().startsWith(localeName)) {
1157 return _replaceLocaleStrings(localeNode, bytes);
1158 }
1159 }
1160 //-- Could not find a language to use
1161 qWarning() << "No match for" << QLocale::system().name() << "in camera definition file";
1162 //-- Just use default, en_US
1163 return true;
1164}
1165
1166bool VehicleCameraControl::_replaceLocaleStrings(const QDomNode node, QByteArray& bytes)
1167{
1168 QDomElement stringElem = node.toElement();
1169 QDomNodeList strings = stringElem.elementsByTagName(kStrings);
1170 for(int i = 0; i < strings.size(); i++) {
1171 QDomNode stringNode = strings.item(i);
1172 QString original;
1173 QString translated;
1174 if(read_attribute(stringNode, kOriginal, original)) {
1175 if(read_attribute(stringNode, kTranslated, translated)) {
1176 QString o; o = "\"" + original + "\"";
1177 QString t; t = "\"" + translated + "\"";
1178 bytes.replace(o.toUtf8(), t.toUtf8());
1179 o = ">" + original + "<";
1180 t = ">" + translated + "<";
1181 bytes.replace(o.toUtf8(), t.toUtf8());
1182 }
1183 }
1184 }
1185 return true;
1186}
1187
1189{
1190 //-- Reset receive list
1191 for(const QString& paramName: _paramIO.keys()) {
1192 if(_paramIO[paramName]) {
1193 _paramIO[paramName]->setParamRequest();
1194 } else {
1195 qCritical() << "QGCParamIO is NULL" << paramName;
1196 }
1197 }
1199 if (sharedLink) {
1201 mavlink_msg_param_ext_request_list_pack_chan(
1202 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
1203 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
1204 sharedLink->mavlinkChannel(),
1205 &msg,
1206 static_cast<uint8_t>(_vehicle->id()),
1207 static_cast<uint8_t>(compID()));
1208 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
1209 }
1210 qCDebug(CameraControlVerboseLog) << "Request all parameters";
1211}
1212
1213QString VehicleCameraControl::_getParamName(const char* param_id)
1214{
1215 // This will null terminate the name string
1216 char parameterNameWithNull[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1] = {};
1217 (void) strncpy(parameterNameWithNull, param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
1218 const QString parameterName(parameterNameWithNull);
1219 return parameterName;
1220}
1221
1222void VehicleCameraControl::handleParamExtAck(const mavlink_param_ext_ack_t& paramExtAck)
1223{
1224 QString paramName = _getParamName(paramExtAck.param_id);
1225 qCDebug(CameraControlLog).noquote() << "Received PARAM_EXT_ACK:"
1226 << "\n\tParam name:" << paramName
1227 << "\n\tResult:" << static_cast<int>(paramExtAck.param_result)
1228 << "\n\tType:" << static_cast<int>(paramExtAck.param_type);
1229
1230 if(!_paramIO.contains(paramName)) {
1231 qCWarning(CameraControlLog) << "Received PARAM_EXT_ACK for unknown param:" << paramName;
1232 return;
1233 }
1234 if(_paramIO[paramName]) {
1235 _paramIO[paramName]->handleParamAck(paramExtAck);
1236 } else {
1237 qCritical() << "QGCParamIO is NULL" << paramName;
1238 }
1239}
1240
1241void VehicleCameraControl::handleParamExtValue(const mavlink_param_ext_value_t& paramExtValue)
1242{
1243 QString paramName = _getParamName(paramExtValue.param_id);
1244 qCDebug(CameraControlLog).noquote() << "Received PARAM_EXT_VALUE:"
1245 << "\n\tParam name:" << paramName
1246 << "\n\tType:" << static_cast<int>(paramExtValue.param_type)
1247 << "\n\tIndex:" << static_cast<int>(paramExtValue.param_index)
1248 << "\n\tCount:" << static_cast<int>(paramExtValue.param_count);
1249
1250 if(!_paramIO.contains(paramName)) {
1251 qCWarning(CameraControlLog) << "Received PARAM_EXT_VALUE for unknown param:" << paramName;
1252 return;
1253 }
1254 if(_paramIO[paramName]) {
1255 _paramIO[paramName]->handleParamValue(paramExtValue);
1256 } else {
1257 qCritical() << "QGCParamIO is NULL" << paramName;
1258 }
1259}
1260
1261void VehicleCameraControl::_updateActiveList()
1262{
1263 //-- Clear out excluded parameters based on exclusion rules
1264 QStringList exclusionList;
1266 Fact* pFact = getFact(param->param);
1267 if(pFact) {
1268 QString option = pFact->rawValueString();
1269 if(param->value == option) {
1270 exclusionList << param->exclusions;
1271 }
1272 }
1273 }
1274 QStringList active;
1275 for(QString key: _settings) {
1276 if(!exclusionList.contains(key)) {
1277 active.append(key);
1278 }
1279 }
1280 if(active != _activeSettings) {
1281 qCDebug(CameraControlVerboseLog) << "Excluding" << exclusionList;
1282 _activeSettings = active;
1283 emit activeSettingsChanged();
1284 //-- Force validity of "Facts" based on active set
1285 if(_paramComplete) {
1286 emit parametersReady();
1287 }
1288 }
1289}
1290
1291bool VehicleCameraControl::_processConditionTest(const QString conditionTest)
1292{
1293 enum {
1294 TEST_NONE,
1295 TEST_EQUAL,
1296 TEST_NOT_EQUAL,
1297 TEST_GREATER,
1298 TEST_SMALLER
1299 };
1300 qCDebug(CameraControlVerboseLog) << "_processConditionTest(" << conditionTest << ")";
1301 int op = TEST_NONE;
1302 QStringList test;
1303
1304 auto split = [&conditionTest](const QString& sep ) {
1305 return conditionTest.split(sep, Qt::SkipEmptyParts);
1306 };
1307
1308 if(conditionTest.contains("!=")) {
1309 test = split("!=");
1310 op = TEST_NOT_EQUAL;
1311 } else if(conditionTest.contains("=")) {
1312 test = split("=");
1313 op = TEST_EQUAL;
1314 } else if(conditionTest.contains(">")) {
1315 test = split(">");
1316 op = TEST_GREATER;
1317 } else if(conditionTest.contains("<")) {
1318 test = split("<");
1319 op = TEST_SMALLER;
1320 }
1321 if(test.size() == 2) {
1322 Fact* pFact = getFact(test[0]);
1323 if(pFact) {
1324 switch(op) {
1325 case TEST_EQUAL:
1326 return pFact->rawValueString() == test[1];
1327 case TEST_NOT_EQUAL:
1328 return pFact->rawValueString() != test[1];
1329 case TEST_GREATER:
1330 return pFact->rawValueString() > test[1];
1331 case TEST_SMALLER:
1332 return pFact->rawValueString() < test[1];
1333 case TEST_NONE:
1334 break;
1335 }
1336 } else {
1337 qWarning() << "Invalid condition parameter:" << test[0] << "in" << conditionTest;
1338 return false;
1339 }
1340 }
1341 qWarning() << "Invalid condition" << conditionTest;
1342 return false;
1343}
1344
1345bool VehicleCameraControl::_processCondition(const QString condition)
1346{
1347 qCDebug(CameraControlVerboseLog) << "_processCondition(" << condition << ")";
1348 bool result = true;
1349 bool andOp = true;
1350 if(!condition.isEmpty()) {
1351 QStringList scond = condition.split(" ", Qt::SkipEmptyParts);
1352 while(scond.size()) {
1353 QString test = scond.first();
1354 scond.removeFirst();
1355 if(andOp) {
1356 result = result && _processConditionTest(test);
1357 } else {
1358 result = result || _processConditionTest(test);
1359 }
1360 if(!scond.size()) {
1361 return result;
1362 }
1363 andOp = scond.first().toUpper() == "AND";
1364 scond.removeFirst();
1365 }
1366 }
1367 return result;
1368}
1369
1370void VehicleCameraControl::_updateRanges(Fact* pFact)
1371{
1372 QMap<Fact*, QGCCameraOptionRange*> rangesSet;
1373 QMap<Fact*, QString> rangesReset;
1374 QStringList changedList;
1375 QStringList resetList;
1376 QStringList updates;
1377 //-- Iterate range sets looking for limited ranges
1378 for(QGCCameraOptionRange* pRange: _optionRanges) {
1379 //-- If this fact or one of its conditions is part of this range set
1380 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
1381 Fact* pRFact = getFact(pRange->param); //-- This parameter
1382 Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
1383 if(pRFact && pTFact) {
1384 //qCDebug(CameraControlVerboseLog) << "Check new set of options for" << pTFact->name();
1385 QString option = pRFact->rawValueString(); //-- This parameter value
1386 //-- If this value (and condition) triggers a change in the target range
1387 //qCDebug(CameraControlVerboseLog) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
1388 if(pRange->value == option && _processCondition(pRange->condition)) {
1389 if(pTFact->enumStrings() != pRange->optNames) {
1390 //-- Set limited range set
1391 rangesSet[pTFact] = pRange;
1392 }
1393 changedList << pRange->targetParam;
1394 }
1395 }
1396 }
1397 }
1398 //-- Iterate range sets again looking for resets
1399 for(QGCCameraOptionRange* pRange: _optionRanges) {
1400 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
1401 Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
1402 if(!resetList.contains(pRange->targetParam)) {
1403 if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) {
1404 //-- Restore full option set
1405 rangesReset[pTFact] = pRange->targetParam;
1406 }
1407 resetList << pRange->targetParam;
1408 }
1409 }
1410 }
1411 //-- Update limited range set
1412 for (Fact* f: rangesSet.keys()) {
1413 f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
1414 if(!updates.contains(f->name())) {
1415 emit f->enumsChanged();
1416 qCDebug(CameraControlVerboseLog) << "Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
1417 updates << f->name();
1418 }
1419 }
1420 //-- Restore full range set
1421 for (Fact* f: rangesReset.keys()) {
1422 f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]);
1423 if(!updates.contains(f->name())) {
1424 emit f->enumsChanged();
1425 qCDebug(CameraControlVerboseLog) << "Restore full set of options for:" << f->name() << _originalOptNames[f->name()];
1426 updates << f->name();
1427 }
1428 }
1429 //-- Parameter update requests
1430 if(_requestUpdates.contains(pFact->name())) {
1431 for(const QString& param: _requestUpdates[pFact->name()]) {
1432 if(!_updatesToRequest.contains(param)) {
1433 _updatesToRequest << param;
1434 }
1435 }
1436 }
1437 if(_updatesToRequest.size()) {
1438 QTimer::singleShot(500, this, &VehicleCameraControl::_requestParamUpdates);
1439 }
1440}
1441
1443{
1444 for(const QString& param: _updatesToRequest) {
1445 _paramIO[param]->paramRequest();
1446 }
1447 _updatesToRequest.clear();
1448}
1449
1451{
1452 qCDebug(CameraControlLog) << "_requestCameraSettings() - retries:" << _cameraSettingsRetries << "timer active:" << _cameraSettingsTimer.isActive();
1453 if(_vehicle) {
1454 // Use REQUEST_MESSAGE instead of deprecated REQUEST_CAMERA_SETTINGS
1455 // first time and every other time after that.
1456
1457 if(_cameraSettingsRetries % 2 == 0) {
1458 qCDebug(CameraControlLog) << " Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_SETTINGS";
1460 _compID, // target component
1461 MAV_CMD_REQUEST_MESSAGE, // command id
1462 false, // showError
1463 MAVLINK_MSG_ID_CAMERA_SETTINGS); // msgid
1464 } else {
1465 qCDebug(CameraControlLog) << " Sending MAV_CMD_REQUEST_CAMERA_SETTINGS (legacy)";
1467 _compID, // Target component
1468 MAV_CMD_REQUEST_CAMERA_SETTINGS, // command id
1469 false, // showError
1470 1); // Do Request
1471 }
1472 if(_cameraSettingsTimer.isActive()) {
1473 qCDebug(CameraControlLog) << "_requestCameraSettings() - RESTARTING already active timer";
1474 } else {
1475 qCDebug(CameraControlLog) << "_requestCameraSettings() - starting timer";
1476 }
1477 _cameraSettingsTimer.start(1000); // Wait up to a second for it
1478 }
1479
1480}
1481
1483{
1484 qCDebug(CameraControlLog) << "_requestStorageInfo() - retries:" << _storageInfoRetries << "timer active:" << _storageInfoTimer.isActive();
1485 if(_vehicle) {
1486 // Use REQUEST_MESSAGE instead of deprecated REQUEST_STORAGE_INFORMATION
1487 // first time and every other time after that.
1488 if(_storageInfoRetries % 2 == 0) {
1489 qCDebug(CameraControlLog) << " Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_STORAGE_INFORMATION";
1491 _compID, // target component
1492 MAV_CMD_REQUEST_MESSAGE, // command id
1493 false, // showError
1494 MAVLINK_MSG_ID_STORAGE_INFORMATION, // msgid
1495 0); // storage ID
1496 } else {
1497 qCDebug(CameraControlLog) << " Sending MAV_CMD_REQUEST_STORAGE_INFORMATION (legacy)";
1499 _compID, // Target component
1500 MAV_CMD_REQUEST_STORAGE_INFORMATION, // command id
1501 false, // showError
1502 0, // Storage ID (0 for all, 1 for first, 2 for second, etc.)
1503 1); // Do Request
1504 }
1505 qCDebug(CameraControlLog) << "_requestStorageInfo() - starting timer";
1506 _storageInfoTimer.start(1000); // Wait up to a second for it
1507 }
1508}
1509
1510void VehicleCameraControl::handleCameraSettings(const mavlink_camera_settings_t& settings)
1511{
1512 qCDebug(CameraControlLog).noquote() << "Received CAMERA_SETTINGS - stopping timer, resetting retries:"
1513 << "\n\tMode:" << settings.mode_id
1514 << "\n\tZoom level:" << settings.zoomLevel
1515 << "\n\tFocus level:" << settings.focusLevel;
1516
1517 _cameraSettingsTimer.stop();
1519
1520 _setCameraMode(static_cast<CameraMode>(settings.mode_id));
1521 qreal z = static_cast<qreal>(settings.zoomLevel);
1522 qreal f = static_cast<qreal>(settings.focusLevel);
1523 if(std::isfinite(z) && z != _zoomLevel) {
1524 _zoomLevel = z;
1525 emit zoomLevelChanged();
1526 }
1527 if(std::isfinite(f) && f != _focusLevel) {
1528 _focusLevel = f;
1529 emit focusLevelChanged();
1530 }
1531}
1532
1533void VehicleCameraControl::handleStorageInformation(const mavlink_storage_information_t& storageInformation)
1534{
1535 qCDebug(CameraControlLog) << "Received STORAGE_INFORMATION - stopping timer, resetting retries:"
1536 << "\n\tStorage id:" << storageInformation.storage_id
1537 << "\n\tStorage count:" << storageInformation.storage_count
1538 << "\n\tStatus:"<< storageStatusToStr(storageInformation.status)
1539 << "\n\tTotal capacity:" << storageInformation.total_capacity
1540 << "\n\tUsed capacity:" << storageInformation.used_capacity
1541 << "\n\tAvailable capacity:" << storageInformation.available_capacity;
1542
1543 _storageInfoTimer.stop();
1545
1546 if(storageInformation.status == STORAGE_STATUS_READY) {
1547 uint32_t t = static_cast<uint32_t>(storageInformation.total_capacity);
1548 if(_storageTotal != t) {
1549 _storageTotal = t;
1550 emit storageTotalChanged();
1551 }
1552 uint32_t a = static_cast<uint32_t>(storageInformation.available_capacity);
1553 if(_storageFree != a) {
1554 _storageFree = a;
1555 emit storageFreeChanged();
1556 }
1557 }
1558 if(_storageStatus != static_cast<StorageStatus>(storageInformation.status)) {
1559 _storageStatus = static_cast<StorageStatus>(storageInformation.status);
1560 emit storageStatusChanged();
1561 }
1562}
1563
1564void VehicleCameraControl::handleBatteryStatus(const mavlink_battery_status_t& bs)
1565{
1566 qCDebug(CameraControlLog).noquote() << "Received BATTERY_STATUS:"
1567 << "\n\tBattery remaining (%):" << bs.battery_remaining;
1568
1569 if(bs.battery_remaining >= 0 && _batteryRemaining != static_cast<int>(bs.battery_remaining)) {
1570 _batteryRemaining = static_cast<int>(bs.battery_remaining);
1572 }
1573}
1574
1575void VehicleCameraControl::handleCameraCaptureStatus(const mavlink_camera_capture_status_t& cameraCaptureStatus)
1576{
1577 qCDebug(CameraControlLog).noquote() << "Received CAMERA_CAPTURE_STATUS - stopping timer, resetting retries:"
1578 << "\n\tImage status:" << captureImageStatusToStr(cameraCaptureStatus.image_status)
1579 << "\n\tVideo status:" << captureVideoStatusToStr(cameraCaptureStatus.video_status)
1580 << "\n\tInterval:" << cameraCaptureStatus.image_interval
1581 << "\n\tRecording time (ms):" << cameraCaptureStatus.recording_time_ms
1582 << "\n\tCapacity:" << cameraCaptureStatus.available_capacity;
1583
1584 _captureStatusTimer.stop();
1586
1587 //-- Disk Free Space
1588 uint32_t a = static_cast<uint32_t>(cameraCaptureStatus.available_capacity);
1589 if(_storageFree != a) {
1590 _storageFree = a;
1591 emit storageFreeChanged();
1592 }
1593 //-- Do we have recording time?
1594 if(cameraCaptureStatus.recording_time_ms) {
1595 // Resync our _recTime timer to the time info received from the camera component
1596 _recordTime = cameraCaptureStatus.recording_time_ms;
1597 _recTime = _recTime.addMSecs(_recTime.msecsTo(QTime::currentTime()) - static_cast<int>(cameraCaptureStatus.recording_time_ms));
1598 emit recordTimeChanged();
1599 }
1600 //-- Video/Image Capture Status
1601 uint8_t vs = cameraCaptureStatus.video_status < static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_LAST) ? cameraCaptureStatus.video_status : static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_UNDEFINED);
1602 uint8_t ps = cameraCaptureStatus.image_status < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cameraCaptureStatus.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
1605 //-- Keep asking for it once in a while when recording
1607 _captureStatusTimer.start(5000);
1608 //-- Same while (single) image capture is busy
1610 _captureStatusTimer.start(1000);
1611 }
1612 //-- Time Lapse
1614 //-- Capture local image as well
1615 const QString photoDir = SettingsManager::instance()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
1617 const QString photoPath = photoDir + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
1618 VideoManager::instance()->grabImage(photoPath);
1619 }
1620}
1621
1622void VehicleCameraControl::handleVideoStreamInformation(const mavlink_video_stream_information_t& videoStreamInformation)
1623{
1624 qCDebug(CameraControlLog).noquote() << "Received VIDEO_STREAM_INFORMATION:"
1625 << "\n\tStream ID:" << videoStreamInformation.stream_id
1626 << "\n\tStream count:" << videoStreamInformation.count
1627 << "\n\tType:" << static_cast<int>(videoStreamInformation.type)
1628 << "\n\tFlags:" << Qt::hex << Qt::showbase << videoStreamInformation.flags << Qt::dec << Qt::noshowbase
1629 << "\n\tBitrate (bits/s):" << videoStreamInformation.bitrate
1630 << "\n\tFramerate (fps):" << videoStreamInformation.framerate
1631 << "\n\tResolution:" << videoStreamInformation.resolution_h << "x" << videoStreamInformation.resolution_v
1632 << "\n\tRotation (deg):" << videoStreamInformation.rotation
1633 << "\n\tHFOV (deg):" << videoStreamInformation.hfov
1634 << "\n\tURI:" << videoStreamInformation.uri;
1635
1636 _expectedCount = videoStreamInformation.count;
1637 if(!_findStream(videoStreamInformation.stream_id, false)) {
1638 qCDebug(CameraControlLog) << "Create stream handler for stream ID:" << videoStreamInformation.stream_id;
1639 QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(videoStreamInformation, this);
1640 QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
1641 _streams.append(pStream);
1642 //-- Thermal is handled separately and not listed
1643 if(!pStream->isThermal()) {
1644 _streamLabels.append(pStream->name());
1645 emit streamsChanged();
1646 emit streamLabelsChanged();
1647 } else {
1648 emit thermalStreamChanged();
1649 }
1650 }
1651 //-- Check for missing count
1652 if(_streams.count() < _expectedCount) {
1653 _streamInfoTimer.start(1000);
1654 } else if (_streamInfoTimer.isActive()) {
1655 //-- Done
1656 qCDebug(CameraControlLog) << "All stream handlers done";
1657 _streamInfoTimer.stop();
1659 emit autoStreamChanged();
1660 emit _vehicle->cameraManager()->streamChanged();
1661 }
1662}
1663
1664void VehicleCameraControl::handleVideoStreamStatus(const mavlink_video_stream_status_t& videoStreamStatus)
1665{
1666 qCDebug(CameraControlLog) << "Received VIDEO_STREAM_STATUS - stopping timer, resetting retries:"
1667 << "\n\tStream ID:" << videoStreamStatus.stream_id
1668 << "\n\tFlags:" << Qt::hex << Qt::showbase << videoStreamStatus.flags << Qt::dec << Qt::noshowbase
1669 << "\n\tBitrate (bits/s):" << videoStreamStatus.bitrate
1670 << "\n\tFramerate (fps):" << videoStreamStatus.framerate
1671 << "\n\tResolution: " << videoStreamStatus.resolution_h << "x" << videoStreamStatus.resolution_v
1672 << "\n\tRotation (deg):" << videoStreamStatus.rotation
1673 << "\n\tHFOV (deg):" << videoStreamStatus.hfov;
1674
1675 _streamStatusTimer.stop();
1677
1678 QGCVideoStreamInfo* pInfo = _findStream(videoStreamStatus.stream_id);
1679 if(pInfo) {
1680 pInfo->update(videoStreamStatus);
1681 }
1682}
1683
1684void VehicleCameraControl::handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t& trackingImageStatus)
1685{
1686 qCDebug(CameraControlLog).noquote() << "Received CAMERA_TRACKING_IMAGE_STATUS:"
1687 << "\n\tTracking status:" << static_cast<int>(trackingImageStatus.tracking_status)
1688 << "\n\tTracking mode:" << static_cast<int>(trackingImageStatus.tracking_mode)
1689 << "\n\tPoint:" << trackingImageStatus.point_x << "," << trackingImageStatus.point_y
1690 << "\n\tRectangle:" << trackingImageStatus.rec_top_x << "," << trackingImageStatus.rec_top_y
1691 << " -> " << trackingImageStatus.rec_bottom_x << "," << trackingImageStatus.rec_bottom_y
1692 << "\n\tRadius:" << trackingImageStatus.radius;
1693
1695
1696 if (_trackingImageStatus.tracking_status == 0 || !trackingEnabled()) {
1697 _trackingImageRect = {};
1698 qCDebug(CameraControlLog) << "Tracking off";
1699 } else {
1700 if (_trackingImageStatus.tracking_mode == 2) {
1701 _trackingImageRect = QRectF(QPointF(_trackingImageStatus.rec_top_x, _trackingImageStatus.rec_top_y),
1702 QPointF(_trackingImageStatus.rec_bottom_x, _trackingImageStatus.rec_bottom_y));
1703 } else {
1704 float r = _trackingImageStatus.radius;
1705 if (qIsNaN(r) || r <= 0 ) {
1706 r = 0.05f;
1707 }
1708 // Bottom is NAN so that we can draw perfect square using video aspect ratio
1709 _trackingImageRect = QRectF(QPointF(_trackingImageStatus.point_x - r, _trackingImageStatus.point_y - r),
1710 QPointF(_trackingImageStatus.point_x + r, NAN));
1711 }
1712 // get rectangle into [0..1] boundaries
1713 _trackingImageRect.setLeft(std::min(std::max(_trackingImageRect.left(), 0.0), 1.0));
1714 _trackingImageRect.setTop(std::min(std::max(_trackingImageRect.top(), 0.0), 1.0));
1715 _trackingImageRect.setRight(std::min(std::max(_trackingImageRect.right(), 0.0), 1.0));
1716 _trackingImageRect.setBottom(std::min(std::max(_trackingImageRect.bottom(), 0.0), 1.0));
1717
1718 qCDebug(CameraControlLog) << "Tracking Image Status [left:" << _trackingImageRect.left()
1719 << "top:" << _trackingImageRect.top()
1720 << "right:" << _trackingImageRect.right()
1721 << "bottom:" << _trackingImageRect.bottom() << "]";
1722 }
1723
1725}
1726
1728{
1729 if (stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) {
1731 if(pInfo) {
1732 qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri();
1733 //-- Stop current stream
1735 _compID, // Target component
1736 MAV_CMD_VIDEO_STOP_STREAMING, // Command id
1737 false, // ShowError
1738 pInfo->streamID()); // Stream ID
1739 }
1740 _currentStream = stream;
1741 pInfo = currentStreamInstance();
1742 if(pInfo) {
1743 //-- Start new stream
1744 qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri();
1746 _compID, // Target component
1747 MAV_CMD_VIDEO_START_STREAMING, // Command id
1748 false, // ShowError
1749 pInfo->streamID()); // Stream ID
1750 //-- Update stream status
1751 _requestStreamStatus(static_cast<uint8_t>(pInfo->streamID()));
1752 }
1753 emit currentStreamChanged();
1754 emit _vehicle->cameraManager()->streamChanged();
1755 }
1756}
1757
1759{
1761 if(pInfo) {
1762 //-- Stop current stream
1764 _compID, // Target component
1765 MAV_CMD_VIDEO_STOP_STREAMING, // Command id
1766 false, // ShowError
1767 pInfo->streamID()); // Stream ID
1768 }
1769}
1770
1772{
1774 if(pInfo) {
1775 //-- Start new stream
1777 _compID, // Target component
1778 MAV_CMD_VIDEO_START_STREAMING, // Command id
1779 false, // ShowError
1780 pInfo->streamID()); // Stream ID
1781 }
1782}
1783
1785{
1786 if(hasVideoStream()) {
1787 return _streams.count() > 0;
1788 }
1789 return false;
1790}
1791
1794{
1795 if(_currentStream < _streamLabels.count() && _streamLabels.count()) {
1797 return pStream;
1798 }
1799 return nullptr;
1800}
1801
1804{
1805 //-- For now, it will return the first thermal listed (if any)
1806 for(int i = 0; i < _streams.count(); i++) {
1807 if(_streams[i]) {
1808 QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
1809 if(pStream) {
1810 if(pStream->isThermal()) {
1811 return pStream;
1812 }
1813 }
1814 }
1815 }
1816 return nullptr;
1817}
1818
1820{
1821 qCDebug(CameraControlLog) << "_requestStreamInfo() - stream:" << streamID << "retries:" << _videoStreamInfoRetries;
1822 // By default, try to use new REQUEST_MESSAGE command instead of
1823 // deprecated MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION.
1824 if (_videoStreamInfoRetries % 2 == 0) {
1825 qCDebug(CameraControlLog) << " Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION";
1827 _compID, // target component
1828 MAV_CMD_REQUEST_MESSAGE, // command id
1829 false, // showError
1830 MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION, // msgid
1831 streamID); // stream ID
1832 } else {
1833 qCDebug(CameraControlLog) << " Sending MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (legacy)";
1835 _compID, // Target component
1836 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id
1837 false, // ShowError
1838 streamID); // Stream ID
1839 }
1840 _streamInfoTimer.start(1000); // Wait up to a second for it
1841}
1842
1844{
1845 qCDebug(CameraControlLog) << "_requestStreamStatus() - stream:" << streamID << "retries:" << _videoStreamStatusRetries;
1846 // By default, try to use new REQUEST_MESSAGE command instead of
1847 // deprecated MAV_CMD_REQUEST_VIDEO_STREAM_STATUS.
1848 if (_videoStreamStatusRetries % 2 == 0) {
1849 qCDebug(CameraControlLog) << " Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_STATUS";
1851 _compID, // target component
1852 MAV_CMD_REQUEST_MESSAGE, // command id
1853 false, // showError
1854 MAVLINK_MSG_ID_VIDEO_STREAM_STATUS, // msgid
1855 streamID); // stream id
1856 } else {
1857 qCDebug(CameraControlLog) << " Sending MAV_CMD_REQUEST_VIDEO_STREAM_STATUS (legacy)";
1859 _compID, // Target component
1860 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, // Command id
1861 false, // ShowError
1862 streamID); // Stream ID
1863 }
1864 _streamStatusTimer.start(1000); // Wait up to a second for it
1865}
1866
1869{
1870 for(int i = 0; i < _streams.count(); i++) {
1871 if(_streams[i]) {
1872 QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
1873 if(pStream) {
1874 if(pStream->streamID() == id) {
1875 return pStream;
1876 }
1877 } else {
1878 qCritical() << "Null QGCVideoStreamInfo instance";
1879 }
1880 }
1881 }
1882 if(report) {
1883 qWarning() << "Stream id not found:" << id;
1884 }
1885 return nullptr;
1886}
1887
1890{
1891 for(int i = 0; i < _streams.count(); i++) {
1892 if(_streams[i]) {
1893 QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
1894 if(pStream) {
1895 if(pStream->name() == name) {
1896 return pStream;
1897 }
1898 }
1899 }
1900 }
1901 return nullptr;
1902}
1903
1905{
1907 int count = _expectedCount * 6;
1908 if(_videoStreamInfoRetries > count) {
1909 qCWarning(CameraControlLog) << "Giving up requesting video stream info";
1910 _streamInfoTimer.stop();
1911 //-- If we have at least one stream, work with what we have.
1912 if(_streams.count()) {
1913 emit autoStreamChanged();
1914 emit _vehicle->cameraManager()->streamChanged();
1915 }
1916 return;
1917 }
1918 for(uint8_t i = 0; i < _expectedCount; i++) {
1919 //-- Stream ID starts at 1
1920 if(!_findStream(i+1, false)) {
1921 _requestStreamInfo(i+1);
1922 return;
1923 }
1924 }
1925}
1926
1928{
1931 qCWarning(CameraControlLog) << "Giving up requesting video stream status";
1932 _streamStatusTimer.stop();
1933 return;
1934 }
1936 if(pStream) {
1937 _requestStreamStatus(static_cast<uint8_t>(pStream->streamID()));
1938 }
1939}
1940
1942{
1944 qCDebug(CameraControlLog) << "_cameraSettingsTimeout() - retries now:" << _cameraSettingsRetries;
1945 if(_cameraSettingsRetries > 5) {
1946 qCWarning(CameraControlLog) << "Giving up requesting camera settings after" << _cameraSettingsRetries << "retries";
1947 _cameraSettingsTimer.stop();
1948 return;
1949 }
1950 qCDebug(CameraControlLog) << "_cameraSettingsTimeout() - calling _requestCameraSettings()";
1952}
1953
1955{
1957 qCDebug(CameraControlLog) << "_storageInfoTimeout() - retries now:" << _storageInfoRetries;
1958 if(_storageInfoRetries > 5) {
1959 qCWarning(CameraControlLog) << "Giving up requesting storage info after" << _storageInfoRetries << "retries";
1960 _storageInfoTimer.stop();
1961 return;
1962 }
1963 qCDebug(CameraControlLog) << "_storageInfoTimeout() - calling _requestStorageInfo()";
1965}
1966
1967QStringList
1968VehicleCameraControl::_loadExclusions(QDomNode option)
1969{
1970 QStringList exclusionList;
1971 QDomElement optionElem = option.toElement();
1972 QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
1973 if(excRoot.size()) {
1974 //-- Iterate exclusions
1975 QDomNode node = excRoot.item(0);
1976 QDomElement elem = node.toElement();
1977 QDomNodeList exclusions = elem.elementsByTagName(kExclusion);
1978 for(int i = 0; i < exclusions.size(); i++) {
1979 QString exclude = exclusions.item(i).toElement().text();
1980 if(!exclude.isEmpty()) {
1981 exclusionList << exclude;
1982 }
1983 }
1984 }
1985 return exclusionList;
1986}
1987
1988QStringList
1989VehicleCameraControl::_loadUpdates(QDomNode option)
1990{
1991 QStringList updateList;
1992 QDomElement optionElem = option.toElement();
1993 QDomNodeList updateRoot = optionElem.elementsByTagName(kUpdates);
1994 if(updateRoot.size()) {
1995 //-- Iterate updates
1996 QDomNode node = updateRoot.item(0);
1997 QDomElement elem = node.toElement();
1998 QDomNodeList updates = elem.elementsByTagName(kUpdate);
1999 for(int i = 0; i < updates.size(); i++) {
2000 QString update = updates.item(i).toElement().text();
2001 if(!update.isEmpty()) {
2002 updateList << update;
2003 }
2004 }
2005 }
2006 return updateList;
2007}
2008
2009bool VehicleCameraControl::_loadRanges(QDomNode option, const QString factName, QString paramValue)
2010{
2011 QDomElement optionElem = option.toElement();
2012 QDomNodeList rangeRoot = optionElem.elementsByTagName(kParameterranges);
2013 if(rangeRoot.size()) {
2014 QDomNode node = rangeRoot.item(0);
2015 QDomElement elem = node.toElement();
2016 QDomNodeList parameterRanges = elem.elementsByTagName(kParameterrange);
2017 //-- Iterate parameter ranges
2018 for(int i = 0; i < parameterRanges.size(); i++) {
2019 QString param;
2020 QString condition;
2021 QDomNode paramRange = parameterRanges.item(i);
2022 if(!read_attribute(paramRange, kParameter, param)) {
2023 qCritical() << QString("Malformed option range for parameter %1").arg(factName);
2024 return false;
2025 }
2026 read_attribute(paramRange, kCondition, condition);
2027 QDomElement pelem = paramRange.toElement();
2028 QDomNodeList rangeOptions = pelem.elementsByTagName(kRoption);
2029 QStringList optNames;
2030 QStringList optValues;
2031 //-- Iterate options
2032 for(int rangeOptionIndex = 0; rangeOptionIndex < rangeOptions.size(); rangeOptionIndex++) {
2033 QString optName;
2034 QString optValue;
2035 QDomNode roption = rangeOptions.item(rangeOptionIndex);
2036 if(!read_attribute(roption, kName, optName)) {
2037 qCritical() << QString("Malformed roption for parameter %1").arg(factName);
2038 return false;
2039 }
2040 if(!read_attribute(roption, kValue, optValue)) {
2041 qCritical() << QString("Malformed rvalue for parameter %1").arg(factName);
2042 return false;
2043 }
2044 optNames << optName;
2045 optValues << optValue;
2046 }
2047 if(optNames.size()) {
2048 QGCCameraOptionRange* pRange = new QGCCameraOptionRange(this, factName, paramValue, param, condition, optNames, optValues);
2049 _optionRanges.append(pRange);
2050 qCDebug(CameraControlVerboseLog) << "New range limit:" << factName << paramValue << param << condition << optNames << optValues;
2051 }
2052 }
2053 }
2054 return true;
2055}
2056
2057void VehicleCameraControl::_processRanges()
2058{
2059 //-- After all parameter are loaded, process parameter ranges
2060 for(QGCCameraOptionRange* pRange: _optionRanges) {
2061 Fact* pRFact = getFact(pRange->targetParam);
2062 if(pRFact) {
2063 for(int i = 0; i < pRange->optNames.size(); i++) {
2064 QVariant optVariant;
2065 QString errorString;
2066 if (!pRFact->metaData()->convertAndValidateRaw(pRange->optValues[i], false, optVariant, errorString)) {
2067 qWarning() << "Invalid roption value, name:" << pRange->targetParam
2068 << " type:" << pRFact->metaData()->type()
2069 << " value:" << pRange->optValues[i]
2070 << " error:" << errorString;
2071 } else {
2072 pRange->optVariants << optVariant;
2073 }
2074 }
2075 }
2076 }
2077}
2078
2079bool VehicleCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant)
2080{
2081 if(!read_attribute(option, kName, optName)) {
2082 qCritical() << QString("Malformed option for parameter %1").arg(factName);
2083 return false;
2084 }
2085 if(!read_attribute(option, kValue, optValue)) {
2086 qCritical() << QString("Malformed value for parameter %1").arg(factName);
2087 return false;
2088 }
2089 QString errorString;
2090 if (!metaData->convertAndValidateRaw(optValue, false, optVariant, errorString)) {
2091 qWarning() << "Invalid option value, name:" << factName
2092 << " type:" << metaData->type()
2093 << " value:" << optValue
2094 << " error:" << errorString;
2095 }
2096 return true;
2097}
2098
2099void VehicleCameraControl::_handleDefinitionFile(const QString &url)
2100{
2101 //-- First check and see if we have it cached
2102 QFile xmlFile(_cacheFile);
2103
2104 QString ftpPrefix(QStringLiteral("%1://").arg(FTPManager::mavlinkFTPScheme));
2105 if (!xmlFile.exists() && url.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
2106 qCDebug(CameraControlLog) << "No camera definition file cached, attempt ftp download";
2107 int ver = static_cast<int>(_mavlinkCameraInfo.cam_definition_version);
2108 QString ext = "";
2109 if (url.endsWith(".lzma", Qt::CaseInsensitive)) { ext = ".lzma"; }
2110 if (url.endsWith(".xz", Qt::CaseInsensitive)) { ext = ".xz"; }
2111 QString fileName = QString::asprintf("%s_%s_%03d.xml%s",
2112 _vendor.toStdString().c_str(),
2113 _modelName.toStdString().c_str(),
2114 ver,
2115 ext.toStdString().c_str());
2116 connect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &VehicleCameraControl::_ftpDownloadComplete);
2118 SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
2119 fileName);
2120 return;
2121 }
2122
2123 if (!xmlFile.exists()) {
2124 qCDebug(CameraControlLog) << "No camera definition file cached, attempt http download";
2125 _httpRequest(url);
2126 return;
2127 }
2128 if (!xmlFile.open(QIODevice::ReadOnly)) {
2129 qWarning() << "Could not read cached camera definition file:" << _cacheFile;
2130 _httpRequest(url);
2131 return;
2132 }
2133 QByteArray bytes = xmlFile.readAll();
2134 QDomDocument doc;
2135 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
2136 if (!result) {
2137 qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
2138 _httpRequest(url);
2139 return;
2140 }
2141 //-- We have it
2142 qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
2143 _cached = true;
2144 emit dataReady(bytes);
2145}
2146
2147void VehicleCameraControl::_httpRequest(const QString &url)
2148{
2149 qCDebug(CameraControlLog) << "Request camera definition:" << url;
2150 if(!_netManager) {
2151 _netManager = new QNetworkAccessManager(this);
2152 }
2154 QNetworkRequest request(QUrl::fromUserInput(url));
2155 request.setAttribute(QNetworkRequest::RedirectPolicyAttribute, true);
2156 QSslConfiguration conf = request.sslConfiguration();
2157 conf.setPeerVerifyMode(QSslSocket::VerifyNone);
2158 request.setSslConfiguration(conf);
2159 QNetworkReply* reply = _netManager->get(request);
2160 connect(reply, &QNetworkReply::finished, this, &VehicleCameraControl::_downloadFinished);
2161}
2162
2164{
2165 QNetworkReply* reply = qobject_cast<QNetworkReply*>(sender());
2166 if(!reply) {
2167 return;
2168 }
2169 int err = reply->error();
2170 int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
2171 QByteArray data = reply->readAll();
2172 if(err == QNetworkReply::NoError && http_code == 200) {
2173 data.append("\n");
2174 } else {
2175 data.clear();
2176 qWarning() << QString("Camera Definition (%1) download error: %2 status: %3").arg(
2177 reply->url().toDisplayString(),
2178 reply->errorString(),
2179 reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString()
2180 );
2181 }
2182 emit dataReady(data);
2183 //reply->deleteLater();
2184}
2185
2186void VehicleCameraControl::_ftpDownloadComplete(const QString& fileName, const QString& errorMsg)
2187{
2188 qCDebug(CameraControlLog) << "FTP Download completed: " << fileName << ", " << errorMsg;
2189
2190 disconnect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &VehicleCameraControl::_ftpDownloadComplete);
2191
2192 QString outputFileName = QGCCompression::decompressIfNeeded(fileName);
2193 if (outputFileName.isEmpty()) {
2194 qCWarning(CameraControlLog) << "Inflate of compressed xml failed" << fileName;
2195 }
2196
2197 QFile xmlFile(outputFileName);
2198
2199 if (!xmlFile.exists()) {
2200 qCDebug(CameraControlLog) << "No camera definition file present after ftp download completed";
2201 return;
2202 }
2203 if (!xmlFile.open(QIODevice::ReadOnly)) {
2204 qWarning() << "Could not read downloaded camera definition file: " << fileName;
2205 return;
2206 }
2207
2208 _cached = true;
2209 QByteArray bytes = xmlFile.readAll();
2210 emit dataReady(bytes);
2211}
2212
2214{
2215 if(data.size()) {
2216 qCDebug(CameraControlLog) << "Parsing camera definition";
2217 _loadCameraDefinitionFile(data);
2218 } else {
2219 qCDebug(CameraControlLog) << "No camera definition received, trying to search on our own...";
2220 QFile definitionFile;
2221 if(QGCCorePlugin::instance()->getOfflineCameraDefinitionFile(_modelName, definitionFile)) {
2222 qCDebug(CameraControlLog) << "Found offline definition file for: " << _modelName << ", loading: " << definitionFile.fileName();
2223 if (definitionFile.open(QIODevice::ReadOnly)) {
2224 QByteArray newData = definitionFile.readAll();
2225 _loadCameraDefinitionFile(newData);
2226 } else {
2227 qCDebug(CameraControlLog) << "error opening offline definition file for: " << _modelName;
2228 }
2229 } else {
2230 qCDebug(CameraControlLog) << "No offline camera definition file found";
2231 }
2232 }
2234}
2235
2237{
2238 for(const QString& param: _paramIO.keys()) {
2239 if(!_paramIO[param]->paramDone()) {
2240 return;
2241 }
2242 }
2243 //-- All parameters loaded (or timed out)
2244 _paramComplete = true;
2245 emit parametersReady();
2246}
2247
2249{
2250 if(_mavlinkCameraInfo.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) {
2251 connect(&_streamInfoTimer, &QTimer::timeout, this, &VehicleCameraControl::_streamInfoTimeout);
2252 _streamInfoTimer.setSingleShot(false);
2253 connect(&_streamStatusTimer, &QTimer::timeout, this, &VehicleCameraControl::_streamStatusTimeout);
2254 _streamStatusTimer.setSingleShot(true);
2255 //-- Request all streams
2257 _streamInfoTimer.start(2000);
2258 }
2259}
2260
2261bool VehicleCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
2262{
2263 Q_UNUSED(pFact);
2264 Q_UNUSED(newValue);
2265 return true;
2266}
2267
2268bool VehicleCameraControl::validateParameter(Fact* pFact, QVariant& newValue)
2269{
2270 Q_UNUSED(pFact);
2271 Q_UNUSED(newValue);
2272 return true;
2273}
2274
2275QStringList
2277{
2278 qCDebug(CameraControlLog) << "Active:" << _activeSettings;
2279 return _activeSettings;
2280}
2281
2282Fact*
2284{
2285 return (_paramComplete && _activeSettings.contains(kCAM_EXPMODE)) ? getFact(kCAM_EXPMODE) : nullptr;
2286}
2287
2288Fact*
2290{
2291 return (_paramComplete && _activeSettings.contains(kCAM_EV)) ? getFact(kCAM_EV) : nullptr;
2292}
2293
2294Fact*
2296{
2297 return (_paramComplete && _activeSettings.contains(kCAM_ISO)) ? getFact(kCAM_ISO) : nullptr;
2298}
2299
2300Fact*
2302{
2303 return (_paramComplete && _activeSettings.contains(kCAM_SHUTTERSPD)) ? getFact(kCAM_SHUTTERSPD) : nullptr;
2304}
2305
2306Fact*
2308{
2309 return (_paramComplete && _activeSettings.contains(kCAM_APERTURE)) ? getFact(kCAM_APERTURE) : nullptr;
2310}
2311
2312Fact*
2314{
2315 return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr;
2316}
2317
2318Fact*
2320{
2321 return _paramComplete && factExists(kCAM_MODE) ? getFact(kCAM_MODE) : nullptr;
2322}
2323
2325{
2326 if(set) {
2328 } else {
2329 _trackingStatus = static_cast<TrackingStatus>(_trackingStatus & ~TRACKING_ENABLED);
2330 }
2332}
2333
2335{
2336 if(_trackingMarquee != rec) {
2337 _trackingMarquee = rec;
2338
2339 qCDebug(CameraControlLog) << "Start Tracking (Rectangle: ["
2340 << static_cast<float>(rec.x()) << ", "
2341 << static_cast<float>(rec.y()) << "] - ["
2342 << static_cast<float>(rec.x() + rec.width()) << ", "
2343 << static_cast<float>(rec.y() + rec.height()) << "]";
2344
2346 MAV_CMD_CAMERA_TRACK_RECTANGLE,
2347 true,
2348 static_cast<float>(rec.x()),
2349 static_cast<float>(rec.y()),
2350 static_cast<float>(rec.x() + rec.width()),
2351 static_cast<float>(rec.y() + rec.height()));
2352
2353 // Request tracking status
2355 }
2356}
2357
2358void VehicleCameraControl::startTracking(QPointF point, double radius)
2359{
2360 if(_trackingPoint != point || _trackingRadius != radius) {
2361 _trackingPoint = point;
2362 _trackingRadius = radius;
2363
2364 qCDebug(CameraControlLog) << "Start Tracking (Point: ["
2365 << static_cast<float>(point.x()) << ", "
2366 << static_cast<float>(point.y()) << "], Radius: "
2367 << static_cast<float>(radius);
2368
2370 MAV_CMD_CAMERA_TRACK_POINT,
2371 true,
2372 static_cast<float>(point.x()),
2373 static_cast<float>(point.y()),
2374 static_cast<float>(radius));
2375
2376 // Request tracking status
2378 }
2379}
2380
2382{
2383 qCDebug(CameraControlLog) << "Stop Tracking";
2384
2385 //-- Stop Tracking
2387 MAV_CMD_CAMERA_STOP_TRACKING,
2388 true);
2389
2390 //-- Stop Sending Tracking Status
2392 MAV_CMD_SET_MESSAGE_INTERVAL,
2393 true,
2394 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
2395 -1);
2396
2397 // reset tracking image rectangle
2398 _trackingImageRect = {};
2399}
2400
2402{
2404 MAV_CMD_SET_MESSAGE_INTERVAL,
2405 true,
2406 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
2407 500000); // Interval (us)
2408}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define qgcApp()
QString errorString
struct __mavlink_message mavlink_message_t
static bool read_value(QDomNode &element, const char *tagName, QString &target)
static bool read_attribute(QDomNode &node, const char *tagName, bool &target)
Fact *savePath READ savePath CONSTANT Fact * savePath()
static constexpr const char * mavlinkFTPScheme
Definition FTPManager.h:78
void downloadComplete(const QString &file, const QString &errorMsg)
bool download(uint8_t fromCompId, const QString &fromURI, const QString &toDir, const QString &fileName="", bool checksize=true)
Definition FTPManager.cc:29
QMap< QString, FactMetaData * > _nameToFactMetaDataMap
Definition FactGroup.h:74
void _addFactGroup(FactGroup *factGroup, const QString &name)
Definition FactGroup.cc:130
void _addFact(Fact *fact, const QString &name)
Definition FactGroup.cc:113
void setRawUnits(const QString &rawUnits)
void setDecimalPlaces(int decimalPlaces)
void setHasControl(bool bValue)
void setShortDescription(const QString &shortDescription)
void setLongDescription(const QString &longDescription)
void setRawMin(const QVariant &rawMin)
bool convertAndValidateRaw(const QVariant &rawValue, bool convertOnly, QVariant &typedValue, QString &errorString) const
void setWriteOnly(bool bValue)
void setRawDefaultValue(const QVariant &rawDefaultValue)
void setRawMax(const QVariant &rawMax)
void setRawIncrement(double increment)
void addEnumInfo(const QString &name, const QVariant &value)
Used to add new values to the enum lists after the meta data has been loaded.
QVariant rawDefaultValue() const
ValueType_t type() const
static ValueType_t stringToType(const QString &typeString, bool &unknownType)
void setReadOnly(bool bValue)
A Fact is used to hold a single value within the system.
Definition Fact.h:19
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
Abstract base class for all camera controls: real and simulated.
void photoCaptureModeChanged()
virtual CameraMode cameraMode() const
void photoCaptureStatusChanged()
QString storageStatusToStr(uint8_t status)
PhotoCaptureStatus _photoCaptureStatus() const
QString captureVideoStatusToStr(uint8_t video_status)
void dataReady(const QByteArray &data)
void trackingImageStatusChanged()
VideoCaptureStatus _videoCaptureStatus() const
PhotoCaptureStatus _photoCaptureStatusValue
void videoCaptureStatusChanged()
void capturePhotosStateChanged()
void captureVideoStateChanged()
QString cameraModeToStr(CameraMode mode)
QString captureImageStatusToStr(uint8_t image_status)
void batteryRemainingChanged()
PhotoCaptureMode _photoCaptureMode
virtual PhotoCaptureMode photoCaptureMode() const
VideoCaptureStatus _videoCaptureStatusValue
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
Camera option exclusions.
QGCCameraOptionExclusion(QObject *parent, QString param_, QString value_, QStringList exclusions_)
Camera option ranges.
QGCCameraOptionRange(QObject *parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
Camera parameter handler.
Definition QGCCameraIO.h:17
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
virtual QGCVideoStreamInfo * thermalStreamInstance()
static constexpr const char * kCAM_ISO
static constexpr const char * kRoption
virtual bool trackingEnabled() const
static constexpr const char * kName
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)
virtual bool trackingImageStatus() const
QList< QGCCameraOptionRange * > _optionRanges
virtual quint32 recordTime() const
static constexpr const char * kType
virtual CapturePhotosState capturePhotosState() const
static constexpr const char * kModel
virtual int version() const
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)
virtual bool photosInVideoMode() const
mavlink_camera_tracking_image_status_t _trackingImageStatus
virtual bool videoInPhotoMode() const
static constexpr const char * kDescription
virtual void _onVideoManagerRecordingChanged(bool recording)
static constexpr const char * kUpdate
virtual bool hasTracking() const
QmlObjectListModel _streams
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)
static constexpr const char * kDecimalPlaces
static constexpr const char * kOptions
virtual bool hasVideoStream() const
virtual void _dataReady(QByteArray data)
virtual QString firmwareVersion() const
virtual QString vendor() const
static constexpr const char * kControl
static constexpr const char * kVersion
virtual void setZoomLevel(qreal level)
virtual void setCurrentStream(int stream)
virtual QString recordTimeStr() const
virtual QString storageFreeStr() const
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)
static constexpr const char * kWriteOnly
VehicleCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr)
static constexpr const char * kCAM_EXPMODE
virtual void _cameraSettingsTimeout()
static constexpr const char * kPhotoLapse
virtual void setCameraMode(CameraMode cameraMode)
virtual qreal focalLength() const
static constexpr const char * kCAM_APERTURE
virtual void setThermalMode(ThermalViewMode mode)
virtual void stepZoom(int direction)
static constexpr const char * kTranslated
static constexpr const char * kParameterranges
virtual void setFocusLevel(qreal level)
virtual bool capturesPhotos() const
static constexpr const char * kUnit
virtual QSizeF sensorSize() const
virtual bool autoStream() const
static constexpr const char * kDefnition
virtual QString modelName() const
static constexpr const char * kVendor
static constexpr const char * kOriginal
QList< QGCCameraOptionExclusion * > _valueExclusions
virtual bool hasFocus() const
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)
static constexpr const char * kCAM_SHUTTERSPD
virtual QSize resolution() const
virtual void _requestTrackingStatus()
static constexpr const char * kDefault
static constexpr const char * kMin
virtual bool isBasic() const
virtual void startTracking(QRectF rec)
virtual void _setCameraMode(CameraMode mode)
virtual QGCVideoStreamInfo * currentStreamInstance()
virtual void factChanged(Fact *pFact)
Notify controller a parameter has changed.
virtual void _requestStreamInfo(uint8_t streamID)
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)
virtual bool validateParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate parameter change.
QMap< QString, QGCCameraParamIO * > _paramIO
static constexpr const char * kPhotoLapseCount
static constexpr const char * kExclusions
static constexpr const char * kLocale
static constexpr const char * kCondition
static constexpr const char * kThermalMode
static constexpr const char * kMax
virtual bool hasModes() const
virtual void _mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
static constexpr const char * kStep
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate incoming parameter.
virtual void _requestStreamStatus(uint8_t streamID)
virtual QStringList activeSettings() const
static constexpr const char * kOption
virtual int compID() const
virtual bool toggleVideoRecording()
virtual void formatCard(int id=1)
static constexpr const char * kExclusion
virtual void setThermalOpacity(double val)
static constexpr const char * kStrings
QMap< QString, QVariantList > _originalOptValues
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)
QMap< QString, QStringList > _originalOptNames
virtual void handleParamExtAck(const mavlink_param_ext_ack_t &paramExtAck)
static constexpr const char * kPhotoMode
static constexpr const char * kReadOnly
virtual void _requestCaptureStatus()
virtual CaptureVideoState captureVideoState() const
virtual bool hasZoom() const
virtual bool capturesVideo() const
static constexpr const char * kParameter
static constexpr const char * kValue
virtual QGCVideoStreamInfo * _findStream(uint8_t streamID, bool report=true)
static constexpr const char * kUpdates
QMap< QString, QStringList > _requestUpdates
virtual void setPhotoLapse(qreal interval)
static constexpr const char * kParameterrange
static constexpr const char * kParameters
virtual void setPhotoLapseCount(int count)
virtual void _requestCameraSettings()
static constexpr const char * kCAM_EV
QNetworkAccessManager * _netManager
virtual QString batteryRemainingStr() const
virtual void startZoom(int direction)
static constexpr const char * kLocalization
virtual void _setPhotoCaptureStatus(PhotoCaptureStatus captureStatus)
static constexpr const char * kCAM_WBMODE
virtual void setTrackingEnabled(bool set)
virtual void handleParamExtValue(const mavlink_param_ext_value_t &paramExtValue)
virtual void _setVideoCaptureStatus(VideoCaptureStatus captureStatus)
mavlink_camera_information_t _mavlinkCameraInfo
static constexpr const char * kCAM_MODE
static constexpr const char * kThermalOpacity
WeakLinkInterfacePtr primaryLink() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2309
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:580
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470
FTPManager * ftpManager()
Definition Vehicle.h:581
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
void recordingChanged(bool recording)
QString decompressIfNeeded(const QString &filePath, const QString &outputPath, bool removeOriginal)
bool ensureDirectoryExists(const QString &path)
void configureProxy(QNetworkAccessManager *manager)
Set up default proxy configuration on a network manager.