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