18#include <QtNetwork/QNetworkAccessManager>
20#include <QtCore/QSettings>
21#include <QtXml/QDomDocument>
22#include <QtXml/QDomNodeList>
23#include <QtQml/QQmlEngine>
24#include <QtNetwork/QNetworkReply>
32 , exclusions(exclusions_)
40 , targetParam(targetParam_)
41 , condition(condition_)
43 , optValues(optValues_)
49 QDomNamedNodeMap attrs = node.attributes();
53 QDomNode subNode = attrs.namedItem(tagName);
54 if(subNode.isNull()) {
57 target = subNode.nodeValue() !=
"0";
63 QDomNamedNodeMap attrs = node.attributes();
67 QDomNode subNode = attrs.namedItem(tagName);
68 if(subNode.isNull()) {
71 target = subNode.nodeValue().toInt();
75static bool read_attribute(QDomNode& node,
const char* tagName, QString& target)
77 QDomNamedNodeMap attrs = node.attributes();
81 QDomNode subNode = attrs.namedItem(tagName);
82 if(subNode.isNull()) {
85 target = subNode.nodeValue();
89static bool read_value(QDomNode& element,
const char* tagName, QString& target)
91 QDomElement de = element.firstChildElement(tagName);
103 QQmlEngine::setObjectOwnership(
this, QQmlEngine::CppOwnership);
107 _vendor = QString(
reinterpret_cast<const char*
>(info->vendor_name));
108 _modelName = QString(
reinterpret_cast<const char*
>(info->model_name));
109 _cacheFile = QString::asprintf(
"%s/%s_%s_%03d.xml",
110 SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
115 if(info->cam_definition_uri[0] != 0) {
117 _handleDefinitionFile(info->cam_definition_uri);
145 qCDebug(CameraControlLog) <<
"Camera Info:";
146 qCDebug(CameraControlLog) <<
" vendor:" <<
vendor();
147 qCDebug(CameraControlLog) <<
" model:" <<
modelName();
148 qCDebug(CameraControlLog) <<
" version:" <<
version();
150 qCDebug(CameraControlLog) <<
" focal length:" <<
focalLength();
151 qCDebug(CameraControlLog) <<
" sensor size:" <<
sensorSize();
152 qCDebug(CameraControlLog) <<
" resolution:" <<
resolution();
153 qCDebug(CameraControlLog) <<
" captures video:" <<
capturesVideo();
154 qCDebug(CameraControlLog) <<
" captures photos:" <<
capturesPhotos();
155 qCDebug(CameraControlLog) <<
" has modes:" <<
hasModes();
156 qCDebug(CameraControlLog) <<
" has zoom:" <<
hasZoom();
157 qCDebug(CameraControlLog) <<
" has focus:" <<
hasFocus();
158 qCDebug(CameraControlLog) <<
" has tracking:" <<
hasTracking();
159 qCDebug(CameraControlLog) <<
" has video stream:" <<
hasVideoStream();
180 qCDebug(CameraControlLog) <<
"_initWhenReady()";
182 qCDebug(CameraControlLog) <<
"Basic, MAVLink only messages, no parameters.";
223 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_VIDEO | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
230 return _mavlinkCameraInfo.flags & (CAMERA_CAP_FLAGS_CAPTURE_IMAGE | CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM);
270 return QString::asprintf(
"%d.%d.%d", major, minor, build);
275 return QTime(0, 0).addMSecs(
static_cast<int>(
recordTime())).toString(
"hh:mm:ss");
297 qCWarning(CameraControlLog) <<
"Camera does not support modes";
301 qCDebug(CameraControlLog) <<
"Camera set to video mode";
311 qCWarning(CameraControlLog) <<
"Camera does not support modes";
315 qCDebug(CameraControlLog) <<
"Camera set to photo mode";
325 qCWarning(CameraControlLog) <<
"Camera does not support modes";
329 qCWarning(CameraControlLog) <<
"Invalid camera mode" <<
cameraMode;
347 MAV_CMD_SET_CAMERA_MODE,
423 qCWarning(CameraControlLog) <<
"Take photo denied - photo capture is disabled";
427 qCWarning(CameraControlLog) <<
"Take photo denied - already capturing";
431 qCDebug(CameraControlLog) <<
"takePhoto()";
433 const bool canUseMavlinkImageCapture =
437 if (canUseMavlinkImageCapture) {
440 MAV_CMD_IMAGE_START_CAPTURE,
450 VideoManager::instance()->grabImage();
452 QTimer::singleShot(500,
this, [
this]() {
457 qgcApp()->showAppMessage(tr(
"Timelapse photo capture is not supported on cameras without still capture capability"));
470 qCWarning(CameraControlLog) <<
"Stop taking photos requested - not currently capturing multiple photos";
474 qCDebug(CameraControlLog) <<
"Camera stop taking photos";
479 MAV_CMD_IMAGE_STOP_CAPTURE,
494 qCWarning(CameraControlLog) <<
"Start video denied - already recording";
498 qCWarning(CameraControlLog) <<
"Start video denied - video capture is disabled";
504 qCDebug(CameraControlLog) <<
"Start video recording:" << (useMavlinkCommand ?
"MAVLink command" :
"VideoManager");
506 if (useMavlinkCommand) {
509 MAV_CMD_VIDEO_START_CAPTURE,
515 VideoManager::instance()->startRecording();
527 qCWarning(CameraControlLog) <<
"Stop video recording requested - already idle";
533 qCDebug(CameraControlLog) <<
"Camera stop video recording" << (useMavlinkCommand ?
"MAVLink command" :
"VideoManager");
535 if (useMavlinkCommand) {
538 MAV_CMD_VIDEO_STOP_CAPTURE,
543 VideoManager::instance()->stopRecording();
559 if(val < 0.0) val = 0.0;
560 if(val > 100.0) val = 100.0;
571 qCDebug(CameraControlLog) <<
"Camera set zoom level to" << level;
574 level = std::min(std::max(level, 0.0), 100.0);
578 MAV_CMD_SET_CAMERA_ZOOM,
581 static_cast<float>(level));
588 qCDebug(CameraControlLog) <<
"Camera set focus level to" << level;
591 level = std::min(std::max(level, 0.0), 100.0);
595 MAV_CMD_SET_CAMERA_FOCUS,
598 static_cast<float>(level));
606 qCDebug(CameraControlLog) <<
"resetSettings()";
610 MAV_CMD_RESET_CAMERA_SETTINGS,
619 qCDebug(CameraControlLog) <<
"formatCard()";
623 MAV_CMD_STORAGE_FORMAT,
633 qCDebug(CameraControlLog) <<
"Camera step zoom" << direction;
637 MAV_CMD_SET_CAMERA_ZOOM,
646 qCDebug(CameraControlLog) <<
"Camera start zoom" << direction;
650 MAV_CMD_SET_CAMERA_ZOOM,
652 ZOOM_TYPE_CONTINUOUS,
659 qCDebug(CameraControlLog) <<
"Camera stop zoom";
663 MAV_CMD_SET_CAMERA_ZOOM,
665 ZOOM_TYPE_CONTINUOUS,
675 qCDebug(CameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS";
678 MAV_CMD_REQUEST_MESSAGE,
680 MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS);
682 qCDebug(CameraControlLog) <<
" Sending MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS (legacy)";
685 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS,
694 _updateRanges(pFact);
699 Q_UNUSED(failureCode);
705 if (result == MAV_RESULT_IN_PROGRESS) {
707 qCDebug(CameraControlLog) <<
"In progress response for" << command;
708 }
else if(result == MAV_RESULT_ACCEPTED) {
710 case MAV_CMD_RESET_CAMERA_SETTINGS:
719 case MAV_CMD_VIDEO_START_CAPTURE:
723 case MAV_CMD_VIDEO_STOP_CAPTURE:
727 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
730 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
733 case MAV_CMD_IMAGE_START_CAPTURE:
739 if ((result == MAV_RESULT_TEMPORARILY_REJECTED) || (result == MAV_RESULT_FAILED)) {
740 if (result == MAV_RESULT_TEMPORARILY_REJECTED) {
741 qCDebug(CameraControlLog) <<
"Command temporarily rejected (MAV_RESULT_TEMPORARILY_REJECTED) for" << commandStr;
743 qCDebug(CameraControlLog) <<
"Command failed (MAV_RESULT_FAILED) for" << commandStr;
746 case MAV_CMD_RESET_CAMERA_SETTINGS:
748 qCDebug(CameraControlLog) <<
"Failed to reset camera settings";
750 case MAV_CMD_IMAGE_START_CAPTURE:
751 case MAV_CMD_IMAGE_STOP_CAPTURE:
755 qCDebug(CameraControlLog) <<
"Giving up start/stop image capture";
759 case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
763 qCDebug(CameraControlLog) <<
"Giving up requesting capture status";
766 case MAV_CMD_REQUEST_STORAGE_INFORMATION:
770 qCDebug(CameraControlLog) <<
"Giving up requesting storage status";
824 qCDebug(CameraControlLog) <<
"Set Photo Status:" << captureStatus;
830bool VehicleCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
832 QByteArray originalData(bytes);
834 if(!_handleLocalization(bytes)) {
839 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
841 qCCritical(CameraControlLog) <<
"Unable to parse camera definition file on line:" << result.errorLine;
842 qCCritical(CameraControlLog) << result.errorMessage;
846 QDomNodeList defElements = doc.elementsByTagName(
kDefnition);
847 if(!defElements.size() || !_loadConstants(defElements)) {
848 qCWarning(CameraControlLog) <<
"Unable to load camera constants from camera definition";
852 QDomNodeList paramElements = doc.elementsByTagName(
kParameters);
853 if(!paramElements.size()) {
854 qCDebug(CameraControlLog) <<
"No parameters to load from camera";
857 if(!_loadSettings(paramElements)) {
858 qCWarning(CameraControlLog) <<
"Unable to load camera parameters from camera definition";
863 qCDebug(CameraControlLog) <<
"Saving camera definition file" <<
_cacheFile;
865 if (!file.open(QIODevice::WriteOnly)) {
866 qWarning() << QString(
"Could not save cache file %1. Error: %2").arg(
_cacheFile).arg(file.errorString());
868 file.write(originalData);
874bool VehicleCameraControl::_loadConstants(
const QDomNodeList nodeList)
876 QDomNode node = nodeList.item(0);
889bool VehicleCameraControl::_loadSettings(
const QDomNodeList nodeList)
891 QDomNode node = nodeList.item(0);
892 QDomElement elem = node.toElement();
893 QDomNodeList parameters = elem.elementsByTagName(
kParameter);
895 for(
int i = 0; i < parameters.size(); i++) {
896 QDomNode parameterNode = parameters.item(i);
905 qCritical() <<
"Parameter entry missing parameter name";
910 for(
int i = 0; i < parameters.size(); i++) {
911 QDomNode parameterNode = parameters.item(i);
916 qCritical() << QString(
"Parameter %1 missing parameter type").arg(factName);
923 bool readOnly =
false;
926 bool writeOnly =
false;
929 if(readOnly && writeOnly) {
930 qCritical() << QString(
"Parameter %1 cannot be both read only and write only").arg(factName);
936 qCritical() << QString(
"Unknown type for parameter %1").arg(factName);
946 qCritical() << QString(
"Parameter %1 missing parameter description").arg(factName);
950 QStringList updates = _loadUpdates(parameterNode);
952 qCDebug(CameraControlVerboseLog) <<
"Parameter" << factName <<
"requires updates for:" << updates;
957 QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
964 QDomElement optionElem = parameterNode.toElement();
965 QDomNodeList optionsRoot = optionElem.elementsByTagName(
kOptions);
966 if(optionsRoot.size()) {
968 QDomNode optionsNode = optionsRoot.item(0);
969 QDomElement optionsElem = optionsNode.toElement();
970 QDomNodeList options = optionsElem.elementsByTagName(
kOption);
971 for(
int optionIndex = 0; optionIndex < options.size(); optionIndex++) {
972 QDomNode option = options.item(optionIndex);
976 if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
984 QStringList exclusions = _loadExclusions(option);
985 if(exclusions.size()) {
986 qCDebug(CameraControlVerboseLog) <<
"New exclusions:" << factName << optValue << exclusions;
988 QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
992 if(!_loadRanges(option, factName, optValue)) {
998 QString defaultValue;
1000 QVariant defaultVariant;
1005 qWarning() <<
"Invalid default value for" << factName
1006 <<
" type:" << metaData->
type()
1007 <<
" value:" << defaultValue
1013 qWarning() << QStringLiteral(
"Duplicate fact name:") << factName;
1020 QVariant typedValue;
1025 qWarning() <<
"Invalid min value for" << factName
1026 <<
" type:" << metaData->
type()
1027 <<
" value:" << attr
1036 QVariant typedValue;
1041 qWarning() <<
"Invalid max value for" << factName
1042 <<
" type:" << metaData->
type()
1043 <<
" value:" << attr
1052 QVariant typedValue;
1057 qWarning() <<
"Invalid step value for" << factName
1058 <<
" type:" << metaData->
type()
1059 <<
" value:" << attr
1068 QVariant typedValue;
1073 qWarning() <<
"Invalid decimal places value for" << factName
1074 <<
" type:" << metaData->
type()
1075 <<
" value:" << attr
1087 qCDebug(CameraControlLog) <<
"New parameter:" << factName << (readOnly ?
"ReadOnly" :
"Writable") << (writeOnly ?
"WriteOnly" :
"Readable");
1090 QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
1091 pFact->setMetaData(metaData);
1094 QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
1109bool VehicleCameraControl::_handleLocalization(QByteArray& bytes)
1112 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
1114 qCritical() <<
"Unable to parse camera definition file on line:" << result.errorLine;
1115 qCritical() << result.errorMessage;
1119 QLocale locale = QLocale::system();
1120#if defined (Q_OS_MACOS)
1121 locale = QLocale(locale.name());
1123 QString localeName = locale.name().toLower().replace(
"-",
"_");
1124 qCDebug(CameraControlLog) <<
"Current locale:" << localeName;
1125 if(localeName ==
"en_us") {
1129 QDomNodeList locRoot = doc.elementsByTagName(
kLocalization);
1130 if(!locRoot.size()) {
1135 QDomNode node = locRoot.item(0);
1136 QDomElement elem = node.toElement();
1137 QDomNodeList locales = elem.elementsByTagName(
kLocale);
1138 for(
int i = 0; i < locales.size(); i++) {
1139 QDomNode localeNode = locales.item(i);
1142 qWarning() <<
"Localization entry is missing its name attribute";
1146 if(localeName == name.toLower().replace(
"-",
"_")) {
1147 return _replaceLocaleStrings(localeNode, bytes);
1151 localeName = localeName.left(3);
1152 for(
int i = 0; i < locales.size(); i++) {
1153 QDomNode localeNode = locales.item(i);
1156 if(name.toLower().startsWith(localeName)) {
1157 return _replaceLocaleStrings(localeNode, bytes);
1161 qWarning() <<
"No match for" << QLocale::system().name() <<
"in camera definition file";
1166bool VehicleCameraControl::_replaceLocaleStrings(
const QDomNode node, QByteArray& bytes)
1168 QDomElement stringElem = node.toElement();
1169 QDomNodeList strings = stringElem.elementsByTagName(
kStrings);
1170 for(
int i = 0; i < strings.size(); i++) {
1171 QDomNode stringNode = strings.item(i);
1176 QString o; o =
"\"" + original +
"\"";
1177 QString t; t =
"\"" + translated +
"\"";
1178 bytes.replace(o.toUtf8(), t.toUtf8());
1179 o =
">" + original +
"<";
1180 t =
">" + translated +
"<";
1181 bytes.replace(o.toUtf8(), t.toUtf8());
1191 for(
const QString& paramName:
_paramIO.keys()) {
1193 _paramIO[paramName]->setParamRequest();
1195 qCritical() <<
"QGCParamIO is NULL" << paramName;
1201 mavlink_msg_param_ext_request_list_pack_chan(
1204 sharedLink->mavlinkChannel(),
1207 static_cast<uint8_t
>(
compID()));
1210 qCDebug(CameraControlVerboseLog) <<
"Request all parameters";
1213QString VehicleCameraControl::_getParamName(
const char* param_id)
1216 char parameterNameWithNull[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1] = {};
1217 (void) strncpy(parameterNameWithNull, param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
1218 const QString parameterName(parameterNameWithNull);
1219 return parameterName;
1224 QString paramName = _getParamName(paramExtAck.param_id);
1225 qCDebug(CameraControlLog).noquote() <<
"Received PARAM_EXT_ACK:"
1226 <<
"\n\tParam name:" << paramName
1227 <<
"\n\tResult:" <<
static_cast<int>(paramExtAck.param_result)
1228 <<
"\n\tType:" <<
static_cast<int>(paramExtAck.param_type);
1230 if(!
_paramIO.contains(paramName)) {
1231 qCWarning(CameraControlLog) <<
"Received PARAM_EXT_ACK for unknown param:" << paramName;
1235 _paramIO[paramName]->handleParamAck(paramExtAck);
1237 qCritical() <<
"QGCParamIO is NULL" << paramName;
1243 QString paramName = _getParamName(paramExtValue.param_id);
1244 qCDebug(CameraControlLog).noquote() <<
"Received PARAM_EXT_VALUE:"
1245 <<
"\n\tParam name:" << paramName
1246 <<
"\n\tType:" <<
static_cast<int>(paramExtValue.param_type)
1247 <<
"\n\tIndex:" <<
static_cast<int>(paramExtValue.param_index)
1248 <<
"\n\tCount:" <<
static_cast<int>(paramExtValue.param_count);
1250 if(!
_paramIO.contains(paramName)) {
1251 qCWarning(CameraControlLog) <<
"Received PARAM_EXT_VALUE for unknown param:" << paramName;
1255 _paramIO[paramName]->handleParamValue(paramExtValue);
1257 qCritical() <<
"QGCParamIO is NULL" << paramName;
1261void VehicleCameraControl::_updateActiveList()
1264 QStringList exclusionList;
1266 Fact* pFact = getFact(param->param);
1268 QString option = pFact->rawValueString();
1269 if(param->value == option) {
1270 exclusionList << param->exclusions;
1276 if(!exclusionList.contains(key)) {
1281 qCDebug(CameraControlVerboseLog) <<
"Excluding" << exclusionList;
1291bool VehicleCameraControl::_processConditionTest(
const QString conditionTest)
1300 qCDebug(CameraControlVerboseLog) <<
"_processConditionTest(" << conditionTest <<
")";
1304 auto split = [&conditionTest](
const QString& sep ) {
1305 return conditionTest.split(sep, Qt::SkipEmptyParts);
1308 if(conditionTest.contains(
"!=")) {
1310 op = TEST_NOT_EQUAL;
1311 }
else if(conditionTest.contains(
"=")) {
1314 }
else if(conditionTest.contains(
">")) {
1317 }
else if(conditionTest.contains(
"<")) {
1321 if(test.size() == 2) {
1322 Fact* pFact = getFact(test[0]);
1326 return pFact->rawValueString() == test[1];
1327 case TEST_NOT_EQUAL:
1328 return pFact->rawValueString() != test[1];
1330 return pFact->rawValueString() > test[1];
1332 return pFact->rawValueString() < test[1];
1337 qWarning() <<
"Invalid condition parameter:" << test[0] <<
"in" << conditionTest;
1341 qWarning() <<
"Invalid condition" << conditionTest;
1345bool VehicleCameraControl::_processCondition(
const QString condition)
1347 qCDebug(CameraControlVerboseLog) <<
"_processCondition(" << condition <<
")";
1350 if(!condition.isEmpty()) {
1351 QStringList scond = condition.split(
" ", Qt::SkipEmptyParts);
1352 while(scond.size()) {
1353 QString test = scond.first();
1354 scond.removeFirst();
1356 result = result && _processConditionTest(test);
1358 result = result || _processConditionTest(test);
1363 andOp = scond.first().toUpper() ==
"AND";
1364 scond.removeFirst();
1370void VehicleCameraControl::_updateRanges(
Fact* pFact)
1372 QMap<Fact*, QGCCameraOptionRange*> rangesSet;
1373 QMap<Fact*, QString> rangesReset;
1374 QStringList changedList;
1375 QStringList resetList;
1376 QStringList updates;
1380 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
1381 Fact* pRFact = getFact(pRange->param);
1382 Fact* pTFact = getFact(pRange->targetParam);
1383 if(pRFact && pTFact) {
1385 QString option = pRFact->rawValueString();
1388 if(pRange->value == option && _processCondition(pRange->condition)) {
1389 if(pTFact->enumStrings() != pRange->optNames) {
1391 rangesSet[pTFact] = pRange;
1393 changedList << pRange->targetParam;
1400 if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
1401 Fact* pTFact = getFact(pRange->targetParam);
1402 if(!resetList.contains(pRange->targetParam)) {
1405 rangesReset[pTFact] = pRange->targetParam;
1407 resetList << pRange->targetParam;
1412 for (
Fact* f: rangesSet.keys()) {
1413 f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
1414 if(!updates.contains(f->name())) {
1415 emit f->enumsChanged();
1416 qCDebug(CameraControlVerboseLog) <<
"Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
1417 updates << f->name();
1421 for (
Fact* f: rangesReset.keys()) {
1423 if(!updates.contains(f->name())) {
1424 emit f->enumsChanged();
1425 qCDebug(CameraControlVerboseLog) <<
"Restore full set of options for:" << f->name() <<
_originalOptNames[f->name()];
1426 updates << f->name();
1458 qCDebug(CameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_CAMERA_SETTINGS";
1461 MAV_CMD_REQUEST_MESSAGE,
1463 MAVLINK_MSG_ID_CAMERA_SETTINGS);
1465 qCDebug(CameraControlLog) <<
" Sending MAV_CMD_REQUEST_CAMERA_SETTINGS (legacy)";
1468 MAV_CMD_REQUEST_CAMERA_SETTINGS,
1473 qCDebug(CameraControlLog) <<
"_requestCameraSettings() - RESTARTING already active timer";
1475 qCDebug(CameraControlLog) <<
"_requestCameraSettings() - starting timer";
1489 qCDebug(CameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_STORAGE_INFORMATION";
1492 MAV_CMD_REQUEST_MESSAGE,
1494 MAVLINK_MSG_ID_STORAGE_INFORMATION,
1497 qCDebug(CameraControlLog) <<
" Sending MAV_CMD_REQUEST_STORAGE_INFORMATION (legacy)";
1500 MAV_CMD_REQUEST_STORAGE_INFORMATION,
1505 qCDebug(CameraControlLog) <<
"_requestStorageInfo() - starting timer";
1512 qCDebug(CameraControlLog).noquote() <<
"Received CAMERA_SETTINGS - stopping timer, resetting retries:"
1513 <<
"\n\tMode:" << settings.mode_id
1514 <<
"\n\tZoom level:" << settings.zoomLevel
1515 <<
"\n\tFocus level:" << settings.focusLevel;
1521 qreal z =
static_cast<qreal
>(settings.zoomLevel);
1522 qreal f =
static_cast<qreal
>(settings.focusLevel);
1535 qCDebug(CameraControlLog) <<
"Received STORAGE_INFORMATION - stopping timer, resetting retries:"
1536 <<
"\n\tStorage id:" << storageInformation.storage_id
1537 <<
"\n\tStorage count:" << storageInformation.storage_count
1539 <<
"\n\tTotal capacity:" << storageInformation.total_capacity
1540 <<
"\n\tUsed capacity:" << storageInformation.used_capacity
1541 <<
"\n\tAvailable capacity:" << storageInformation.available_capacity;
1546 if(storageInformation.status == STORAGE_STATUS_READY) {
1547 uint32_t t =
static_cast<uint32_t
>(storageInformation.total_capacity);
1552 uint32_t a =
static_cast<uint32_t
>(storageInformation.available_capacity);
1566 qCDebug(CameraControlLog).noquote() <<
"Received BATTERY_STATUS:"
1567 <<
"\n\tBattery remaining (%):" << bs.battery_remaining;
1569 if(bs.battery_remaining >= 0 &&
_batteryRemaining !=
static_cast<int>(bs.battery_remaining)) {
1577 qCDebug(CameraControlLog).noquote() <<
"Received CAMERA_CAPTURE_STATUS - stopping timer, resetting retries:"
1580 <<
"\n\tInterval:" << cameraCaptureStatus.image_interval
1581 <<
"\n\tRecording time (ms):" << cameraCaptureStatus.recording_time_ms
1582 <<
"\n\tCapacity:" << cameraCaptureStatus.available_capacity;
1588 uint32_t a =
static_cast<uint32_t
>(cameraCaptureStatus.available_capacity);
1594 if(cameraCaptureStatus.recording_time_ms) {
1596 _recordTime = cameraCaptureStatus.recording_time_ms;
1597 _recTime =
_recTime.addMSecs(
_recTime.msecsTo(QTime::currentTime()) -
static_cast<int>(cameraCaptureStatus.recording_time_ms));
1615 const QString photoDir = SettingsManager::instance()->appSettings()->
savePath()->rawValue().toString() + QStringLiteral(
"/Photo");
1617 const QString photoPath = photoDir +
"/" + QDateTime::currentDateTime().toString(
"yyyy-MM-dd_hh.mm.ss.zzz") +
".jpg";
1618 VideoManager::instance()->grabImage(photoPath);
1624 qCDebug(CameraControlLog).noquote() <<
"Received VIDEO_STREAM_INFORMATION:"
1625 <<
"\n\tStream ID:" << videoStreamInformation.stream_id
1626 <<
"\n\tStream count:" << videoStreamInformation.count
1627 <<
"\n\tType:" <<
static_cast<int>(videoStreamInformation.type)
1628 <<
"\n\tFlags:" << Qt::hex << Qt::showbase << videoStreamInformation.flags << Qt::dec << Qt::noshowbase
1629 <<
"\n\tBitrate (bits/s):" << videoStreamInformation.bitrate
1630 <<
"\n\tFramerate (fps):" << videoStreamInformation.framerate
1631 <<
"\n\tResolution:" << videoStreamInformation.resolution_h <<
"x" << videoStreamInformation.resolution_v
1632 <<
"\n\tRotation (deg):" << videoStreamInformation.rotation
1633 <<
"\n\tHFOV (deg):" << videoStreamInformation.hfov
1634 <<
"\n\tURI:" << videoStreamInformation.uri;
1637 if(!
_findStream(videoStreamInformation.stream_id,
false)) {
1638 qCDebug(CameraControlLog) <<
"Create stream handler for stream ID:" << videoStreamInformation.stream_id;
1640 QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
1643 if(!pStream->isThermal()) {
1656 qCDebug(CameraControlLog) <<
"All stream handlers done";
1660 emit
_vehicle->cameraManager()->streamChanged();
1666 qCDebug(CameraControlLog) <<
"Received VIDEO_STREAM_STATUS - stopping timer, resetting retries:"
1667 <<
"\n\tStream ID:" << videoStreamStatus.stream_id
1668 <<
"\n\tFlags:" << Qt::hex << Qt::showbase << videoStreamStatus.flags << Qt::dec << Qt::noshowbase
1669 <<
"\n\tBitrate (bits/s):" << videoStreamStatus.bitrate
1670 <<
"\n\tFramerate (fps):" << videoStreamStatus.framerate
1671 <<
"\n\tResolution: " << videoStreamStatus.resolution_h <<
"x" << videoStreamStatus.resolution_v
1672 <<
"\n\tRotation (deg):" << videoStreamStatus.rotation
1673 <<
"\n\tHFOV (deg):" << videoStreamStatus.hfov;
1680 pInfo->update(videoStreamStatus);
1686 qCDebug(CameraControlLog).noquote() <<
"Received CAMERA_TRACKING_IMAGE_STATUS:"
1698 qCDebug(CameraControlLog) <<
"Tracking off";
1705 if (qIsNaN(r) || r <= 0 ) {
1718 qCDebug(CameraControlLog) <<
"Tracking Image Status [left:" <<
_trackingImageRect.left()
1732 qCDebug(CameraControlLog) <<
"Stopping stream:" << pInfo->uri();
1736 MAV_CMD_VIDEO_STOP_STREAMING,
1744 qCDebug(CameraControlLog) <<
"Starting stream:" << pInfo->uri();
1747 MAV_CMD_VIDEO_START_STREAMING,
1754 emit
_vehicle->cameraManager()->streamChanged();
1765 MAV_CMD_VIDEO_STOP_STREAMING,
1778 MAV_CMD_VIDEO_START_STREAMING,
1810 if(pStream->isThermal()) {
1821 qCDebug(CameraControlLog) <<
"_requestStreamInfo() - stream:" << streamID <<
"retries:" <<
_videoStreamInfoRetries;
1825 qCDebug(CameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION";
1828 MAV_CMD_REQUEST_MESSAGE,
1830 MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION,
1833 qCDebug(CameraControlLog) <<
" Sending MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION (legacy)";
1836 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION,
1849 qCDebug(CameraControlLog) <<
" Sending REQUEST_MESSAGE:MAVLINK_MSG_ID_VIDEO_STREAM_STATUS";
1852 MAV_CMD_REQUEST_MESSAGE,
1854 MAVLINK_MSG_ID_VIDEO_STREAM_STATUS,
1857 qCDebug(CameraControlLog) <<
" Sending MAV_CMD_REQUEST_VIDEO_STREAM_STATUS (legacy)";
1860 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS,
1874 if(pStream->streamID() ==
id) {
1878 qCritical() <<
"Null QGCVideoStreamInfo instance";
1883 qWarning() <<
"Stream id not found:" << id;
1895 if(pStream->name() == name) {
1909 qCWarning(CameraControlLog) <<
"Giving up requesting video stream info";
1914 emit
_vehicle->cameraManager()->streamChanged();
1931 qCWarning(CameraControlLog) <<
"Giving up requesting video stream status";
1946 qCWarning(CameraControlLog) <<
"Giving up requesting camera settings after" <<
_cameraSettingsRetries <<
"retries";
1950 qCDebug(CameraControlLog) <<
"_cameraSettingsTimeout() - calling _requestCameraSettings()";
1957 qCDebug(CameraControlLog) <<
"_storageInfoTimeout() - retries now:" <<
_storageInfoRetries;
1959 qCWarning(CameraControlLog) <<
"Giving up requesting storage info after" <<
_storageInfoRetries <<
"retries";
1963 qCDebug(CameraControlLog) <<
"_storageInfoTimeout() - calling _requestStorageInfo()";
1968VehicleCameraControl::_loadExclusions(QDomNode option)
1970 QStringList exclusionList;
1971 QDomElement optionElem = option.toElement();
1972 QDomNodeList excRoot = optionElem.elementsByTagName(
kExclusions);
1973 if(excRoot.size()) {
1975 QDomNode node = excRoot.item(0);
1976 QDomElement elem = node.toElement();
1977 QDomNodeList exclusions = elem.elementsByTagName(
kExclusion);
1978 for(
int i = 0; i < exclusions.size(); i++) {
1979 QString exclude = exclusions.item(i).toElement().text();
1980 if(!exclude.isEmpty()) {
1981 exclusionList << exclude;
1985 return exclusionList;
1989VehicleCameraControl::_loadUpdates(QDomNode option)
1991 QStringList updateList;
1992 QDomElement optionElem = option.toElement();
1993 QDomNodeList updateRoot = optionElem.elementsByTagName(
kUpdates);
1994 if(updateRoot.size()) {
1996 QDomNode node = updateRoot.item(0);
1997 QDomElement elem = node.toElement();
1998 QDomNodeList updates = elem.elementsByTagName(
kUpdate);
1999 for(
int i = 0; i < updates.size(); i++) {
2000 QString update = updates.item(i).toElement().text();
2001 if(!update.isEmpty()) {
2002 updateList << update;
2009bool VehicleCameraControl::_loadRanges(QDomNode option,
const QString factName, QString paramValue)
2011 QDomElement optionElem = option.toElement();
2013 if(rangeRoot.size()) {
2014 QDomNode node = rangeRoot.item(0);
2015 QDomElement elem = node.toElement();
2016 QDomNodeList parameterRanges = elem.elementsByTagName(
kParameterrange);
2018 for(
int i = 0; i < parameterRanges.size(); i++) {
2021 QDomNode paramRange = parameterRanges.item(i);
2023 qCritical() << QString(
"Malformed option range for parameter %1").arg(factName);
2027 QDomElement pelem = paramRange.toElement();
2028 QDomNodeList rangeOptions = pelem.elementsByTagName(
kRoption);
2029 QStringList optNames;
2030 QStringList optValues;
2032 for(
int rangeOptionIndex = 0; rangeOptionIndex < rangeOptions.size(); rangeOptionIndex++) {
2035 QDomNode roption = rangeOptions.item(rangeOptionIndex);
2037 qCritical() << QString(
"Malformed roption for parameter %1").arg(factName);
2041 qCritical() << QString(
"Malformed rvalue for parameter %1").arg(factName);
2044 optNames << optName;
2045 optValues << optValue;
2047 if(optNames.size()) {
2050 qCDebug(CameraControlVerboseLog) <<
"New range limit:" << factName << paramValue << param << condition << optNames << optValues;
2057void VehicleCameraControl::_processRanges()
2061 Fact* pRFact = getFact(pRange->targetParam);
2063 for(
int i = 0; i < pRange->optNames.size(); i++) {
2064 QVariant optVariant;
2067 qWarning() <<
"Invalid roption value, name:" << pRange->targetParam
2068 <<
" type:" << pRFact->metaData()->
type()
2069 <<
" value:" << pRange->optValues[i]
2072 pRange->optVariants << optVariant;
2079bool VehicleCameraControl::_loadNameValue(QDomNode option,
const QString factName,
FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant)
2082 qCritical() << QString(
"Malformed option for parameter %1").arg(factName);
2086 qCritical() << QString(
"Malformed value for parameter %1").arg(factName);
2091 qWarning() <<
"Invalid option value, name:" << factName
2092 <<
" type:" << metaData->
type()
2093 <<
" value:" << optValue
2099void VehicleCameraControl::_handleDefinitionFile(
const QString &url)
2105 if (!xmlFile.exists() && url.startsWith(ftpPrefix, Qt::CaseInsensitive)) {
2106 qCDebug(CameraControlLog) <<
"No camera definition file cached, attempt ftp download";
2109 if (url.endsWith(
".lzma", Qt::CaseInsensitive)) { ext =
".lzma"; }
2110 if (url.endsWith(
".xz", Qt::CaseInsensitive)) { ext =
".xz"; }
2111 QString fileName = QString::asprintf(
"%s_%s_%03d.xml%s",
2112 _vendor.toStdString().c_str(),
2115 ext.toStdString().c_str());
2118 SettingsManager::instance()->appSettings()->parameterSavePath().toStdString().c_str(),
2123 if (!xmlFile.exists()) {
2124 qCDebug(CameraControlLog) <<
"No camera definition file cached, attempt http download";
2128 if (!xmlFile.open(QIODevice::ReadOnly)) {
2129 qWarning() <<
"Could not read cached camera definition file:" <<
_cacheFile;
2133 QByteArray bytes = xmlFile.readAll();
2135 const QDomDocument::ParseResult result = doc.setContent(bytes, QDomDocument::ParseOption::Default);
2137 qWarning() <<
"Could not parse cached camera definition file:" <<
_cacheFile;
2142 qCDebug(CameraControlLog) <<
"Using cached camera definition file:" <<
_cacheFile;
2147void VehicleCameraControl::_httpRequest(
const QString &url)
2149 qCDebug(CameraControlLog) <<
"Request camera definition:" << url;
2154 QNetworkRequest request(QUrl::fromUserInput(url));
2155 request.setAttribute(QNetworkRequest::RedirectPolicyAttribute,
true);
2156 QSslConfiguration conf = request.sslConfiguration();
2157 conf.setPeerVerifyMode(QSslSocket::VerifyNone);
2158 request.setSslConfiguration(conf);
2165 QNetworkReply* reply = qobject_cast<QNetworkReply*>(sender());
2169 int err = reply->error();
2170 int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
2171 QByteArray data = reply->readAll();
2172 if(err == QNetworkReply::NoError && http_code == 200) {
2176 qWarning() << QString(
"Camera Definition (%1) download error: %2 status: %3").arg(
2177 reply->url().toDisplayString(),
2178 reply->errorString(),
2179 reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString()
2186void VehicleCameraControl::_ftpDownloadComplete(
const QString& fileName,
const QString& errorMsg)
2188 qCDebug(CameraControlLog) <<
"FTP Download completed: " << fileName <<
", " << errorMsg;
2193 if (outputFileName.isEmpty()) {
2194 qCWarning(CameraControlLog) <<
"Inflate of compressed xml failed" << fileName;
2197 QFile xmlFile(outputFileName);
2199 if (!xmlFile.exists()) {
2200 qCDebug(CameraControlLog) <<
"No camera definition file present after ftp download completed";
2203 if (!xmlFile.open(QIODevice::ReadOnly)) {
2204 qWarning() <<
"Could not read downloaded camera definition file: " << fileName;
2209 QByteArray bytes = xmlFile.readAll();
2216 qCDebug(CameraControlLog) <<
"Parsing camera definition";
2217 _loadCameraDefinitionFile(data);
2219 qCDebug(CameraControlLog) <<
"No camera definition received, trying to search on our own...";
2220 QFile definitionFile;
2221 if(QGCCorePlugin::instance()->getOfflineCameraDefinitionFile(
_modelName, definitionFile)) {
2222 qCDebug(CameraControlLog) <<
"Found offline definition file for: " <<
_modelName <<
", loading: " << definitionFile.fileName();
2223 if (definitionFile.open(QIODevice::ReadOnly)) {
2224 QByteArray newData = definitionFile.readAll();
2225 _loadCameraDefinitionFile(newData);
2227 qCDebug(CameraControlLog) <<
"error opening offline definition file for: " <<
_modelName;
2230 qCDebug(CameraControlLog) <<
"No offline camera definition file found";
2238 for(
const QString& param:
_paramIO.keys()) {
2239 if(!
_paramIO[param]->paramDone()) {
2339 qCDebug(CameraControlLog) <<
"Start Tracking (Rectangle: ["
2340 <<
static_cast<float>(rec.x()) <<
", "
2341 <<
static_cast<float>(rec.y()) <<
"] - ["
2342 <<
static_cast<float>(rec.x() + rec.width()) <<
", "
2343 <<
static_cast<float>(rec.y() + rec.height()) <<
"]";
2346 MAV_CMD_CAMERA_TRACK_RECTANGLE,
2348 static_cast<float>(rec.x()),
2349 static_cast<float>(rec.y()),
2350 static_cast<float>(rec.x() + rec.width()),
2351 static_cast<float>(rec.y() + rec.height()));
2364 qCDebug(CameraControlLog) <<
"Start Tracking (Point: ["
2365 <<
static_cast<float>(point.x()) <<
", "
2366 <<
static_cast<float>(point.y()) <<
"], Radius: "
2367 <<
static_cast<float>(radius);
2370 MAV_CMD_CAMERA_TRACK_POINT,
2372 static_cast<float>(point.x()),
2373 static_cast<float>(point.y()),
2374 static_cast<float>(radius));
2383 qCDebug(CameraControlLog) <<
"Stop Tracking";
2387 MAV_CMD_CAMERA_STOP_TRACKING,
2392 MAV_CMD_SET_MESSAGE_INTERVAL,
2394 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
2404 MAV_CMD_SET_MESSAGE_INTERVAL,
2406 MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS,
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
static bool read_value(QDomNode &element, const char *tagName, QString &target)
static bool read_attribute(QDomNode &node, const char *tagName, bool &target)
Fact *savePath READ savePath CONSTANT Fact * savePath()
static constexpr const char * mavlinkFTPScheme
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
void _addFactGroup(FactGroup *factGroup, const QString &name)
void _addFact(Fact *fact, const QString &name)
A Fact is used to hold a single value within the system.
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
Abstract base class for all camera controls: real and simulated.
void photoCaptureModeChanged()
virtual CameraMode cameraMode() const
void trackingEnabledChanged()
void photoCaptureStatusChanged()
QString storageStatusToStr(uint8_t status)
PhotoCaptureStatus _photoCaptureStatus() const
QString captureVideoStatusToStr(uint8_t video_status)
void dataReady(const QByteArray &data)
void trackingImageStatusChanged()
void thermalOpacityChanged()
void storageFreeChanged()
void storageTotalChanged()
@ CapturePhotosStateCapturingMultiplePhotos
@ CapturePhotosStateCapturingSinglePhoto
@ CapturePhotosStateDisabled
void streamLabelsChanged()
QTimer _videoRecordTimeUpdateTimer
VideoCaptureStatus _videoCaptureStatus() const
PhotoCaptureStatus _photoCaptureStatusValue
void videoCaptureStatusChanged()
void thermalStreamChanged()
void capturePhotosStateChanged()
void captureVideoStateChanged()
void photoLapseCountChanged()
void currentStreamChanged()
@ PHOTO_CAPTURE_IN_PROGRESS
@ PHOTO_CAPTURE_STATUS_UNDEFINED
@ PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
@ PHOTO_CAPTURE_INTERVAL_IDLE
void storageStatusChanged()
void thermalModeChanged()
@ CaptureVideoStateDisabled
@ CaptureVideoStateCapturing
QString cameraModeToStr(CameraMode mode)
QString captureImageStatusToStr(uint8_t image_status)
void batteryRemainingChanged()
@ VIDEO_CAPTURE_STATUS_RUNNING
@ VIDEO_CAPTURE_STATUS_UNDEFINED
@ VIDEO_CAPTURE_STATUS_STOPPED
@ VIDEO_CAPTURE_STATUS_LAST
PhotoCaptureMode _photoCaptureMode
virtual PhotoCaptureMode photoCaptureMode() const
void activeSettingsChanged()
VideoCaptureStatus _videoCaptureStatusValue
static MissionCommandTree * instance()
QString rawName(MAV_CMD command) const
Returns the raw name for the specified command.
Camera option exclusions.
QGCCameraOptionExclusion(QObject *parent, QString param_, QString value_, QStringList exclusions_)
QGCCameraOptionRange(QObject *parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_)
Camera parameter handler.
static QString mavResultToString(uint8_t result)
Encapsulates the contents of a VIDEO_STREAM_INFORMATION message.
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
virtual void _storageInfoTimeout()
QStringList _updatesToRequest
QRectF _trackingImageRect
virtual QGCVideoStreamInfo * thermalStreamInstance()
static constexpr const char * kCAM_ISO
virtual void _paramDone()
virtual void toggleCameraMode()
virtual void _downloadFinished()
virtual void _streamInfoTimeout()
static constexpr const char * kRoption
virtual void _streamStatusTimeout()
virtual void _requestAllParameters()
virtual bool trackingEnabled() const
QTimer _cameraSettingsTimer
static constexpr const char * kName
virtual void handleCameraCaptureStatus(const mavlink_camera_capture_status_t &cameraCaptureStatus)
virtual bool trackingImageStatus() const
QList< QGCCameraOptionRange * > _optionRanges
virtual bool startVideoRecording()
virtual quint32 recordTime() const
virtual bool stopVideoRecording()
static constexpr const char * kType
virtual CapturePhotosState capturePhotosState() const
static constexpr const char * kModel
virtual int version() const
virtual void setPhotoCaptureMode(PhotoCaptureMode mode)
virtual void handleCameraSettings(const mavlink_camera_settings_t &settings)
virtual bool photosInVideoMode() const
mavlink_camera_tracking_image_status_t _trackingImageStatus
virtual bool videoInPhotoMode() const
virtual Fact * aperture()
static constexpr const char * kDescription
virtual void _checkForVideoStreams()
virtual void _onVideoManagerRecordingChanged(bool recording)
static constexpr const char * kUpdate
virtual bool hasTracking() const
QmlObjectListModel _streams
virtual void handleTrackingImageStatus(const mavlink_camera_tracking_image_status_t &trackingImageStatus)
virtual void _requestStorageInfo()
static constexpr const char * kDecimalPlaces
static constexpr const char * kOptions
virtual bool hasVideoStream() const
virtual void setCameraModeVideo()
virtual void _dataReady(QByteArray data)
virtual QString firmwareVersion() const
virtual void _initWhenReady()
virtual Fact * exposureMode()
virtual void _requestParamUpdates()
int _videoStreamInfoRetries
virtual QString vendor() const
static constexpr const char * kControl
static constexpr const char * kVersion
virtual void setZoomLevel(qreal level)
virtual void setCurrentStream(int stream)
virtual QString recordTimeStr() const
virtual QString storageFreeStr() const
virtual void handleStorageInformation(const mavlink_storage_information_t &storageInformation)
int _videoStreamStatusRetries
static constexpr const char * kWriteOnly
VehicleCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject *parent=nullptr)
static constexpr const char * kCAM_EXPMODE
virtual void _cameraSettingsTimeout()
static constexpr const char * kPhotoLapse
virtual void setCameraMode(CameraMode cameraMode)
virtual qreal focalLength() const
virtual void resumeStream()
static constexpr const char * kCAM_APERTURE
virtual void setThermalMode(ThermalViewMode mode)
virtual void stepZoom(int direction)
static constexpr const char * kTranslated
virtual void resetSettings()
virtual void setCameraModePhoto()
virtual void stopTracking()
TrackingStatus _trackingStatus
static constexpr const char * kParameterranges
virtual void setFocusLevel(qreal level)
virtual bool capturesPhotos() const
ThermalViewMode _thermalMode
QTimer _streamStatusTimer
static constexpr const char * kUnit
virtual QSizeF sensorSize() const
virtual bool autoStream() const
virtual void stopStream()
static constexpr const char * kDefnition
virtual QString modelName() const
static constexpr const char * kVendor
static constexpr const char * kOriginal
QList< QGCCameraOptionExclusion * > _valueExclusions
virtual bool hasFocus() const
virtual void handleVideoStreamStatus(const mavlink_video_stream_status_t &videoStreamStatus)
static constexpr const char * kCAM_SHUTTERSPD
virtual QSize resolution() const
virtual void _requestTrackingStatus()
virtual bool stopTakePhoto()
static constexpr const char * kDefault
static constexpr const char * kMin
virtual bool isBasic() const
virtual void startTracking(QRectF rec)
virtual void _setCameraMode(CameraMode mode)
virtual QGCVideoStreamInfo * currentStreamInstance()
virtual void factChanged(Fact *pFact)
Notify controller a parameter has changed.
virtual void _requestStreamInfo(uint8_t streamID)
virtual void handleBatteryStatus(const mavlink_battery_status_t &bs)
virtual bool validateParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate parameter change.
QStringList _activeSettings
QMap< QString, QGCCameraParamIO * > _paramIO
static constexpr const char * kPhotoLapseCount
static constexpr const char * kExclusions
static constexpr const char * kLocale
static constexpr const char * kCondition
static constexpr const char * kThermalMode
static constexpr const char * kMax
virtual bool hasModes() const
virtual void _mavCommandResult(int vehicleId, int component, int command, int result, int failureCode)
static constexpr const char * kStep
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)
Allow controller to modify or invalidate incoming parameter.
virtual void _requestStreamStatus(uint8_t streamID)
virtual QStringList activeSettings() const
static constexpr const char * kOption
virtual int compID() const
QTimer _captureStatusTimer
virtual bool toggleVideoRecording()
virtual void _recTimerHandler()
virtual void formatCard(int id=1)
static constexpr const char * kExclusion
virtual void setThermalOpacity(double val)
static constexpr const char * kStrings
QMap< QString, QVariantList > _originalOptValues
virtual void handleVideoStreamInformation(const mavlink_video_stream_information_t &videoStreamInformation)
QMap< QString, QStringList > _originalOptNames
virtual void handleParamExtAck(const mavlink_param_ext_ack_t ¶mExtAck)
static constexpr const char * kPhotoMode
QStringList _streamLabels
static constexpr const char * kReadOnly
virtual void _requestCaptureStatus()
virtual CaptureVideoState captureVideoState() const
virtual bool hasZoom() const
virtual bool capturesVideo() const
static constexpr const char * kParameter
virtual Fact * shutterSpeed()
static constexpr const char * kValue
virtual QGCVideoStreamInfo * _findStream(uint8_t streamID, bool report=true)
static constexpr const char * kUpdates
int _cameraCaptureStatusRetries
QMap< QString, QStringList > _requestUpdates
virtual void setPhotoLapse(qreal interval)
static constexpr const char * kParameterrange
static constexpr const char * kParameters
virtual void setPhotoLapseCount(int count)
virtual void _requestCameraSettings()
static constexpr const char * kCAM_EV
int _cameraSettingsRetries
StorageStatus _storageStatus
virtual ~VehicleCameraControl()
QNetworkAccessManager * _netManager
virtual QString batteryRemainingStr() const
virtual void startZoom(int direction)
static constexpr const char * kLocalization
virtual void _setPhotoCaptureStatus(PhotoCaptureStatus captureStatus)
static constexpr const char * kCAM_WBMODE
virtual void setTrackingEnabled(bool set)
virtual void handleParamExtValue(const mavlink_param_ext_value_t ¶mExtValue)
virtual void _setVideoCaptureStatus(VideoCaptureStatus captureStatus)
mavlink_camera_information_t _mavlinkCameraInfo
static constexpr const char * kCAM_MODE
static constexpr const char * kThermalOpacity
WeakLinkInterfacePtr primaryLink() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
FTPManager * ftpManager()
void mavCommandResult(int vehicleId, int targetComponent, int command, int ackResult, int failureCode)
void recordingChanged(bool recording)
QString decompressIfNeeded(const QString &filePath, const QString &outputPath, bool removeOriginal)
bool ensureDirectoryExists(const QString &path)
void configureProxy(QNetworkAccessManager *manager)
Set up default proxy configuration on a network manager.