22#include <QtNetwork/QNetworkAccessManager>
26#include <QtCore/QSettings>
27#include <QtXml/QDomDocument>
28#include <QtXml/QDomNodeList>
29#include <QtQml/QQmlEngine>
30#include <QtNetwork/QNetworkReply>
42 , exclusions(exclusions_)
50 , targetParam(targetParam_)
51 , condition(condition_)
53 , optValues(optValues_)
59 QDomNamedNodeMap attrs = node.attributes();
63 QDomNode subNode = attrs.namedItem(tagName);
64 if(subNode.isNull()) {
67 target = subNode.nodeValue() !=
"0";
73 QDomNamedNodeMap attrs = node.attributes();
77 QDomNode subNode = attrs.namedItem(tagName);
78 if(subNode.isNull()) {
81 target = subNode.nodeValue().toInt();
85static bool read_attribute(QDomNode& node,
const char* tagName, QString& target)
87 QDomNamedNodeMap attrs = node.attributes();
91 QDomNode subNode = attrs.namedItem(tagName);
92 if(subNode.isNull()) {
95 target = subNode.nodeValue();
99static bool read_value(QDomNode& element,
const char* tagName, QString& target)
101 QDomElement de = element.firstChildElement(tagName);
113 QQmlEngine::setObjectOwnership(
this, QQmlEngine::CppOwnership);
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",
127 if(info->cam_definition_uri[0] != 0) {
129 _handleDefinitionFile(info->cam_definition_uri);
149 qCDebug(VehicleCameraControlLog) <<
"Camera Info:";
150 qCDebug(VehicleCameraControlLog) <<
" vendor:" <<
vendor();
151 qCDebug(VehicleCameraControlLog) <<
" model:" <<
modelName();
152 qCDebug(VehicleCameraControlLog) <<
" version:" <<
version();
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();
184 qCDebug(VehicleCameraControlLog) <<
"_initWhenReady()";
186 qCDebug(VehicleCameraControlLog) <<
"Basic, MAVLink only messages, no parameters.";
227 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_VIDEO | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
234 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_IMAGE | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
279 return QString::asprintf(
"%d.%d.%d.%d", major, minor, patch, dev);
281 return QString::asprintf(
"%d.%d.%d", major, minor, patch);
286 return QTime(0, 0).addMSecs(
static_cast<int>(
recordTime())).toString(
"hh:mm:ss");
308 qCWarning(VehicleCameraControlLog) <<
"Camera does not support modes";
312 qCDebug(VehicleCameraControlLog) <<
"Camera set to video mode";
322 qCWarning(VehicleCameraControlLog) <<
"Camera does not support modes";
326 qCDebug(VehicleCameraControlLog) <<
"Camera set to photo mode";
336 qCWarning(VehicleCameraControlLog) <<
"Camera does not support modes";
340 qCWarning(VehicleCameraControlLog) <<
"Invalid camera mode" <<
cameraMode;
358 MAV_CMD_SET_CAMERA_MODE,
434 qCWarning(VehicleCameraControlLog) <<
"Take photo denied - photo capture is disabled";
438 qCWarning(VehicleCameraControlLog) <<
"Take photo denied - already capturing";
442 qCDebug(VehicleCameraControlLog) <<
"takePhoto()";
444 const bool canUseMavlinkImageCapture =
448 if (canUseMavlinkImageCapture) {
451 MAV_CMD_IMAGE_START_CAPTURE,
463 QTimer::singleShot(500,
this, [
this]() {
468 QGC::showAppMessage(tr(
"Timelapse photo capture is not supported on cameras without still capture capability"));
481 qCWarning(VehicleCameraControlLog) <<
"Stop taking photos requested - not currently capturing multiple photos";
485 qCDebug(VehicleCameraControlLog) <<
"Camera stop taking photos";
490 MAV_CMD_IMAGE_STOP_CAPTURE,
505 qCWarning(VehicleCameraControlLog) <<
"Start video denied - already recording";
509 qCWarning(VehicleCameraControlLog) <<
"Start video denied - video capture is disabled";
515 qCDebug(VehicleCameraControlLog) <<
"Start video recording:" << (useMavlinkCommand ?
"MAVLink command" :
"VideoManager");
517 if (useMavlinkCommand) {
520 MAV_CMD_VIDEO_START_CAPTURE,
538 qCWarning(VehicleCameraControlLog) <<
"Stop video recording requested - already idle";
544 qCDebug(VehicleCameraControlLog) <<
"Camera stop video recording" << (useMavlinkCommand ?
"MAVLink command" :
"VideoManager");
546 if (useMavlinkCommand) {
549 MAV_CMD_VIDEO_STOP_CAPTURE,
570 if(val < 0.0) val = 0.0;
571 if(val > 100.0) val = 100.0;
582 qCDebug(VehicleCameraControlLog) <<
"Camera set zoom level to" << level;
585 level = std::min(std::max(level, 0.0), 100.0);
589 MAV_CMD_SET_CAMERA_ZOOM,
592 static_cast<float>(level));
599 qCDebug(VehicleCameraControlLog) <<
"Camera set focus level to" << level;
602 level = std::min(std::max(level, 0.0), 100.0);
606 MAV_CMD_SET_CAMERA_FOCUS,
609 static_cast<float>(level));
617 qCDebug(VehicleCameraControlLog) <<
"resetSettings()";
621 MAV_CMD_RESET_CAMERA_SETTINGS,
630 qCDebug(VehicleCameraControlLog) <<
"formatCard()";
634 MAV_CMD_STORAGE_FORMAT,
644 qCDebug(VehicleCameraControlLog) <<
"Camera step zoom" << direction;
648 MAV_CMD_SET_CAMERA_ZOOM,
657 qCDebug(VehicleCameraControlLog) <<
"Camera start zoom" << direction;
661 MAV_CMD_SET_CAMERA_ZOOM,
663 ZOOM_TYPE_CONTINUOUS,
670 qCDebug(VehicleCameraControlLog) <<
"Camera stop zoom";
674 MAV_CMD_SET_CAMERA_ZOOM,
676 ZOOM_TYPE_CONTINUOUS,
683 qCDebug(VehicleCameraControlLog) <<
"Camera step focus" << direction;
687 MAV_CMD_SET_CAMERA_FOCUS,
696 qCDebug(VehicleCameraControlLog) <<
"Camera start focus" << direction;
700 MAV_CMD_SET_CAMERA_FOCUS,
702 FOCUS_TYPE_CONTINUOUS,
709 qCDebug(VehicleCameraControlLog) <<
"Camera stop focus";
713 MAV_CMD_SET_CAMERA_FOCUS,
715 FOCUS_TYPE_CONTINUOUS,
725 qCDebug(VehicleCameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS";
728 MAV_CMD_REQUEST_MESSAGE,
730 MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS);
732 qCDebug(VehicleCameraControlLog) <<
" Sending MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (legacy)";
735 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,
744 _updateRanges(pFact);
749 Q_UNUSED(failureCode);
755 if (result == MAV_RESULT_IN_PROGRESS) {
757 qCDebug(VehicleCameraControlLog) <<
"In progress response for" << command;
758 }
else if(result == MAV_RESULT_ACCEPTED) {
760 case MAV_CMD_RESET_CAMERA_SETTINGS:
769 case MAV_CMD_VIDEO_START_CAPTURE:
773 case MAV_CMD_VIDEO_STOP_CAPTURE:
777 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
780 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
783 case MAV_CMD_IMAGE_START_CAPTURE:
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;
793 qCDebug(VehicleCameraControlLog) <<
"Command failed (MAV_RESULT_FAILED) for" << commandStr;
796 case MAV_CMD_RESET_CAMERA_SETTINGS:
798 qCDebug(VehicleCameraControlLog) <<
"Failed to reset camera settings";
800 case MAV_CMD_IMAGE_START_CAPTURE:
801 case MAV_CMD_IMAGE_STOP_CAPTURE:
805 qCDebug(VehicleCameraControlLog) <<
"Giving up start/stop image capture";
809 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
813 qCDebug(VehicleCameraControlLog) <<
"Giving up requesting capture status";
816 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
820 qCDebug(VehicleCameraControlLog) <<
"Giving up requesting storage status";
874 qCDebug(VehicleCameraControlLog) <<
"Set Photo Status:" << captureStatus;
880bool VehicleCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
882 QByteArray originalData(bytes);
884 if(!_handleLocalization(bytes)) {
889 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
891 qCCritical(VehicleCameraControlLog) <<
"Unable to parse camera definition file on line:" << result.errorLine;
892 qCCritical(VehicleCameraControlLog) << result.errorMessage;
896 QDomNodeList defElements = doc.elementsByTagName(
kDefnition);
897 if(!defElements.size() || !_loadConstants(defElements)) {
898 qCWarning(VehicleCameraControlLog) <<
"Unable to load camera constants from camera definition";
902 QDomNodeList paramElements = doc.elementsByTagName(
kParameters);
903 if(!paramElements.size()) {
904 qCDebug(VehicleCameraControlLog) <<
"No parameters to load from camera";
907 if(!_loadSettings(paramElements)) {
908 qCWarning(VehicleCameraControlLog) <<
"Unable to load camera parameters from camera definition";
913 qCDebug(VehicleCameraControlLog) <<
"Saving camera definition file" <<
_cacheFile;
915 if (!file.open(QIODevice::WriteOnly)) {
916 qWarning() << QString(
"Could not save cache file %1. Error: %2").arg(
_cacheFile).arg(file.errorString());
918 file.write(originalData);
924bool VehicleCameraControl::_loadConstants(
const QDomNodeList nodeList)
926 QDomNode node = nodeList.item(0);
939bool VehicleCameraControl::_loadSettings(
const QDomNodeList nodeList)
941 QDomNode node = nodeList.item(0);
942 QDomElement elem = node.toElement();
943 QDomNodeList parameters = elem.elementsByTagName(
kParameter);
945 for(
int i = 0; i < parameters.size(); i++) {
946 QDomNode parameterNode = parameters.item(i);
955 qCritical() <<
"Parameter entry missing parameter name";
960 for(
int i = 0; i < parameters.size(); i++) {
961 QDomNode parameterNode = parameters.item(i);
966 qCritical() << QString(
"Parameter %1 missing parameter type").arg(factName);
973 bool readOnly =
false;
976 bool writeOnly =
false;
979 if(readOnly && writeOnly) {
980 qCritical() << QString(
"Parameter %1 cannot be both read only and write only").arg(factName);
986 qCritical() << QString(
"Unknown type for parameter %1").arg(factName);
996 qCritical() << QString(
"Parameter %1 missing parameter description").arg(factName);
1000 QStringList updates = _loadUpdates(parameterNode);
1001 if(updates.size()) {
1002 qCDebug(VehicleCameraControlVerboseLog) <<
"Parameter" << factName <<
"requires updates for:" << updates;
1007 QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
1014 QDomElement optionElem = parameterNode.toElement();
1015 QDomNodeList optionsRoot = optionElem.elementsByTagName(
kOptions);
1016 if(optionsRoot.size()) {
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);
1025 QVariant optVariant;
1026 if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
1034 QStringList exclusions = _loadExclusions(option);
1035 if(exclusions.size()) {
1036 qCDebug(VehicleCameraControlVerboseLog) <<
"New exclusions:" << factName << optValue << exclusions;
1038 QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
1042 if(!_loadRanges(option, factName, optValue)) {
1048 QString defaultValue;
1050 QVariant defaultVariant;
1055 qWarning() <<
"Invalid default value for" << factName
1056 <<
" type:" << metaData->
type()
1057 <<
" value:" << defaultValue
1063 qWarning() << QStringLiteral(
"Duplicate fact name:") << factName;
1070 QVariant typedValue;
1075 qWarning() <<
"Invalid min value for" << factName
1076 <<
" type:" << metaData->
type()
1077 <<
" value:" << attr
1086 QVariant typedValue;
1091 qWarning() <<
"Invalid max value for" << factName
1092 <<
" type:" << metaData->
type()
1093 <<
" value:" << attr
1102 QVariant typedValue;
1107 qWarning() <<
"Invalid step value for" << factName
1108 <<
" type:" << metaData->
type()
1109 <<
" value:" << attr
1118 QVariant typedValue;
1123 qWarning() <<
"Invalid decimal places value for" << factName
1124 <<
" type:" << metaData->
type()
1125 <<
" value:" << attr
1137 qCDebug(VehicleCameraControlLog) <<
"New parameter:" << factName << (readOnly ?
"ReadOnly" :
"Writable") << (writeOnly ?
"WriteOnly" :
"Readable");
1140 QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
1144 QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
1159bool VehicleCameraControl::_handleLocalization(QByteArray& bytes)
1162 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
1164 qCritical() <<
"Unable to parse camera definition file on line:" << result.errorLine;
1165 qCritical() << result.errorMessage;
1169 QLocale locale = QLocale::system();
1170#if defined (Q_OS_MACOS)
1171 locale = QLocale(locale.name());
1173 QString localeName = locale.name().toLower().replace(
"-",
"_");
1174 qCDebug(VehicleCameraControlLog) <<
"Current locale:" << localeName;
1175 if(localeName ==
"en_us") {
1179 QDomNodeList locRoot = doc.elementsByTagName(
kLocalization);
1180 if(!locRoot.size()) {
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);
1192 qWarning() <<
"Localization entry is missing its name attribute";
1196 if(localeName == name.toLower().replace(
"-",
"_")) {
1197 return _replaceLocaleStrings(localeNode, bytes);
1201 localeName = localeName.left(3);
1202 for(
int i = 0; i < locales.size(); i++) {
1203 QDomNode localeNode = locales.item(i);
1206 if(name.toLower().startsWith(localeName)) {
1207 return _replaceLocaleStrings(localeNode, bytes);
1211 qWarning() <<
"No match for" << QLocale::system().name() <<
"in camera definition file";
1216bool VehicleCameraControl::_replaceLocaleStrings(
const QDomNode node, QByteArray& bytes)
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);
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());
1241 for(
const QString& paramName:
_paramIO.keys()) {
1243 _paramIO[paramName]->setParamRequest();
1245 qCritical() <<
"QGCParamIO is NULL" << paramName;
1251 mavlink_msg_param_ext_request_list_pack_chan(
1254 sharedLink->mavlinkChannel(),
1257 static_cast<uint8_t
>(
compID()));
1260 qCDebug(VehicleCameraControlVerboseLog) <<
"Request all parameters";
1263QString VehicleCameraControl::_getParamName(
const char* param_id)
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;
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);
1280 if(!
_paramIO.contains(paramName)) {
1281 qCWarning(VehicleCameraControlLog) <<
"Received PARAM_EXT_ACK for unknown param:" << paramName;
1285 _paramIO[paramName]->handleParamAck(paramExtAck);
1287 qCritical() <<
"QGCParamIO is NULL" << paramName;
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);
1300 if(!
_paramIO.contains(paramName)) {
1301 qCWarning(VehicleCameraControlLog) <<
"Received PARAM_EXT_VALUE for unknown param:" << paramName;
1305 _paramIO[paramName]->handleParamValue(paramExtValue);
1307 qCritical() <<
"QGCParamIO is NULL" << paramName;
1311void VehicleCameraControl::_updateActiveList()
1314 QStringList exclusionList;
1319 if(param->value == option) {
1320 exclusionList << param->exclusions;
1326 if(!exclusionList.contains(key)) {
1331 qCDebug(VehicleCameraControlVerboseLog) <<
"Excluding" << exclusionList;
1341bool VehicleCameraControl::_processConditionTest(
const QString conditionTest)
1350 qCDebug(VehicleCameraControlVerboseLog) <<
"_processConditionTest(" << conditionTest <<
")";
1354 auto split = [&conditionTest](
const QString& sep ) {
1355 return conditionTest.split(sep, Qt::SkipEmptyParts);
1358 if(conditionTest.contains(
"!=")) {
1360 op = TEST_NOT_EQUAL;
1361 }
else if(conditionTest.contains(
"=")) {
1364 }
else if(conditionTest.contains(
">")) {
1367 }
else if(conditionTest.contains(
"<")) {
1371 if(test.size() == 2) {
1377 case TEST_NOT_EQUAL:
1387 qWarning() <<
"Invalid condition parameter:" << test[0] <<
"in" << conditionTest;
1391 qWarning() <<
"Invalid condition" << conditionTest;
1395bool VehicleCameraControl::_processCondition(
const QString condition)
1397 qCDebug(VehicleCameraControlVerboseLog) <<
"_processCondition(" << condition <<
")";
1400 if(!condition.isEmpty()) {
1401 QStringList scond = condition.split(
" ", Qt::SkipEmptyParts);
1402 while(scond.size()) {
1403 QString test = scond.first();
1404 scond.removeFirst();
1406 result = result && _processConditionTest(test);
1408 result = result || _processConditionTest(test);
1413 andOp = scond.first().toUpper() ==
"AND";
1414 scond.removeFirst();
1420void VehicleCameraControl::_updateRanges(
Fact* pFact)
1422 QMap<Fact*, QGCCameraOptionRange*> rangesSet;
1423 QMap<Fact*, QString> rangesReset;
1424 QStringList changedList;
1425 QStringList resetList;
1426 QStringList updates;
1430 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->
name() || pRange->condition.contains(pFact->
name()))) {
1433 if(pRFact && pTFact) {
1438 if(pRange->value == option && _processCondition(pRange->condition)) {
1441 rangesSet[pTFact] = pRange;
1443 changedList << pRange->targetParam;
1450 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->
name() || pRange->condition.contains(pFact->
name()))) {
1452 if(!resetList.contains(pRange->targetParam)) {
1455 rangesReset[pTFact] = pRange->targetParam;
1457 resetList << pRange->targetParam;
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();
1471 for (
Fact* f: rangesReset.keys()) {
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();
1508 qCDebug(VehicleCameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_SETTINGS";
1511 MAV_CMD_REQUEST_MESSAGE,
1513 MAVLINK_MSG_ID_CAMERA_SETTINGS);
1515 qCDebug(VehicleCameraControlLog) <<
" Sending MAV_CMD_REQUEST_CAMERA_SETTINGS (legacy)";
1518 MAV_CMD_REQUEST_CAMERA_SETTINGS,
1523 qCDebug(VehicleCameraControlLog) <<
"_requestCameraSettings() - RESTARTING already active timer";
1525 qCDebug(VehicleCameraControlLog) <<
"_requestCameraSettings() - starting timer";
1539 qCDebug(VehicleCameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_STORAGE_INFORMATION";
1542 MAV_CMD_REQUEST_MESSAGE,
1544 MAVLINK_MSG_ID_STORAGE_INFORMATION,
1547 qCDebug(VehicleCameraControlLog) <<
" Sending MAV_CMD_REQUEST_STORAGE_INFORMATION (legacy)";
1550 MAV_CMD_REQUEST_STORAGE_INFORMATION,
1555 qCDebug(VehicleCameraControlLog) <<
"_requestStorageInfo() - starting timer";
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;
1571 qreal z =
static_cast<qreal
>(settings.zoomLevel);
1572 qreal f =
static_cast<qreal
>(settings.focusLevel);
1585 qCDebug(VehicleCameraControlLog) <<
"Received STORAGE_INFORMATION - stopping timer, resetting retries:"
1586 <<
"\n\tStorage id:" << storageInformation.storage_id
1587 <<
"\n\tStorage count:" << storageInformation.storage_count
1589 <<
"\n\tTotal capacity:" << storageInformation.total_capacity
1590 <<
"\n\tUsed capacity:" << storageInformation.used_capacity
1591 <<
"\n\tAvailable capacity:" << storageInformation.available_capacity;
1596 if(storageInformation.status == STORAGE_STATUS_READY) {
1597 uint32_t t =
static_cast<uint32_t
>(storageInformation.total_capacity);
1602 uint32_t a =
static_cast<uint32_t
>(storageInformation.available_capacity);
1616 qCDebug(VehicleCameraControlLog).noquote() <<
"Received BATTERY_STATUS:"
1617 <<
"\n\tBattery remaining (%):" << bs.battery_remaining;
1619 if(bs.battery_remaining >= 0 &&
_batteryRemaining !=
static_cast<int>(bs.battery_remaining)) {
1627 qCDebug(VehicleCameraControlLog).noquote() <<
"Received CAMERA_CAPTURE_STATUS - stopping timer, resetting retries:"
1630 <<
"\n\tInterval:" << cameraCaptureStatus.image_interval
1631 <<
"\n\tRecording time (ms):" << cameraCaptureStatus.recording_time_ms
1632 <<
"\n\tCapacity:" << cameraCaptureStatus.available_capacity;
1638 uint32_t a =
static_cast<uint32_t
>(cameraCaptureStatus.available_capacity);
1644 if(cameraCaptureStatus.recording_time_ms) {
1646 _recordTime = cameraCaptureStatus.recording_time_ms;
1647 _recTime =
_recTime.addMSecs(
_recTime.msecsTo(QTime::currentTime()) -
static_cast<int>(cameraCaptureStatus.recording_time_ms));
1667 const QString photoPath = photoDir +
"/" + QDateTime::currentDateTime().toString(
"yyyy-MM-dd_hh.mm.ss.zzz") +
".jpg";
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;
1687 if(!
_findStream(videoStreamInformation.stream_id,
false)) {
1688 qCDebug(VehicleCameraControlLog) <<
"Create stream handler for stream ID:" << videoStreamInformation.stream_id;
1690 QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
1706 qCDebug(VehicleCameraControlLog) <<
"All stream handlers done";
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;
1730 pInfo->
update(videoStreamStatus);
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;
1747 const bool isPoint = active && (
_trackingImageStatus.tracking_mode == CAMERA_TRACKING_MODE_POINT);
1750 qCDebug(VehicleCameraControlLog) <<
"Tracking off";
1754 }
else if (isPoint) {
1758 if (qIsNaN(radius) || radius <= 0) {
1761 radius = std::clamp(radius, 0.0, 1.0);
1763 qCDebug(VehicleCameraControlLog) <<
"Tracking Point [" << point <<
"] radius:" << radius;
1775 const QRectF rect = QRectF(QPointF(std::clamp(
static_cast<qreal
>(
_trackingImageStatus.rec_top_x), 0.0, 1.0),
1779 qCDebug(VehicleCameraControlLog) <<
"Tracking Rect [" << rect <<
"]";
1803 qCDebug(VehicleCameraControlLog) <<
"Stopping stream:" << pInfo->
uri();
1807 MAV_CMD_VIDEO_STOP_STREAMING,
1815 qCDebug(VehicleCameraControlLog) <<
"Starting stream:" << pInfo->
uri();
1818 MAV_CMD_VIDEO_START_STREAMING,
1836 MAV_CMD_VIDEO_STOP_STREAMING,
1849 MAV_CMD_VIDEO_START_STREAMING,
1892 qCDebug(VehicleCameraControlLog) <<
"_requestStreamInfo() - stream:" << streamID <<
"retries:" <<
_videoStreamInfoRetries;
1896 qCDebug(VehicleCameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION";
1899 MAV_CMD_REQUEST_MESSAGE,
1901 MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
1904 qCDebug(VehicleCameraControlLog) <<
" Sending MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (legacy)";
1907 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,
1916 qCDebug(VehicleCameraControlLog) <<
"_requestStreamStatus() - stream:" << streamID <<
"retries:" <<
_videoStreamStatusRetries;
1920 qCDebug(VehicleCameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_STATUS";
1923 MAV_CMD_REQUEST_MESSAGE,
1925 MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
1928 qCDebug(VehicleCameraControlLog) <<
" Sending MAV_CMD_REQUEST_VIDEO_STREAM_STATUS (legacy)";
1931 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS,
1949 qCritical() <<
"Null QGCVideoStreamInfo instance";
1954 qWarning() <<
"Stream id not found:" << id;
1966 if(pStream->
name() == name) {
1980 qCWarning(VehicleCameraControlLog) <<
"Giving up requesting video stream info";
2002 qCWarning(VehicleCameraControlLog) <<
"Giving up requesting video stream status";
2017 qCWarning(VehicleCameraControlLog) <<
"Giving up requesting camera settings after" <<
_cameraSettingsRetries <<
"retries";
2021 qCDebug(VehicleCameraControlLog) <<
"_cameraSettingsTimeout() - calling _requestCameraSettings()";
2028 qCDebug(VehicleCameraControlLog) <<
"_storageInfoTimeout() - retries now:" <<
_storageInfoRetries;
2030 qCWarning(VehicleCameraControlLog) <<
"Giving up requesting storage info after" <<
_storageInfoRetries <<
"retries";
2034 qCDebug(VehicleCameraControlLog) <<
"_storageInfoTimeout() - calling _requestStorageInfo()";
2039VehicleCameraControl::_loadExclusions(QDomNode option)
2041 QStringList exclusionList;
2042 QDomElement optionElem = option.toElement();
2043 QDomNodeList excRoot = optionElem.elementsByTagName(
kExclusions);
2044 if(excRoot.size()) {
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;
2056 return exclusionList;
2060VehicleCameraControl::_loadUpdates(QDomNode option)
2062 QStringList updateList;
2063 QDomElement optionElem = option.toElement();
2064 QDomNodeList updateRoot = optionElem.elementsByTagName(
kUpdates);
2065 if(updateRoot.size()) {
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;
2080bool VehicleCameraControl::_loadRanges(QDomNode option,
const QString factName, QString paramValue)
2082 QDomElement optionElem = option.toElement();
2084 if(rangeRoot.size()) {
2085 QDomNode node = rangeRoot.item(0);
2086 QDomElement elem = node.toElement();
2087 QDomNodeList parameterRanges = elem.elementsByTagName(
kParameterrange);
2089 for(
int i = 0; i < parameterRanges.size(); i++) {
2092 QDomNode paramRange = parameterRanges.item(i);
2094 qCritical() << QString(
"Malformed option range for parameter %1").arg(factName);
2098 QDomElement pelem = paramRange.toElement();
2099 QDomNodeList rangeOptions = pelem.elementsByTagName(
kRoption);
2100 QStringList optNames;
2101 QStringList optValues;
2103 for(
int rangeOptionIndex = 0; rangeOptionIndex < rangeOptions.size(); rangeOptionIndex++) {
2106 QDomNode roption = rangeOptions.item(rangeOptionIndex);
2108 qCritical() << QString(
"Malformed roption for parameter %1").arg(factName);
2112 qCritical() << QString(
"Malformed rvalue for parameter %1").arg(factName);
2115 optNames << optName;
2116 optValues << optValue;
2118 if(optNames.size()) {
2121 qCDebug(VehicleCameraControlVerboseLog) <<
"New range limit:" << factName << paramValue << param << condition << optNames << optValues;
2128void VehicleCameraControl::_processRanges()
2134 for(
int i = 0; i < pRange->optNames.size(); i++) {
2135 QVariant optVariant;
2138 qWarning() <<
"Invalid roption value, name:" << pRange->targetParam
2140 <<
" value:" << pRange->optValues[i]
2143 pRange->optVariants << optVariant;
2150bool VehicleCameraControl::_loadNameValue(QDomNode option,
const QString factName,
FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant)
2153 qCritical() << QString(
"Malformed option for parameter %1").arg(factName);
2157 qCritical() << QString(
"Malformed value for parameter %1").arg(factName);
2162 qWarning() <<
"Invalid option value, name:" << factName
2163 <<
" type:" << metaData->
type()
2164 <<
" value:" << optValue
2170void VehicleCameraControl::_handleDefinitionFile(
const QString &url)
2176 if (!xmlFile.exists() && url.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
2177 qCDebug(VehicleCameraControlLog) <<
"No camera definition file cached, attempt ftp download";
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(),
2186 ext.toStdString().c_str());
2194 if (!xmlFile.exists()) {
2195 qCDebug(VehicleCameraControlLog) <<
"No camera definition file cached, attempt http download";
2199 if (!xmlFile.open(QIODevice::ReadOnly)) {
2200 qWarning() <<
"Could not read cached camera definition file:" <<
_cacheFile;
2204 QByteArray bytes = xmlFile.readAll();
2206 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
2208 qWarning() <<
"Could not parse cached camera definition file:" <<
_cacheFile;
2213 qCDebug(VehicleCameraControlLog) <<
"Using cached camera definition file:" <<
_cacheFile;
2218void VehicleCameraControl::_httpRequest(
const QString &url)
2220 qCDebug(VehicleCameraControlLog) <<
"Request camera definition:" << url;
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);
2236 QNetworkReply* reply = qobject_cast<QNetworkReply*>(sender());
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) {
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()
2257void VehicleCameraControl::_ftpDownloadComplete(
const QString& fileName,
const QString& errorMsg)
2259 qCDebug(VehicleCameraControlLog) <<
"FTP Download completed: " << fileName <<
", " << errorMsg;
2264 if (outputFileName.isEmpty()) {
2265 qCWarning(VehicleCameraControlLog) <<
"Inflate of compressed xml failed" << fileName;
2268 QFile xmlFile(outputFileName);
2270 if (!xmlFile.exists()) {
2271 qCDebug(VehicleCameraControlLog) <<
"No camera definition file present after ftp download completed";
2274 if (!xmlFile.open(QIODevice::ReadOnly)) {
2275 qWarning() <<
"Could not read downloaded camera definition file: " << fileName;
2280 QByteArray bytes = xmlFile.readAll();
2287 qCDebug(VehicleCameraControlLog) <<
"Parsing camera definition";
2288 _loadCameraDefinitionFile(data);
2290 qCDebug(VehicleCameraControlLog) <<
"No camera definition received, trying to search on our own...";
2291 QFile 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);
2298 qCDebug(VehicleCameraControlLog) <<
"error opening offline definition file for: " <<
_modelName;
2301 qCDebug(VehicleCameraControlLog) <<
"No offline camera definition file found";
2309 for(
const QString& param:
_paramIO.keys()) {
2310 if(!
_paramIO[param]->paramDone()) {
2410 qCCritical(VehicleCameraControlLog) <<
"startTrackingRect called but camera does not have rectangle tracking capability";
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()) <<
"]";
2421 MAV_CMD_CAMERA_TRACK_RECTANGLE,
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()));
2434 qCCritical(VehicleCameraControlLog) <<
"startTrackingPoint called but camera does not have point tracking capability";
2438 qCDebug(VehicleCameraControlLog) <<
"Start Tracking (Point: ["
2439 <<
static_cast<float>(point.x()) <<
", "
2440 <<
static_cast<float>(point.y()) <<
"], Radius: "
2441 <<
static_cast<float>(radius);
2444 MAV_CMD_CAMERA_TRACK_POINT,
2446 static_cast<float>(point.x()),
2447 static_cast<float>(point.y()),
2448 static_cast<float>(radius));
2455 qCDebug(VehicleCameraControlLog) <<
"Stop Tracking";
2459 MAV_CMD_CAMERA_STOP_TRACKING,
2464 MAV_CMD_SET_MESSAGE_INTERVAL,
2466 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
2486 MAV_CMD_SET_MESSAGE_INTERVAL,
2488 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
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
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)
QMap< QString, FactMetaData * > _nameToFactMetaDataMap
Q_INVOKABLE Fact * getFact(const QString &name) const
void _addFactGroup(FactGroup *factGroup, const QString &name)
Q_INVOKABLE bool factExists(const QString &name) const
@ return true: if the fact exists in the group
void _addFact(Fact *fact, const QString &name)
A Fact is used to hold a single value within the system.
void setMetaData(FactMetaData *metaData, bool setDefaultFromMetaData=false)
void containerSetRawValue(const QVariant &value)
Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
FactMetaData * metaData()
void setRawValue(const QVariant &value)
QString rawValueString() const
QStringList enumStrings() const
static int getComponentId()
static MAVLinkProtocol * instance()
Abstract base class for all camera controls: real and simulated.
void trackingImageRadiusChanged()
@ CapturePhotosStateDisabled
@ CapturePhotosStateCapturingSinglePhoto
@ CapturePhotosStateCapturingMultiplePhotos
void trackingImageIsPointChanged()
@ PHOTO_CAPTURE_INTERVAL_IDLE
@ PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
@ PHOTO_CAPTURE_IN_PROGRESS
@ PHOTO_CAPTURE_STATUS_UNDEFINED
void batteryRemainingChanged()
void photoLapseCountChanged()
void videoCaptureStatusChanged()
void storageFreeChanged()
PhotoCaptureStatus _photoCaptureStatus() const
friend class QGCCameraParamIO
QString storageStatusToStr(uint8_t status)
PhotoCaptureMode _photoCaptureMode
void storageStatusChanged()
QString cameraModeToStr(CameraMode mode)
virtual PhotoCaptureMode photoCaptureMode() const
void photoCaptureStatusChanged()
QString captureImageStatusToStr(uint8_t image_status)
VideoCaptureStatus _videoCaptureStatusValue
void trackingEnabledChanged()
void storageTotalChanged()
void activeSettingsChanged()
VideoCaptureStatus _videoCaptureStatus() const
void capturePhotosStateChanged()
@ VIDEO_CAPTURE_STATUS_UNDEFINED
@ VIDEO_CAPTURE_STATUS_STOPPED
@ VIDEO_CAPTURE_STATUS_LAST
@ VIDEO_CAPTURE_STATUS_RUNNING
void trackingImageRectChanged()
void captureVideoStateChanged()
void trackingImageIsActiveChanged()
virtual CameraMode cameraMode() const
void trackingImagePointChanged()
void thermalOpacityChanged()
void currentStreamChanged()
void thermalModeChanged()
void streamLabelsChanged()
void thermalStreamChanged()
PhotoCaptureStatus _photoCaptureStatusValue
@ CaptureVideoStateDisabled
@ CaptureVideoStateCapturing
QString captureVideoStatusToStr(uint8_t video_status)
void dataReady(const QByteArray &data)
void photoCaptureModeChanged()
QTimer _videoRecordTimeUpdateTimer
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
Camera option exclusions.
QGCCameraOptionRange(QObject *parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
Camera parameter handler.
static QGCCorePlugin * instance()
static QString mavResultToString(uint8_t result)
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
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.
virtual void _storageInfoTimeout()
QStringList _updatesToRequest
QRectF _trackingImageRect
void handleParamExtValue(const mavlink_param_ext_value_t ¶mExtValue) override
Fact * shutterSpeed() override
static constexpr const char * kCAM_ISO
void setPhotoLapse(qreal interval) override
virtual void _downloadFinished()
virtual void _streamInfoTimeout()
static constexpr const char * kRoption
virtual void _streamStatusTimeout()
virtual void _requestAllParameters()
QSize resolution() const override
bool incomingParameter(Fact *pFact, QVariant &newValue) override
Allow controller to modify or invalidate incoming parameter.
QTimer _cameraSettingsTimer
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
virtual void _checkForVideoStreams()
QString recordTimeStr() const override
Q_INVOKABLE void formatCard(int id=1) override
bool hasVideoStream() const override
virtual void _onVideoManagerRecordingChanged(bool recording)
bool _trackingImageIsPoint
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
Fact * exposureMode() override
void setFocusLevel(qreal level) override
virtual void _requestStorageInfo()
bool _hasTrackingPointCapability
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
bool _hasTrackingRectCapability
Q_INVOKABLE bool toggleVideoRecording() override
virtual void _dataReady(QByteArray data)
virtual void _initWhenReady()
virtual void _requestParamUpdates()
int _videoStreamInfoRetries
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
int _videoStreamStatusRetries
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
ThermalViewMode _thermalMode
QTimer _streamStatusTimer
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.
QStringList _activeSettings
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 ¶mExtAck) override
static constexpr const char * kOption
void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus) override
QTimer _captureStatusTimer
virtual void _recTimerHandler()
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
QStringList _streamLabels
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)
qreal _trackingImageRadius
CaptureVideoState captureVideoState() const override
static constexpr const char * kUpdates
int _cameraCaptureStatusRetries
void handleCameraSettings(const mavlink_camera_settings_t &settings) override
QMap< QString, QStringList > _requestUpdates
void _paramDone() override
Q_INVOKABLE void stopTracking() override
~VehicleCameraControl() override
Fact * aperture() 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
int _cameraSettingsRetries
bool hasZoom() const override
StorageStatus _storageStatus
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
QPointF _trackingImagePoint
virtual void _setVideoCaptureStatus(VideoCaptureStatus captureStatus)
bool _trackingImageIsActive
mavlink_camera_information_t _mavlinkCameraInfo
static constexpr const char * kCAM_MODE
static constexpr const char * kThermalOpacity
WeakLinkInterfacePtr primaryLink() const
QGCCameraManager * cameraManager()
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)
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
FTPManager * ftpManager()
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").
QString bigSizeMBToString(quint64 sizeMB)
MB-scaled size, output in MB/GB/TB. Input is in MB.
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.