Newer
Older
if(read_attribute(parameterNode, kMax, attr)) {
QVariant typedValue;
QString errorString;
if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawMax(typedValue);
} else {
qWarning() << "Invalid max value for" << factName
<< " type:" << metaData->type()
<< " value:" << attr
<< " error:" << errorString;
}
}
}
{
//-- Check for Step Value
QString attr;
if(read_attribute(parameterNode, kStep, attr)) {
QVariant typedValue;
QString errorString;
if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawIncrement(typedValue.toDouble());
} else {
qWarning() << "Invalid step value for" << factName
<< " type:" << metaData->type()
<< " value:" << attr
<< " error:" << errorString;
}
}
}
{
//-- Check for Decimal Places
QString attr;
if(read_attribute(parameterNode, kDecimalPlaces, attr)) {
QVariant typedValue;
QString errorString;
if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
metaData->setDecimalPlaces(typedValue.toInt());
} else {
qWarning() << "Invalid decimal places value for" << factName
<< " type:" << metaData->type()
<< " value:" << attr
<< " error:" << errorString;
}
}
}
{
//-- Check for Units
QString attr;
if(read_attribute(parameterNode, kUnit, attr)) {
metaData->setRawUnits(attr);
}
}
qCDebug(CameraControlLog) << "New parameter:" << factName << (readOnly ? "ReadOnly" : "Writable") << (writeOnly ? "WriteOnly" : "Readable");
_nameToFactMetaDataMap[factName] = metaData;
Fact* pFact = new Fact(_compID, factName, factType, this);
QQmlEngine::setObjectOwnership(pFact, QQmlEngine::CppOwnership);
QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle);
QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership);
1061
1062
1063
1064
1065
1066
1067
1068
1069
1070
1071
1072
1073
1074
1075
1076
1077
1078
1079
1080
1081
1082
1083
1084
1085
1086
1087
1088
_paramIO[factName] = pIO;
_addFact(pFact, factName);
}
}
if(_nameToFactMetaDataMap.size() > 0) {
_addFactGroup(this, "camera");
_processRanges();
_activeSettings = _settings;
emit activeSettingsChanged();
return true;
}
return false;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_handleLocalization(QByteArray& bytes)
{
QString errorMsg;
int errorLine;
QDomDocument doc;
if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) {
qCritical() << "Unable to parse camera definition file on line:" << errorLine;
qCritical() << errorMsg;
return false;
}
//-- Find out where we are
QLocale locale = QLocale::system();
1090
1091
1092
1093
1094
1095
1096
1097
1098
1099
1100
1101
1102
1103
1104
1105
1106
1107
1108
1109
1110
1111
1112
1113
1114
1115
1116
1117
1118
1119
1120
1121
1122
1123
1124
1125
1126
1127
1128
1129
1130
1131
1132
1133
1134
1135
1136
1137
1138
1139
1140
1141
1142
1143
1144
1145
1146
1147
1148
1149
1150
1151
1152
1153
1154
1155
1156
1157
1158
1159
1160
1161
1162
1163
locale = QLocale(locale.name());
#endif
QString localeName = locale.name().toLower().replace("-", "_");
qCDebug(CameraControlLog) << "Current locale:" << localeName;
if(localeName == "en_us") {
// Nothing to do
return true;
}
QDomNodeList locRoot = doc.elementsByTagName(kLocalization);
if(!locRoot.size()) {
// Nothing to do
return true;
}
//-- Iterate locales
QDomNode node = locRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList locales = elem.elementsByTagName(kLocale);
for(int i = 0; i < locales.size(); i++) {
QDomNode locale = locales.item(i);
QString name;
if(!read_attribute(locale, kName, name)) {
qWarning() << "Localization entry is missing its name attribute";
continue;
}
// If we found a direct match, deal with it now
if(localeName == name.toLower().replace("-", "_")) {
return _replaceLocaleStrings(locale, bytes);
}
}
//-- No direct match. Pick first matching language (if any)
localeName = localeName.left(3);
for(int i = 0; i < locales.size(); i++) {
QDomNode locale = locales.item(i);
QString name;
read_attribute(locale, kName, name);
if(name.toLower().startsWith(localeName)) {
return _replaceLocaleStrings(locale, bytes);
}
}
//-- Could not find a language to use
qWarning() << "No match for" << QLocale::system().name() << "in camera definition file";
//-- Just use default, en_US
return true;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_replaceLocaleStrings(const QDomNode node, QByteArray& bytes)
{
QDomElement stringElem = node.toElement();
QDomNodeList strings = stringElem.elementsByTagName(kStrings);
for(int i = 0; i < strings.size(); i++) {
QDomNode stringNode = strings.item(i);
QString original;
QString translated;
if(read_attribute(stringNode, kOriginal, original)) {
if(read_attribute(stringNode, kTranslated, translated)) {
QString o; o = "\"" + original + "\"";
QString t; t = "\"" + translated + "\"";
bytes.replace(o.toUtf8(), t.toUtf8());
o = ">" + original + "<";
t = ">" + translated + "<";
bytes.replace(o.toUtf8(), t.toUtf8());
}
}
}
return true;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestAllParameters()
{
//-- Reset receive list
for(const QString& paramName: _paramIO.keys()) {
if(_paramIO[paramName]) {
_paramIO[paramName]->setParamRequest();
} else {
qCritical() << "QGCParamIO is NULL" << paramName;
}
}
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_ext_request_list_pack_chan(
static_cast<uint8_t>(mavlink->getSystemId()),
static_cast<uint8_t>(mavlink->getComponentId()),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
static_cast<uint8_t>(_vehicle->id()),
static_cast<uint8_t>(compID()));
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(CameraControlVerboseLog) << "Request all parameters";
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::_getParamName(const char* param_id)
{
QByteArray bytes(param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
QString parameterName(bytes);
return parameterName;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
QString paramName = _getParamName(ack.param_id);
if(!_paramIO.contains(paramName)) {
qCWarning(CameraControlLog) << "Received PARAM_EXT_ACK for unknown param:" << paramName;
return;
}
if(_paramIO[paramName]) {
_paramIO[paramName]->handleParamAck(ack);
} else {
qCritical() << "QGCParamIO is NULL" << paramName;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleParamValue(const mavlink_param_ext_value_t& value)
{
QString paramName = _getParamName(value.param_id);
if(!_paramIO.contains(paramName)) {
qCWarning(CameraControlLog) << "Received PARAM_EXT_VALUE for unknown param:" << paramName;
return;
}
if(_paramIO[paramName]) {
_paramIO[paramName]->handleParamValue(value);
} else {
qCritical() << "QGCParamIO is NULL" << paramName;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateActiveList()
{
//-- Clear out excluded parameters based on exclusion rules
QStringList exclusionList;
for(QGCCameraOptionExclusion* param: _valueExclusions) {
Fact* pFact = getFact(param->param);
if(pFact) {
QString option = pFact->rawValueString();
if(param->value == option) {
exclusionList << param->exclusions;
}
}
}
QStringList active;
for(QString key: _settings) {
active.append(key);
if(active != _activeSettings) {
qCDebug(CameraControlVerboseLog) << "Excluding" << exclusionList;
_activeSettings = active;
emit activeSettingsChanged();
//-- Force validity of "Facts" based on active set
if(_paramComplete) {
emit parametersReady();
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processConditionTest(const QString conditionTest)
{
enum {
TEST_NONE,
TEST_EQUAL,
TEST_NOT_EQUAL,
TEST_GREATER,
TEST_SMALLER
};
qCDebug(CameraControlVerboseLog) << "_processConditionTest(" << conditionTest << ")";
1269
1270
1271
1272
1273
1274
1275
1276
1277
1278
1279
1280
1281
1282
1283
1284
1285
1286
1287
1288
1289
1290
1291
1292
1293
1294
1295
1296
1297
1298
1299
1300
1301
1302
1303
1304
1305
1306
1307
1308
1309
1310
1311
int op = TEST_NONE;
QStringList test;
if(conditionTest.contains("!=")) {
test = conditionTest.split("!=", QString::SkipEmptyParts);
op = TEST_NOT_EQUAL;
} else if(conditionTest.contains("=")) {
test = conditionTest.split("=", QString::SkipEmptyParts);
op = TEST_EQUAL;
} else if(conditionTest.contains(">")) {
test = conditionTest.split(">", QString::SkipEmptyParts);
op = TEST_GREATER;
} else if(conditionTest.contains("<")) {
test = conditionTest.split("<", QString::SkipEmptyParts);
op = TEST_SMALLER;
}
if(test.size() == 2) {
Fact* pFact = getFact(test[0]);
if(pFact) {
switch(op) {
case TEST_EQUAL:
return pFact->rawValueString() == test[1];
case TEST_NOT_EQUAL:
return pFact->rawValueString() != test[1];
case TEST_GREATER:
return pFact->rawValueString() > test[1];
case TEST_SMALLER:
return pFact->rawValueString() < test[1];
case TEST_NONE:
break;
}
} else {
qWarning() << "Invalid condition parameter:" << test[0] << "in" << conditionTest;
return false;
}
}
qWarning() << "Invalid condition" << conditionTest;
return false;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processCondition(const QString condition)
{
qCDebug(CameraControlVerboseLog) << "_processCondition(" << condition << ")";
1313
1314
1315
1316
1317
1318
1319
1320
1321
1322
1323
1324
1325
1326
1327
1328
1329
1330
1331
1332
1333
1334
1335
1336
1337
1338
bool result = true;
bool andOp = true;
if(!condition.isEmpty()) {
QStringList scond = condition.split(" ", QString::SkipEmptyParts);
while(scond.size()) {
QString test = scond.first();
scond.removeFirst();
if(andOp) {
result = result && _processConditionTest(test);
} else {
result = result || _processConditionTest(test);
}
if(!scond.size()) {
return result;
}
andOp = scond.first().toUpper() == "AND";
scond.removeFirst();
}
}
return result;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_updateRanges(Fact* pFact)
{
QMap<Fact*, QGCCameraOptionRange*> rangesSet;
QMap<Fact*, QString> rangesReset;
QStringList changedList;
QStringList resetList;
QStringList updates;
//-- Iterate range sets looking for limited ranges
for(QGCCameraOptionRange* pRange: _optionRanges) {
//-- If this fact or one of its conditions is part of this range set
if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
Fact* pRFact = getFact(pRange->param); //-- This parameter
Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
if(pRFact && pTFact) {
//qCDebug(CameraControlVerboseLog) << "Check new set of options for" << pTFact->name();
QString option = pRFact->rawValueString(); //-- This parameter value
//-- If this value (and condition) triggers a change in the target range
//qCDebug(CameraControlVerboseLog) << "Range value:" << pRange->value << "Current value:" << option << "Condition:" << pRange->condition;
if(pRange->value == option && _processCondition(pRange->condition)) {
if(pTFact->enumStrings() != pRange->optNames) {
//-- Set limited range set
rangesSet[pTFact] = pRange;
}
}
}
}
//-- Iterate range sets again looking for resets
for(QGCCameraOptionRange* pRange: _optionRanges) {
if(!changedList.contains(pRange->targetParam) && (pRange->param == pFact->name() || pRange->condition.contains(pFact->name()))) {
Fact* pTFact = getFact(pRange->targetParam); //-- The target parameter (the one its range is to change)
if(!resetList.contains(pRange->targetParam)) {
if(pTFact->enumStrings() != _originalOptNames[pRange->targetParam]) {
//-- Restore full option set
rangesReset[pTFact] = pRange->targetParam;
resetList << pRange->targetParam;
//-- Update limited range set
for (Fact* f: rangesSet.keys()) {
f->setEnumInfo(rangesSet[f]->optNames, rangesSet[f]->optVariants);
if(!updates.contains(f->name())) {
_paramIO[f->name()]->optNames = rangesSet[f]->optNames;
_paramIO[f->name()]->optVariants = rangesSet[f]->optVariants;
emit f->enumsChanged();
qCDebug(CameraControlVerboseLog) << "Limited set of options for:" << f->name() << rangesSet[f]->optNames;;
updates << f->name();
}
}
//-- Restore full range set
for (Fact* f: rangesReset.keys()) {
f->setEnumInfo(_originalOptNames[rangesReset[f]], _originalOptValues[rangesReset[f]]);
if(!updates.contains(f->name())) {
_paramIO[f->name()]->optNames = _originalOptNames[rangesReset[f]];
_paramIO[f->name()]->optVariants = _originalOptValues[rangesReset[f]];
emit f->enumsChanged();
qCDebug(CameraControlVerboseLog) << "Restore full set of options for:" << f->name() << _originalOptNames[f->name()];
updates << f->name();
//-- Parameter update requests
if(_requestUpdates.contains(pFact->name())) {
for(const QString& param: _requestUpdates[pFact->name()]) {
if(!_updatesToRequest.contains(param)) {
_updatesToRequest << param;
}
}
if(_updatesToRequest.size()) {
QTimer::singleShot(500, this, &QGCCameraControl::_requestParamUpdates);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestParamUpdates()
{
for(const QString& param: _updatesToRequest) {
_paramIO[param]->paramRequest();
}
_updatesToRequest.clear();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCameraSettings()
{
qCDebug(CameraControlLog) << "_requestCameraSettings()";
if(_vehicle) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_CAMERA_SETTINGS, // command id
false, // showError
1); // Do Request
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStorageInfo()
{
qCDebug(CameraControlLog) << "_requestStorageInfo()";
if(_vehicle) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_STORAGE_INFORMATION, // command id
false, // showError
0, // Storage ID (0 for all, 1 for first, 2 for second, etc.)
1); // Do Request
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleSettings(const mavlink_camera_settings_t& settings)
{
qCDebug(CameraControlLog) << "handleSettings() Mode:" << settings.mode_id;
_setCameraMode(static_cast<CameraMode>(settings.mode_id));
qreal z = static_cast<qreal>(settings.zoomLevel);
qreal f = static_cast<qreal>(settings.focusLevel);
if(std::isfinite(z) && z != _zoomLevel) {
_zoomLevel = z;
emit zoomLevelChanged();
}
if(std::isfinite(f) && f != _focusLevel) {
_focusLevel = f;
emit focusLevelChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleStorageInfo(const mavlink_storage_information_t& st)
{
qCDebug(CameraControlLog) << "handleStorageInfo:" << st.available_capacity << st.status << st.storage_count << st.storage_id << st.total_capacity << st.used_capacity;
if(st.status == STORAGE_STATUS_READY) {
uint32_t t = static_cast<uint32_t>(st.total_capacity);
if(_storageTotal != t) {
_storageTotal = t;
emit storageTotalChanged();
}
uint32_t a = static_cast<uint32_t>(st.available_capacity);
if(_storageFree != a) {
_storageFree = a;
emit storageFreeChanged();
}
}
if(_storageStatus != static_cast<StorageStatus>(st.status)) {
_storageStatus = static_cast<StorageStatus>(st.status);
emit storageStatusChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap)
{
//-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
qCDebug(CameraControlLog) << "handleCaptureStatus:" << cap.available_capacity << cap.image_interval << cap.image_status << cap.recording_time_ms << cap.video_status;
//-- Disk Free Space
uint32_t a = static_cast<uint32_t>(cap.available_capacity);
if(_storageFree != a) {
_storageFree = a;
//-- Do we have recording time?
if(cap.recording_time_ms) {
_recordTime = cap.recording_time_ms;
_recTime = _recTime.addMSecs(_recTime.elapsed() - static_cast<int>(cap.recording_time_ms));
emit recordTimeChanged();
}
//-- Video/Image Capture Status
uint8_t vs = cap.video_status < static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast<uint8_t>(VIDEO_CAPTURE_STATUS_UNDEFINED);
uint8_t ps = cap.image_status < static_cast<uint8_t>(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast<uint8_t>(PHOTO_CAPTURE_STATUS_UNDEFINED);
_setVideoStatus(static_cast<VideoStatus>(vs));
_setPhotoStatus(static_cast<PhotoStatus>(ps));
//-- Keep asking for it once in a while when recording
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_captureStatusTimer.start(5000);
//-- Same while (single) image capture is busy
} else if(photoStatus() != PHOTO_CAPTURE_IDLE && photoMode() == PHOTO_CAPTURE_SINGLE) {
_captureStatusTimer.start(1000);
//-- Time Lapse
if(photoStatus() == PHOTO_CAPTURE_INTERVAL_IDLE || photoStatus() == PHOTO_CAPTURE_INTERVAL_IN_PROGRESS) {
//-- Capture local image as well
if(qgcApp()->toolbox()->videoManager()->videoReceiver()) {
QString photoPath = qgcApp()->toolbox()->settingsManager()->appSettings()->savePath()->rawValue().toString() + QStringLiteral("/Photo");
QDir().mkpath(photoPath);
photoPath += + "/" + QDateTime::currentDateTime().toString("yyyy-MM-dd_hh.mm.ss.zzz") + ".jpg";
qgcApp()->toolbox()->videoManager()->videoReceiver()->grabImage(photoPath);
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoInfo(const mavlink_video_stream_information_t* vi)
{
qCDebug(CameraControlLog) << "handleVideoInfo:" << vi->stream_id << vi->uri;
_expectedCount = vi->count;
if(!_findStream(vi->stream_id, false)) {
qCDebug(CameraControlLog) << "Create stream handler for stream ID:" << vi->stream_id;
QGCVideoStreamInfo* pStream = new QGCVideoStreamInfo(this, vi);
QQmlEngine::setObjectOwnership(pStream, QQmlEngine::CppOwnership);
_streams.append(pStream);
//-- Thermal is handled separately and not listed
if(!pStream->isThermal()) {
_streamLabels.append(pStream->name());
emit streamsChanged();
emit streamLabelsChanged();
} else {
emit thermalStreamChanged();
}
}
//-- Check for missing count
if(_streams.count() < _expectedCount) {
_streamInfoTimer.start(1000);
} else {
//-- Done
qCDebug(CameraControlLog) << "All stream handlers done";
_streamInfoTimer.stop();
emit autoStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::handleVideoStatus(const mavlink_video_stream_status_t* vs)
{
_streamStatusTimer.stop();
qCDebug(CameraControlLog) << "handleVideoStatus:" << vs->stream_id;
QGCVideoStreamInfo* pInfo = _findStream(vs->stream_id);
if(pInfo) {
pInfo->update(vs);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCurrentStream(int stream)
{
if(stream != _currentStream && stream >= 0 && stream < _streamLabels.count()) {
if(_currentStream != stream) {
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
qCDebug(CameraControlLog) << "Stopping stream:" << pInfo->uri();
//-- Stop current stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_STOP_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
_currentStream = stream;
pInfo = currentStreamInstance();
if(pInfo) {
//-- Start new stream
qCDebug(CameraControlLog) << "Starting stream:" << pInfo->uri();
1600
1601
1602
1603
1604
1605
1606
1607
1608
1609
1610
1611
1612
1613
1614
1615
1616
1617
1618
1619
1620
1621
1622
1623
1624
1625
1626
1627
1628
1629
1630
1631
1632
1633
1634
1635
1636
1637
1638
1639
1640
1641
1642
1643
1644
1645
1646
1647
1648
1649
1650
1651
1652
1653
1654
1655
1656
1657
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
//-- Update stream status
_requestStreamStatus(static_cast<uint8_t>(pInfo->streamID()));
}
emit currentStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::stopStream()
{
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
//-- Stop current stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_STOP_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::resumeStream()
{
QGCVideoStreamInfo* pInfo = currentStreamInstance();
if(pInfo) {
//-- Start new stream
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_VIDEO_START_STREAMING, // Command id
false, // ShowError
pInfo->streamID()); // Stream ID
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::autoStream()
{
if(hasVideoStream()) {
return _streams.count() > 0;
}
return false;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::currentStreamInstance()
{
if(_currentStream < _streamLabels.count() && _streamLabels.count()) {
QGCVideoStreamInfo* pStream = _findStream(_streamLabels[_currentStream]);
return pStream;
}
return nullptr;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::thermalStreamInstance()
{
//-- For now, it will return the first thermal listed (if any)
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->isThermal()) {
return pStream;
}
}
}
}
return nullptr;
}
1683
1684
1685
1686
1687
1688
1689
1690
1691
1692
1693
1694
1695
1696
1697
1698
1699
1700
1701
1702
1703
1704
1705
1706
1707
1708
1709
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamInfo(uint8_t streamID)
{
qCDebug(CameraControlLog) << "Requesting video stream info for:" << streamID;
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION, // Command id
false, // ShowError
streamID); // Stream ID
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestStreamStatus(uint8_t streamID)
{
qCDebug(CameraControlLog) << "Requesting video stream status for:" << streamID;
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_REQUEST_VIDEO_STREAM_STATUS, // Command id
false, // ShowError
streamID); // Stream ID
_streamStatusTimer.start(1000); // Wait up to a second for it
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::_findStream(uint8_t id, bool report)
{
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->streamID() == id) {
return pStream;
}
} else {
qCritical() << "Null QGCVideoStreamInfo instance";
}
}
}
if(report) {
qWarning() << "Stream id not found:" << id;
}
return nullptr;
}
//-----------------------------------------------------------------------------
QGCVideoStreamInfo*
QGCCameraControl::_findStream(const QString name)
{
for(int i = 0; i < _streams.count(); i++) {
if(_streams[i]) {
QGCVideoStreamInfo* pStream = qobject_cast<QGCVideoStreamInfo*>(_streams[i]);
if(pStream) {
if(pStream->name() == name) {
return pStream;
}
}
}
}
return nullptr;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamTimeout()
{
_requestCount++;
int count = _expectedCount * 3;
if(_requestCount > count) {
qCWarning(CameraControlLog) << "Giving up requesting video stream info";
_streamInfoTimer.stop();
//-- If we have at least one stream, work with what we have.
if(_streams.count()) {
emit autoStreamChanged();
emit _vehicle->dynamicCameras()->streamChanged();
}
return;
}
for(uint8_t i = 0; i < _expectedCount; i++) {
//-- Stream ID starts at 1
if(!_findStream(i+1, false)) {
_requestStreamInfo(i+1);
return;
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_streamStatusTimeout()
{
QGCVideoStreamInfo* pStream = currentStreamInstance();
if(pStream) {
_requestStreamStatus(static_cast<uint8_t>(pStream->streamID()));
}
}
//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadExclusions(QDomNode option)
{
QStringList exclusionList;
QDomElement optionElem = option.toElement();
QDomNodeList excRoot = optionElem.elementsByTagName(kExclusions);
if(excRoot.size()) {
//-- Iterate exclusions
QDomNode node = excRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList exclusions = elem.elementsByTagName(kExclusion);
for(int i = 0; i < exclusions.size(); i++) {
QString exclude = exclusions.item(i).toElement().text();
if(!exclude.isEmpty()) {
exclusionList << exclude;
}
}
}
return exclusionList;
}
1804
1805
1806
1807
1808
1809
1810
1811
1812
1813
1814
1815
1816
1817
1818
1819
1820
1821
1822
1823
1824
1825
//-----------------------------------------------------------------------------
QStringList
QGCCameraControl::_loadUpdates(QDomNode option)
{
QStringList updateList;
QDomElement optionElem = option.toElement();
QDomNodeList updateRoot = optionElem.elementsByTagName(kUpdates);
if(updateRoot.size()) {
//-- Iterate updates
QDomNode node = updateRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList updates = elem.elementsByTagName(kUpdate);
for(int i = 0; i < updates.size(); i++) {
QString update = updates.item(i).toElement().text();
if(!update.isEmpty()) {
updateList << update;
}
}
}
return updateList;
}
1826
1827
1828
1829
1830
1831
1832
1833
1834
1835
1836
1837
1838
1839
1840
1841
1842
1843
1844
1845
1846
1847
1848
1849
1850
1851
1852
1853
1854
1855
1856
1857
1858
1859
1860
1861
1862
1863
1864
1865
1866
1867
1868
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadRanges(QDomNode option, const QString factName, QString paramValue)
{
QDomElement optionElem = option.toElement();
QDomNodeList rangeRoot = optionElem.elementsByTagName(kParameterranges);
if(rangeRoot.size()) {
QDomNode node = rangeRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList parameterRanges = elem.elementsByTagName(kParameterrange);
//-- Iterate parameter ranges
for(int i = 0; i < parameterRanges.size(); i++) {
QString param;
QString condition;
QDomNode paramRange = parameterRanges.item(i);
if(!read_attribute(paramRange, kParameter, param)) {
qCritical() << QString("Malformed option range for parameter %1").arg(factName);
return false;
}
read_attribute(paramRange, kCondition, condition);
QDomElement pelem = paramRange.toElement();
QDomNodeList rangeOptions = pelem.elementsByTagName(kRoption);
QStringList optNames;
QStringList optValues;
//-- Iterate options
for(int i = 0; i < rangeOptions.size(); i++) {
QString optName;
QString optValue;
QDomNode roption = rangeOptions.item(i);
if(!read_attribute(roption, kName, optName)) {
qCritical() << QString("Malformed roption for parameter %1").arg(factName);
return false;
}
if(!read_attribute(roption, kValue, optValue)) {
qCritical() << QString("Malformed rvalue for parameter %1").arg(factName);
return false;
}
optNames << optName;
optValues << optValue;
}
if(optNames.size()) {
QGCCameraOptionRange* pRange = new QGCCameraOptionRange(this, factName, paramValue, param, condition, optNames, optValues);
_optionRanges.append(pRange);
qCDebug(CameraControlVerboseLog) << "New range limit:" << factName << paramValue << param << condition << optNames << optValues;
}
}
}
return true;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_processRanges()
{
//-- After all parameter are loaded, process parameter ranges
for(QGCCameraOptionRange* pRange: _optionRanges) {
1882
1883
1884
1885
1886
1887
1888
1889
1890
1891
1892
1893
1894
1895
1896
1897
1898
1899
1900
1901
1902
1903
1904
1905
1906
1907
1908
1909
1910
1911
1912
1913
1914
1915
1916
1917
1918
1919
1920
Fact* pRFact = getFact(pRange->targetParam);
if(pRFact) {
for(int i = 0; i < pRange->optNames.size(); i++) {
QVariant optVariant;
QString errorString;
if (!pRFact->metaData()->convertAndValidateRaw(pRange->optValues[i], false, optVariant, errorString)) {
qWarning() << "Invalid roption value, name:" << pRange->targetParam
<< " type:" << pRFact->metaData()->type()
<< " value:" << pRange->optValues[i]
<< " error:" << errorString;
} else {
pRange->optVariants << optVariant;
}
}
}
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant)
{
if(!read_attribute(option, kName, optName)) {
qCritical() << QString("Malformed option for parameter %1").arg(factName);
return false;
}
if(!read_attribute(option, kValue, optValue)) {
qCritical() << QString("Malformed value for parameter %1").arg(factName);
return false;
}
QString errorString;
if (!metaData->convertAndValidateRaw(optValue, false, optVariant, errorString)) {
qWarning() << "Invalid option value, name:" << factName
<< " type:" << metaData->type()
<< " value:" << optValue
<< " error:" << errorString;
}
return true;
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_handleDefinitionFile(const QString &url)
{
//-- First check and see if we have it cached
if (!xmlFile.exists()) {
qCDebug(CameraControlLog) << "No camera definition file cached";
_httpRequest(url);
return;
}
if (!xmlFile.open(QIODevice::ReadOnly)) {
qWarning() << "Could not read cached camera definition file:" << _cacheFile;
_httpRequest(url);
return;
}
QByteArray bytes = xmlFile.readAll();
QDomDocument doc;
if(!doc.setContent(bytes, false)) {
qWarning() << "Could not parse cached camera definition file:" << _cacheFile;
_httpRequest(url);
return;
}
//-- We have it
qCDebug(CameraControlLog) << "Using cached camera definition file:" << _cacheFile;
_cached = true;
emit dataReady(bytes);
}
1951
1952
1953
1954
1955
1956
1957
1958
1959
1960
1961
1962
1963
1964
1965
1966
1967
1968
1969
1970
1971
1972
1973
1974
1975
1976
1977
1978
1979
1980
1981
1982
1983
1984
1985
1986
1987
1988
1989
1990
1991
1992
1993
1994
1995
1996
1997
1998
1999
2000
//-----------------------------------------------------------------------------
void
QGCCameraControl::_httpRequest(const QString &url)
{
qCDebug(CameraControlLog) << "Request camera definition:" << url;
if(!_netManager) {
_netManager = new QNetworkAccessManager(this);
}
QNetworkProxy savedProxy = _netManager->proxy();
QNetworkProxy tempProxy;
tempProxy.setType(QNetworkProxy::DefaultProxy);
_netManager->setProxy(tempProxy);
QNetworkRequest request(url);
request.setAttribute(QNetworkRequest::FollowRedirectsAttribute, true);
QSslConfiguration conf = request.sslConfiguration();
conf.setPeerVerifyMode(QSslSocket::VerifyNone);
request.setSslConfiguration(conf);
QNetworkReply* reply = _netManager->get(request);
connect(reply, &QNetworkReply::finished, this, &QGCCameraControl::_downloadFinished);
_netManager->setProxy(savedProxy);
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_downloadFinished()
{
QNetworkReply* reply = qobject_cast<QNetworkReply*>(sender());
if(!reply) {
return;
}
int err = reply->error();
int http_code = reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toInt();
QByteArray data = reply->readAll();
if(err == QNetworkReply::NoError && http_code == 200) {
data.append("\n");
} else {
data.clear();
qWarning() << QString("Camera Definition download error: %1 status: %2").arg(reply->errorString(), reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString());
}
emit dataReady(data);
//reply->deleteLater();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_dataReady(QByteArray data)
{
if(data.size()) {
qCDebug(CameraControlLog) << "Parsing camera definition";
_loadCameraDefinitionFile(data);