Newer
Older
/*!
* @file
* @brief Camera Controller
* @author Gus Grubba <mavlink@grubba.com>
*
*/
#include "QGCCameraControl.h"
#include "QGCCameraIO.h"
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"
#include <QDomDocument>
#include <QDomNodeList>
QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog")
QGC_LOGGING_CATEGORY(CameraControlLogVerbose, "CameraControlLogVerbose")
static const char* kCondition = "condition";
static const char* kControl = "control";
static const char* kDefault = "default";
static const char* kDefnition = "definition";
static const char* kDescription = "description";
static const char* kExclusion = "exclude";
static const char* kExclusions = "exclusions";
static const char* kLocale = "locale";
static const char* kLocalization = "localization";
static const char* kMax = "max";
static const char* kMin = "min";
static const char* kModel = "model";
static const char* kName = "name";
static const char* kOption = "option";
static const char* kOptions = "options";
static const char* kParameter = "parameter";
static const char* kParameterrange = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters = "parameters";
static const char* kReadOnly = "readonly";
static const char* kRoption = "roption";
static const char* kStep = "step";
static const char* kStrings = "strings";
static const char* kTranslated = "translated";
static const char* kType = "type";
static const char* kUnit = "unit";
static const char* kUpdate = "update";
static const char* kUpdates = "updates";
static const char* kValue = "value";
static const char* kVendor = "vendor";
static const char* kVersion = "version";
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, bool& target)
{
QDomNamedNodeMap attrs = node.attributes();
if(!attrs.count()) {
return false;
}
QDomNode subNode = attrs.namedItem(tagName);
if(subNode.isNull()) {
return false;
}
target = subNode.nodeValue() != "0";
return true;
}
//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, int& target)
{
QDomNamedNodeMap attrs = node.attributes();
if(!attrs.count()) {
return false;
}
QDomNode subNode = attrs.namedItem(tagName);
if(subNode.isNull()) {
return false;
}
target = subNode.nodeValue().toInt();
return true;
}
//-----------------------------------------------------------------------------
static bool
read_attribute(QDomNode& node, const char* tagName, QString& target)
{
QDomNamedNodeMap attrs = node.attributes();
if(!attrs.count()) {
return false;
}
QDomNode subNode = attrs.namedItem(tagName);
if(subNode.isNull()) {
return false;
}
target = subNode.nodeValue();
return true;
}
//-----------------------------------------------------------------------------
static bool
read_value(QDomNode& element, const char* tagName, QString& target)
{
QDomElement de = element.firstChildElement(tagName);
if(de.isNull()) {
return false;
}
target = de.text();
return true;
}
//-----------------------------------------------------------------------------
QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Vehicle* vehicle, int compID, QObject* parent)
: FactGroup(0, parent)
, _vehicle(vehicle)
, _compID(compID)
, _version(0)
, _storageFree(0)
, _storageTotal(0)
, _netManager(NULL)
, _cameraMode(CAM_MODE_UNDEFINED)
, _photo_status(PHOTO_CAPTURE_STATUS_UNDEFINED)
, _storageInfoRetries(0)
, _captureInfoRetries(0)
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
memcpy(&_info, info, sizeof(mavlink_camera_information_t));
connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady);
_vendor = QString((const char*)(void*)&info->vendor_name[0]);
_modelName = QString((const char*)(void*)&info->model_name[0]);
int ver = (int)_info.cam_definition_version;
_cacheFile.sprintf("%s/%s_%s_%03d.xml",
qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(),
_vendor.toStdString().c_str(),
_modelName.toStdString().c_str(),
ver);
}
//-----------------------------------------------------------------------------
QGCCameraControl::~QGCCameraControl()
{
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
if(_netManager) {
delete _netManager;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_initWhenReady()
{
qCDebug(CameraControlLog) << "_initWhenReady()";
if(isBasic()) {
qCDebug(CameraControlLog) << "Basic, MAVLink only messages.";
_requestCameraSettings();
} else {
_requestAllParameters();
//-- Give some time to load the parameters before going after the camera settings
QTimer::singleShot(2000, this, &QGCCameraControl::_requestCameraSettings);
}
connect(_vehicle, &Vehicle::mavCommandResult, this, &QGCCameraControl::_mavCommandResult);
connect(&_captureStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_requestCaptureStatus);
_captureStatusTimer.setSingleShot(true);
QTimer::singleShot(2500, this, &QGCCameraControl::_requestStorageInfo);
_captureStatusTimer.start(2750);
emit infoChanged();
if(_netManager) {
delete _netManager;
_netManager = NULL;
}
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::firmwareVersion()
{
int major = (_info.firmware_version >> 24) & 0xFF;
int minor = (_info.firmware_version >> 16) & 0xFF;
int build = _info.firmware_version & 0xFFFF;
QString ver;
ver.sprintf("%d.%d.%d", major, minor, build);
return ver;
}
//-----------------------------------------------------------------------------
QGCCameraControl::VideoStatus
QGCCameraControl::videoStatus()
{
return _video_status;
}
//-----------------------------------------------------------------------------
QGCCameraControl::PhotoStatus
QGCCameraControl::photoStatus()
{
return _photo_status;
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl::storageFreeStr()
{
return QGCMapEngine::bigSizeToString((quint64)_storageFree * 1024 * 1024);
//-----------------------------------------------------------------------------
void
QGCCameraControl::setCameraMode(CameraMode mode)
{
qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")";
if(mode == CAM_MODE_VIDEO) {
} else if(mode == CAM_MODE_PHOTO) {
setPhotoMode();
} else {
qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode;
return;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setCameraMode(CameraMode mode)
{
_cameraMode = mode;
emit cameraModeChanged();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::toggleMode()
{
if(cameraMode() == CAM_MODE_PHOTO) {
} else if(cameraMode() == CAM_MODE_VIDEO) {
setPhotoMode();
}
}
//-----------------------------------------------------------------------------
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
return stopVideo();
} else {
return startVideo();
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::takePhoto()
{
qCDebug(CameraControlLog) << "takePhoto()";
//-- Check if camera can capture photos or if it can capture it while in Video Mode
if(!capturesPhotos() || (cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) || photoStatus() != PHOTO_CAPTURE_IDLE) {
return false;
}
if(capturesPhotos()) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
MAV_CMD_IMAGE_START_CAPTURE, // Command id
false, // ShowError
0, // Duration between two consecutive pictures (in seconds--ignored if single image)
1); // Number of images to capture total - 0 for unlimited capture
_setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS);
_captureInfoRetries = 0;
//-- Capture local image as well
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);
return true;
}
return false;
}
//-----------------------------------------------------------------------------
qCDebug(CameraControlLog) << "startVideo()";
//-- Check if camera can capture videos or if it can capture it while in Photo Mode
if(!capturesVideo() || (cameraMode() == CAM_MODE_PHOTO && !videoInPhotoMode())) {
return false;
}
if(videoStatus() != VIDEO_CAPTURE_STATUS_RUNNING) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
MAV_CMD_VIDEO_START_CAPTURE, // Command id
true, // ShowError
0); // CAMERA_CAPTURE_STATUS Frequency
return true;
}
return false;
}
//-----------------------------------------------------------------------------
qCDebug(CameraControlLog) << "stopVideo()";
if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) {
_vehicle->sendMavCommand(
MAV_COMP_ID_CAMERA, // Target component
MAV_CMD_VIDEO_STOP_CAPTURE, // Command id
true, // ShowError
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setVideoMode()
{
if(hasModes() && _cameraMode != CAM_MODE_VIDEO) {
qCDebug(CameraControlLog) << "setVideoMode()";
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_VIDEO);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::setPhotoMode()
{
if(hasModes() && _cameraMode != CAM_MODE_PHOTO) {
qCDebug(CameraControlLog) << "setPhotoMode()";
//-- Use basic MAVLink message
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_SET_CAMERA_MODE, // Command id
true, // ShowError
CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video)
_setCameraMode(CAM_MODE_PHOTO);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::resetSettings()
{
qCDebug(CameraControlLog) << "resetSettings()";
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_RESET_CAMERA_SETTINGS, // Command id
true, // ShowError
1); // Do Reset
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::formatCard(int id)
{
qCDebug(CameraControlLog) << "formatCard()";
if(_vehicle) {
_vehicle->sendMavCommand(
_compID, // Target component
MAV_CMD_STORAGE_FORMAT, // Command id
true, // ShowError
id, // Storage ID (1 for first, 2 for second, etc.)
1); // Do Format
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_requestCaptureStatus()
{
qCDebug(CameraControlLog) << "_requestCaptureStatus()";
_vehicle->sendMavCommand(
_compID, // target component
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS, // command id
false, // showError
1); // Do Request
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::factChanged(Fact* pFact)
{
_updateActiveList();
_updateRanges(pFact);
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle)
//-- Is this ours?
if(_vehicle->id() != vehicleId || compID() != component) {
return;
}
if(!noReponseFromVehicle && result == MAV_RESULT_IN_PROGRESS) {
//-- Do Nothing
qCDebug(CameraControlLog) << "In progress response for" << command;
}else if(!noReponseFromVehicle && result == MAV_RESULT_ACCEPTED) {
switch(command) {
case MAV_CMD_RESET_CAMERA_SETTINGS:
if(isBasic()) {
_requestCameraSettings();
} else {
QTimer::singleShot(500, this, &QGCCameraControl::_requestAllParameters);
QTimer::singleShot(2500, this, &QGCCameraControl::_requestCameraSettings);
}
break;
case MAV_CMD_VIDEO_START_CAPTURE:
_setVideoStatus(VIDEO_CAPTURE_STATUS_RUNNING);
_captureStatusTimer.start(1000);
break;
case MAV_CMD_VIDEO_STOP_CAPTURE:
_setVideoStatus(VIDEO_CAPTURE_STATUS_STOPPED);
_captureStatusTimer.start(1000);
case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
_captureInfoRetries = 0;
break;
case MAV_CMD_REQUEST_STORAGE_INFORMATION:
_storageInfoRetries = 0;
break;
if(noReponseFromVehicle || result == MAV_RESULT_TEMPORARILY_REJECTED || result == MAV_RESULT_FAILED) {
if(noReponseFromVehicle) {
qCDebug(CameraControlLog) << "No response for" << command;
} else if (result == MAV_RESULT_TEMPORARILY_REJECTED) {
qCDebug(CameraControlLog) << "Command temporarily rejected for" << command;
} else {
qCDebug(CameraControlLog) << "Command failed for" << command;
}
switch(command) {
case MAV_CMD_IMAGE_START_CAPTURE:
if(++_captureInfoRetries < 5) {
_captureStatusTimer.start(1000);
} else {
qCDebug(CameraControlLog) << "Giving up requesting capture status";
}
break;
case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS:
if(++_captureInfoRetries < 3) {
_captureStatusTimer.start(500);
} else {
qCDebug(CameraControlLog) << "Giving up requesting capture status";
}
break;
case MAV_CMD_REQUEST_STORAGE_INFORMATION:
if(++_storageInfoRetries < 3) {
QTimer::singleShot(500, this, &QGCCameraControl::_requestStorageInfo);
} else {
qCDebug(CameraControlLog) << "Giving up requesting storage status";
}
break;
}
qCDebug(CameraControlLog) << "Bad response for" << command << result;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setVideoStatus(VideoStatus status)
{
if(_video_status != status) {
_video_status = status;
emit videoStatusChanged();
//-----------------------------------------------------------------------------
void
QGCCameraControl::_setPhotoStatus(PhotoStatus status)
{
if(_photo_status != status) {
_photo_status = status;
emit photoStatusChanged();
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes)
{
//-- Handle localization
if(!_handleLocalization(bytes)) {
return false;
}
int errorLine;
QString errorMsg;
QDomDocument doc;
if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) {
qCritical() << "Unable to parse camera definition file on line:" << errorLine;
qCritical() << errorMsg;
return false;
}
//-- Load camera constants
QDomNodeList defElements = doc.elementsByTagName(kDefnition);
if(!defElements.size() || !_loadConstants(defElements)) {
qWarning() << "Unable to load camera constants from camera definition";
return false;
}
//-- Load camera parameters
QDomNodeList paramElements = doc.elementsByTagName(kParameters);
if(!paramElements.size() || !_loadSettings(paramElements)) {
qWarning() << "Unable to load camera parameters from camera definition";
//-- If this is new, cache it
if(!_cached) {
qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile;
QFile file(_cacheFile);
qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString());
} else {
file.write(originalData);
}
}
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
return true;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadConstants(const QDomNodeList nodeList)
{
QDomNode node = nodeList.item(0);
if(!read_attribute(node, kVersion, _version)) {
return false;
}
if(!read_value(node, kModel, _modelName)) {
return false;
}
if(!read_value(node, kVendor, _vendor)) {
return false;
}
return true;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
{
QDomNode node = nodeList.item(0);
QDomElement elem = node.toElement();
QDomNodeList parameters = elem.elementsByTagName(kParameter);
//-- Pre-process settings (maintain order and skip non-controls)
for(int i = 0; i < parameters.size(); i++) {
QDomNode parameterNode = parameters.item(i);
QString name;
if(read_attribute(parameterNode, kName, name)) {
bool control = true;
read_attribute(parameterNode, kControl, control);
if(control) {
_settings << name;
}
} else {
qCritical() << "Parameter entry missing parameter name";
return false;
}
}
//-- Load parameters
for(int i = 0; i < parameters.size(); i++) {
QDomNode parameterNode = parameters.item(i);
QString factName;
read_attribute(parameterNode, kName, factName);
QString type;
if(!read_attribute(parameterNode, kType, type)) {
qCritical() << QString("Parameter %1 missing parameter type").arg(factName);
return false;
}
//-- Does it have a control?
bool control = true;
read_attribute(parameterNode, kControl, control);
//-- Is it read only?
bool readOnly = false;
read_attribute(parameterNode, kReadOnly, readOnly);
//-- Param type
bool unknownType;
FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
if (unknownType) {
qCritical() << QString("Unknown type for parameter %1").arg(factName);
return false;
}
//-- By definition, custom types do not have control
if(factType == FactMetaData::valueTypeCustom) {
control = false;
}
QString description;
if(!read_value(parameterNode, kDescription, description)) {
qCritical() << QString("Parameter %1 missing parameter description").arg(factName);
return false;
}
//-- Check for updates
QStringList updates = _loadUpdates(parameterNode);
if(updates.size()) {
qCDebug(CameraControlLogVerbose) << "Parameter" << factName << "requires updates for:" << updates;
_requestUpdates[factName] = updates;
//-- Build metadata
FactMetaData* metaData = new FactMetaData(factType, factName, this);
QQmlEngine::setObjectOwnership(metaData, QQmlEngine::CppOwnership);
metaData->setShortDescription(description);
metaData->setLongDescription(description);
metaData->setHasControl(control);
metaData->setReadOnly(readOnly);
//-- Options (enums)
QDomElement optionElem = parameterNode.toElement();
QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
if(optionsRoot.size()) {
//-- Iterate options
QDomNode node = optionsRoot.item(0);
QDomElement elem = node.toElement();
QDomNodeList options = elem.elementsByTagName(kOption);
for(int i = 0; i < options.size(); i++) {
QDomNode option = options.item(i);
QString optName;
QString optValue;
QVariant optVariant;
if(!_loadNameValue(option, factName, metaData, optName, optValue, optVariant)) {
delete metaData;
return false;
}
metaData->addEnumInfo(optName, optVariant);
_originalOptNames[factName] << optName;
_originalOptValues[factName] << optVariant;
//-- Check for exclusions
QStringList exclusions = _loadExclusions(option);
if(exclusions.size()) {
qCDebug(CameraControlLogVerbose) << "New exclusions:" << factName << optValue << exclusions;
QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions);
QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership);
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
_valueExclusions.append(pExc);
}
//-- Check for range rules
if(!_loadRanges(option, factName, optValue)) {
delete metaData;
return false;
}
}
}
QString defaultValue;
if(read_attribute(parameterNode, kDefault, defaultValue)) {
QVariant defaultVariant;
QString errorString;
if (metaData->convertAndValidateRaw(defaultValue, false, defaultVariant, errorString)) {
metaData->setRawDefaultValue(defaultVariant);
} else {
qWarning() << "Invalid default value for" << factName
<< " type:" << metaData->type()
<< " value:" << defaultValue
<< " error:" << errorString;
}
}
//-- Set metadata and Fact
if (_nameToFactMetaDataMap.contains(factName)) {
qWarning() << QStringLiteral("Duplicate fact name:") << factName;
delete metaData;
} else {
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
{
//-- Check for Min Value
QString attr;
if(read_attribute(parameterNode, kMin, attr)) {
QVariant typedValue;
QString errorString;
if (metaData->convertAndValidateRaw(attr, true /* convertOnly */, typedValue, errorString)) {
metaData->setRawMin(typedValue);
} else {
qWarning() << "Invalid min value for" << factName
<< " type:" << metaData->type()
<< " value:" << attr
<< " error:" << errorString;
}
}
}
{
//-- Check for Max Value
QString attr;
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->setIncrement(typedValue.toDouble());
} else {
qWarning() << "Invalid step 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;
_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);
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
_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();
#if defined (__macos__)
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
foreach(QString paramName, _paramIO.keys()) {
if(_paramIO[paramName]) {
_paramIO[paramName]->setParamRequest();
} else {
qCritical() << "QGCParamIO is NULL" << paramName;
}
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
}
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_message_t msg;
mavlink_msg_param_ext_request_list_pack_chan(
mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
compID());
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
qCDebug(CameraControlLogVerbose) << "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;
foreach(QGCCameraOptionExclusion* param, _valueExclusions) {
Fact* pFact = getFact(param->param);
if(pFact) {
QString option = pFact->rawValueString();
if(param->value == option) {
exclusionList << param->exclusions;
}
}
}
foreach(QString key, _settings) {
if(!exclusionList.contains(key)) {
if(active != _activeSettings) {
qCDebug(CameraControlLogVerbose) << "Excluding" << exclusionList;
_activeSettings = active;
emit activeSettingsChanged();
}
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl::_processConditionTest(const QString conditionTest)
{
enum {
TEST_NONE,
TEST_EQUAL,
TEST_NOT_EQUAL,
TEST_GREATER,
TEST_SMALLER
};
qCDebug(CameraControlLogVerbose) << "_processConditionTest(" << conditionTest << ")";
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(CameraControlLogVerbose) << "_processCondition(" << condition << ")";
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) {