From 9f3203ed4da168342839cf2044e73a68bb5c3a47 Mon Sep 17 00:00:00 2001 From: laptoy <2107884590@qq.com> Date: Tue, 11 Jun 2024 14:53:16 +0800 Subject: [PATCH] add --- src/Camera/QGCCameraControl.cc | 2259 ++++++++++++++++++++++++++++++++ src/Camera/QGCCameraControl.h | 422 ++++++ src/Camera/QGCCameraIO.cc | 372 ++++++ src/Camera/QGCCameraIO.h | 72 + src/Camera/QGCCameraManager.cc | 518 ++++++++ src/Camera/QGCCameraManager.h | 112 ++ README.md => src/README.md | 0 src/api/QGCCorePlugin.cc | 502 +++++++ src/api/QGCCorePlugin.h | 222 ++++ src/api/QGCOptions.cc | 47 + src/api/QGCOptions.h | 170 +++ src/api/QGCSettings.cc | 21 + src/api/QGCSettings.h | 37 + src/api/QmlComponentInfo.cc | 19 + src/api/QmlComponentInfo.h | 35 + 15 files changed, 4808 insertions(+) create mode 100644 src/Camera/QGCCameraControl.cc create mode 100644 src/Camera/QGCCameraControl.h create mode 100644 src/Camera/QGCCameraIO.cc create mode 100644 src/Camera/QGCCameraIO.h create mode 100644 src/Camera/QGCCameraManager.cc create mode 100644 src/Camera/QGCCameraManager.h rename README.md => src/README.md (100%) create mode 100644 src/api/QGCCorePlugin.cc create mode 100644 src/api/QGCCorePlugin.h create mode 100644 src/api/QGCOptions.cc create mode 100644 src/api/QGCOptions.h create mode 100644 src/api/QGCSettings.cc create mode 100644 src/api/QGCSettings.h create mode 100644 src/api/QmlComponentInfo.cc create mode 100644 src/api/QmlComponentInfo.h diff --git a/src/Camera/QGCCameraControl.cc b/src/Camera/QGCCameraControl.cc new file mode 100644 index 0000000..f85acb7 --- /dev/null +++ b/src/Camera/QGCCameraControl.cc @@ -0,0 +1,2259 @@ + + +#include "QGCCameraControl.h" +#include "QGCCameraIO.h" +#include "SettingsManager.h" +#include "VideoManager.h" +#include "QGCMapEngine.h" +#include "QGCCameraManager.h" +#include "FTPManager.h" +#include "QGCLZMA.h" + +#include +#include +#include +#include + +QGC_LOGGING_CATEGORY(CameraControlLog, "CameraControlLog") +QGC_LOGGING_CATEGORY(CameraControlVerboseLog, "CameraControlVerboseLog") + +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* kOriginal = "original"; +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* kWriteOnly = "writeonly"; +static const char* kRoption = "roption"; +static const char* kStep = "step"; +static const char* kDecimalPlaces = "decimalPlaces"; +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"; + +static const char* kPhotoMode = "PhotoMode"; +static const char* kPhotoLapse = "PhotoLapse"; +static const char* kPhotoLapseCount = "PhotoLapseCount"; +static const char* kThermalOpacity = "ThermalOpacity"; +static const char* kThermalMode = "ThermalMode"; + +//----------------------------------------------------------------------------- +// Known Parameters +const char* QGCCameraControl::kCAM_EV = "CAM_EV"; +const char* QGCCameraControl::kCAM_EXPMODE = "CAM_EXPMODE"; +const char* QGCCameraControl::kCAM_ISO = "CAM_ISO"; +const char* QGCCameraControl::kCAM_SHUTTERSPD = "CAM_SHUTTERSPD"; +const char* QGCCameraControl::kCAM_APERTURE = "CAM_APERTURE"; +const char* QGCCameraControl::kCAM_WBMODE = "CAM_WBMODE"; +const char* QGCCameraControl::kCAM_MODE = "CAM_MODE"; + +//----------------------------------------------------------------------------- +QGCCameraOptionExclusion::QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_) + : QObject(parent) + , param(param_) + , value(value_) + , exclusions(exclusions_) +{ +} + +//----------------------------------------------------------------------------- +QGCCameraOptionRange::QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_) + : QObject(parent) + , param(param_) + , value(value_) + , targetParam(targetParam_) + , condition(condition_) + , optNames(optNames_) + , optValues(optValues_) +{ +} + +//----------------------------------------------------------------------------- +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, true /* ignore camel case */) + , _vehicle(vehicle) + , _compID(compID) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + memcpy(&_info, info, sizeof(mavlink_camera_information_t)); + connect(this, &QGCCameraControl::dataReady, this, &QGCCameraControl::_dataReady); + _vendor = QString(reinterpret_cast(info->vendor_name)); + _modelName = QString(reinterpret_cast(info->model_name)); + int ver = static_cast(_info.cam_definition_version); + _cacheFile = QString::asprintf("%s/%s_%s_%03d.xml", + qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(), + _vendor.toStdString().c_str(), + _modelName.toStdString().c_str(), + ver); + if(info->cam_definition_uri[0] != 0) { + //-- Process camera definition file + _handleDefinitionFile(info->cam_definition_uri); + } else { + _initWhenReady(); + } + QSettings settings; + _photoMode = static_cast(settings.value(kPhotoMode, static_cast(PHOTO_CAPTURE_SINGLE)).toInt()); + _photoLapse = settings.value(kPhotoLapse, 1.0).toDouble(); + _photoLapseCount = settings.value(kPhotoLapseCount, 0).toInt(); + _thermalOpacity = settings.value(kThermalOpacity, 85.0).toDouble(); + _thermalMode = static_cast(settings.value(kThermalMode, static_cast(THERMAL_BLEND)).toUInt()); + _recTimer.setSingleShot(false); + _recTimer.setInterval(333); + connect(&_recTimer, &QTimer::timeout, this, &QGCCameraControl::_recTimerHandler); +} + +//----------------------------------------------------------------------------- +QGCCameraControl::~QGCCameraControl() +{ + delete _netManager; + _netManager = nullptr; +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_initWhenReady() +{ + qCDebug(CameraControlLog) << "_initWhenReady()"; + if(isBasic()) { + qCDebug(CameraControlLog) << "Basic, MAVLink only messages."; + _requestCameraSettings(); + QTimer::singleShot(250, this, &QGCCameraControl::_checkForVideoStreams); + //-- Basic cameras have no parameters + _paramComplete = true; + emit parametersReady(); + } 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(); + + delete _netManager; + _netManager = nullptr; +} + +//----------------------------------------------------------------------------- +QString +QGCCameraControl::firmwareVersion() +{ + int major = (_info.firmware_version >> 24) & 0xFF; + int minor = (_info.firmware_version >> 16) & 0xFF; + int build = _info.firmware_version & 0xFFFF; + return QString::asprintf("%d.%d.%d", major, minor, build); +} + +//----------------------------------------------------------------------------- +QString +QGCCameraControl::recordTimeStr() +{ + return QTime(0, 0).addMSecs(static_cast(recordTime())).toString("hh:mm:ss"); +} + +//----------------------------------------------------------------------------- +QGCCameraControl::VideoStatus +QGCCameraControl::videoStatus() +{ + return _video_status; +} + +//----------------------------------------------------------------------------- +QGCCameraControl::PhotoStatus +QGCCameraControl::photoStatus() +{ + return _photo_status; +} + +//----------------------------------------------------------------------------- +QString +QGCCameraControl::storageFreeStr() +{ + return QGCMapEngine::storageFreeSizeToString(static_cast(_storageFree)); +} + +//----------------------------------------------------------------------------- +QString +QGCCameraControl::batteryRemainingStr() +{ + if(_batteryRemaining >= 0) { + return QGCMapEngine::numberToString(static_cast(_batteryRemaining)) + " %"; + } + return ""; +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setCameraMode(CameraMode mode) +{ + if(!_resetting) { + qCDebug(CameraControlLog) << "setCameraMode(" << mode << ")"; + if(mode == CAM_MODE_VIDEO) { + setVideoMode(); + } else if(mode == CAM_MODE_PHOTO) { + setPhotoMode(); + } else { + qCDebug(CameraControlLog) << "setCameraMode() Invalid mode:" << mode; + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setPhotoMode(PhotoMode mode) +{ + if(!_resetting) { + _photoMode = mode; + QSettings settings; + settings.setValue(kPhotoMode, static_cast(mode)); + emit photoModeChanged(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setPhotoLapse(qreal interval) +{ + _photoLapse = interval; + QSettings settings; + settings.setValue(kPhotoLapse, interval); + emit photoLapseChanged(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setPhotoLapseCount(int count) +{ + _photoLapseCount = count; + QSettings settings; + settings.setValue(kPhotoLapseCount, count); + emit photoLapseCountChanged(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_setCameraMode(CameraMode mode) +{ + if(_cameraMode != mode) { + _cameraMode = mode; + emit cameraModeChanged(); + //-- Update stream status + _streamStatusTimer.start(1000); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::toggleMode() +{ + if(!_resetting) { + if(cameraMode() == CAM_MODE_PHOTO || cameraMode() == CAM_MODE_SURVEY) { + setVideoMode(); + } else if(cameraMode() == CAM_MODE_VIDEO) { + setPhotoMode(); + } + } +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::toggleVideo() +{ + if(!_resetting) { + if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { + return stopVideo(); + } else { + return startVideo(); + } + } + return false; +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::takePhoto() +{ + qCDebug(CameraControlLog) << "takePhoto()"; + //-- Check if camera can capture photos or if it can capture it while in Video Mode + if(!capturesPhotos()) { + qCWarning(CameraControlLog) << "Camera does not handle image capture"; + return false; + } + if(cameraMode() == CAM_MODE_VIDEO && !photosInVideoMode()) { + qCWarning(CameraControlLog) << "Camera does not handle image capture while in video mode"; + return false; + } + if(photoStatus() != PHOTO_CAPTURE_IDLE) { + qCWarning(CameraControlLog) << "Camera not idle"; + return false; + } + if(!_resetting) { + if(capturesPhotos()) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_IMAGE_START_CAPTURE, // Command id + false, // ShowError + 0, // Reserved (Set to 0) + static_cast(_photoMode == PHOTO_CAPTURE_SINGLE ? 0 : _photoLapse), // Duration between two consecutive pictures (in seconds--ignored if single image) + _photoMode == PHOTO_CAPTURE_SINGLE ? 1 : _photoLapseCount); // Number of images to capture total - 0 for unlimited capture + _setPhotoStatus(PHOTO_CAPTURE_IN_PROGRESS); + _captureInfoRetries = 0; + //-- Capture local image as well + if(qgcApp()->toolbox()->videoManager()) { + qgcApp()->toolbox()->videoManager()->grabImage(); + } + return true; + } + } + return false; +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::stopTakePhoto() +{ + if(!_resetting) { + qCDebug(CameraControlLog) << "stopTakePhoto()"; + if(photoStatus() == PHOTO_CAPTURE_IDLE || (photoStatus() != PHOTO_CAPTURE_INTERVAL_IDLE && photoStatus() != PHOTO_CAPTURE_INTERVAL_IN_PROGRESS)) { + return false; + } + if(capturesPhotos()) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_IMAGE_STOP_CAPTURE, // Command id + false, // ShowError + 0); // Reserved (Set to 0) + _setPhotoStatus(PHOTO_CAPTURE_IDLE); + _captureInfoRetries = 0; + return true; + } + } + return false; +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::startVideo() +{ + if(!_resetting) { + 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( + _compID, // Target component + MAV_CMD_VIDEO_START_CAPTURE, // Command id + false, // Don't Show Error (handle locally) + 0, // Reserved (Set to 0) + 0); // CAMERA_CAPTURE_STATUS Frequency + return true; + } + } + return false; +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::stopVideo() +{ + if(!_resetting) { + qCDebug(CameraControlLog) << "stopVideo()"; + if(videoStatus() == VIDEO_CAPTURE_STATUS_RUNNING) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_STOP_CAPTURE, // Command id + false, // Don't Show Error (handle locally) + 0); // Reserved (Set to 0) + return true; + } + } + return false; +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setVideoMode() +{ + if(!_resetting && hasModes()) { + qCDebug(CameraControlLog) << "setVideoMode()"; + //-- Does it have a mode parameter? + Fact* pMode = mode(); + if(pMode) { + if(cameraMode() != CAM_MODE_VIDEO) { + pMode->setRawValue(CAM_MODE_VIDEO); + _setCameraMode(CAM_MODE_VIDEO); + } + } else { + //-- Use MAVLink Command + if(_cameraMode != CAM_MODE_VIDEO) { + //-- Use basic MAVLink message + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_MODE, // Command id + true, // ShowError + 0, // Reserved (Set to 0) + CAM_MODE_VIDEO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_VIDEO); + } + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setPhotoMode() +{ + if(!_resetting && hasModes()) { + qCDebug(CameraControlLog) << "setPhotoMode()"; + //-- Does it have a mode parameter? + Fact* pMode = mode(); + if(pMode) { + if(cameraMode() != CAM_MODE_PHOTO) { + pMode->setRawValue(CAM_MODE_PHOTO); + _setCameraMode(CAM_MODE_PHOTO); + } + } else { + //-- Use MAVLink Command + if(_cameraMode != CAM_MODE_PHOTO) { + //-- Use basic MAVLink message + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_MODE, // Command id + true, // ShowError + 0, // Reserved (Set to 0) + CAM_MODE_PHOTO); // Camera mode (0: photo, 1: video) + _setCameraMode(CAM_MODE_PHOTO); + } + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setThermalMode(ThermalViewMode mode) +{ + QSettings settings; + settings.setValue(kThermalMode, static_cast(mode)); + _thermalMode = mode; + emit thermalModeChanged(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setThermalOpacity(double val) +{ + if(val < 0.0) val = 0.0; + if(val > 100.0) val = 100.0; + if(fabs(_thermalOpacity - val) > 0.1) { + _thermalOpacity = val; + QSettings settings; + settings.setValue(kThermalOpacity, val); + emit thermalOpacityChanged(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setZoomLevel(qreal level) +{ + qCDebug(CameraControlLog) << "setZoomLevel()" << level; + if(hasZoom()) { + //-- Limit + level = std::min(std::max(level, 0.0), 100.0); + if(_vehicle) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_ZOOM, // Command id + false, // ShowError + ZOOM_TYPE_RANGE, // Zoom type + static_cast(level)); // Level + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::setFocusLevel(qreal level) +{ + qCDebug(CameraControlLog) << "setFocusLevel()" << level; + if(hasFocus()) { + //-- Limit + level = std::min(std::max(level, 0.0), 100.0); + if(_vehicle) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_FOCUS, // Command id + false, // ShowError + FOCUS_TYPE_RANGE, // Focus type + static_cast(level)); // Level + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::resetSettings() +{ + if(!_resetting) { + qCDebug(CameraControlLog) << "resetSettings()"; + _resetting = true; + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_RESET_CAMERA_SETTINGS, // Command id + true, // ShowError + 1); // Do Reset + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::formatCard(int id) +{ + if(!_resetting) { + 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::stepZoom(int direction) +{ + qCDebug(CameraControlLog) << "stepZoom()" << direction; + if(_vehicle && hasZoom()) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_ZOOM, // Command id + false, // ShowError + ZOOM_TYPE_STEP, // Zoom type + direction); // Direction (-1 wide, 1 tele) + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::startZoom(int direction) +{ + qCDebug(CameraControlLog) << "startZoom()" << direction; + if(_vehicle && hasZoom()) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_ZOOM, // Command id + false, // ShowError + ZOOM_TYPE_CONTINUOUS, // Zoom type + direction); // Direction (-1 wide, 1 tele) + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::stopZoom() +{ + qCDebug(CameraControlLog) << "stopZoom()"; + if(_vehicle && hasZoom()) { + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_SET_CAMERA_ZOOM, // Command id + false, // ShowError + ZOOM_TYPE_CONTINUOUS, // Zoom type + 0); // Direction (-1 wide, 1 tele) + } +} + +//----------------------------------------------------------------------------- +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: + _resetting = false; + 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); + break; + case MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS: + _captureInfoRetries = 0; + break; + case MAV_CMD_REQUEST_STORAGE_INFORMATION: + _storageInfoRetries = 0; + break; + case MAV_CMD_IMAGE_START_CAPTURE: + _captureStatusTimer.start(1000); + break; + } + } else { + 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_RESET_CAMERA_SETTINGS: + _resetting = false; + qCDebug(CameraControlLog) << "Failed to reset camera settings"; + break; + case MAV_CMD_IMAGE_START_CAPTURE: + case MAV_CMD_IMAGE_STOP_CAPTURE: + if(++_captureInfoRetries < 3) { + _captureStatusTimer.start(1000); + } else { + qCDebug(CameraControlLog) << "Giving up start/stop image capture"; + _setPhotoStatus(PHOTO_CAPTURE_IDLE); + } + 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; + } + } else { + qCDebug(CameraControlLog) << "Bad response for" << command << result; + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_setVideoStatus(VideoStatus status) +{ + if(_video_status != status) { + _video_status = status; + emit videoStatusChanged(); + if(status == VIDEO_CAPTURE_STATUS_RUNNING) { + _recordTime = 0; + _recTime = QTime::currentTime(); + _recTimer.start(); + } else { + _recTimer.stop(); + _recordTime = 0; + emit recordTimeChanged(); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_recTimerHandler() +{ + _recordTime = static_cast(_recTime.msecsTo(QTime::currentTime())); + emit recordTimeChanged(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_setPhotoStatus(PhotoStatus status) +{ + if(_photo_status != status) { + qCDebug(CameraControlLog) << "Set Photo Status:" << status; + _photo_status = status; + emit photoStatusChanged(); + } +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::_loadCameraDefinitionFile(QByteArray& bytes) +{ + QByteArray originalData(bytes); + //-- Handle localization + if(!_handleLocalization(bytes)) { + return false; + } + int errorLine; + QString errorMsg; + QDomDocument doc; + if(!doc.setContent(bytes, false, &errorMsg, &errorLine)) { + qCCritical(CameraControlLog) << "Unable to parse camera definition file on line:" << errorLine; + qCCritical(CameraControlLog) << errorMsg; + return false; + } + //-- Load camera constants + QDomNodeList defElements = doc.elementsByTagName(kDefnition); + if(!defElements.size() || !_loadConstants(defElements)) { + qCWarning(CameraControlLog) << "Unable to load camera constants from camera definition"; + return false; + } + //-- Load camera parameters + QDomNodeList paramElements = doc.elementsByTagName(kParameters); + if(!paramElements.size()) { + qCDebug(CameraControlLog) << "No parameters to load from camera"; + return false; + } + if(!_loadSettings(paramElements)) { + qCWarning(CameraControlLog) << "Unable to load camera parameters from camera definition"; + return false; + } + //-- If this is new, cache it + if(!_cached) { + qCDebug(CameraControlLog) << "Saving camera definition file" << _cacheFile; + QFile file(_cacheFile); + if (!file.open(QIODevice::WriteOnly)) { + qWarning() << QString("Could not save cache file %1. Error: %2").arg(_cacheFile).arg(file.errorString()); + } else { + file.write(originalData); + } + } + 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); + //-- Is it write only? + bool writeOnly = false; + read_attribute(parameterNode, kWriteOnly, writeOnly); + //-- It can't be both + if(readOnly && writeOnly) { + qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName); + } + //-- 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; + } + //-- Description + 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(CameraControlVerboseLog) << "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); + metaData->setWriteOnly(writeOnly); + //-- 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(CameraControlVerboseLog) << "New exclusions:" << factName << optValue << exclusions; + QGCCameraOptionExclusion* pExc = new QGCCameraOptionExclusion(this, factName, optValue, exclusions); + QQmlEngine::setObjectOwnership(pExc, QQmlEngine::CppOwnership); + _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 { + { + //-- 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->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); + pFact->setMetaData(metaData); + pFact->_containerSetRawValue(metaData->rawDefaultValue()); + QGCCameraParamIO* pIO = new QGCCameraParamIO(this, pFact, _vehicle); + QQmlEngine::setObjectOwnership(pIO, QQmlEngine::CppOwnership); + _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 (Q_OS_MAC) + 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; + } + } + WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink(); + if (!weakLink.expired()) { + SharedLinkInterfacePtr sharedLink = weakLink.lock(); + + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); + mavlink_message_t msg; + mavlink_msg_param_ext_request_list_pack_chan( + static_cast(mavlink->getSystemId()), + static_cast(mavlink->getComponentId()), + sharedLink->mavlinkChannel(), + &msg, + static_cast(_vehicle->id()), + static_cast(compID())); + _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), 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) { + if(!exclusionList.contains(key)) { + 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 << ")"; + int op = TEST_NONE; + QStringList test; + + auto split = [&conditionTest](const QString& sep ) { + return conditionTest.split(sep, Qt::SkipEmptyParts); + }; + + if(conditionTest.contains("!=")) { + test = split("!="); + op = TEST_NOT_EQUAL; + } else if(conditionTest.contains("=")) { + test = split("="); + op = TEST_EQUAL; + } else if(conditionTest.contains(">")) { + test = split(">"); + op = TEST_GREATER; + } else if(conditionTest.contains("<")) { + test = split("<"); + 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 << ")"; + bool result = true; + bool andOp = true; + if(!condition.isEmpty()) { + QStringList scond = condition.split(" ", Qt::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 rangesSet; + QMap 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; + } + changedList << pRange->targetParam; + } + } + } + } + //-- 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(settings.mode_id)); + qreal z = static_cast(settings.zoomLevel); + qreal f = static_cast(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(st.total_capacity); + if(_storageTotal != t) { + _storageTotal = t; + emit storageTotalChanged(); + } + uint32_t a = static_cast(st.available_capacity); + if(_storageFree != a) { + _storageFree = a; + emit storageFreeChanged(); + } + } + if(_storageStatus != static_cast(st.status)) { + _storageStatus = static_cast(st.status); + emit storageStatusChanged(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::handleBatteryStatus(const mavlink_battery_status_t& bs) +{ + qCDebug(CameraControlLog) << "handleBatteryStatus:" << bs.battery_remaining; + if(bs.battery_remaining >= 0 && _batteryRemaining != static_cast(bs.battery_remaining)) { + _batteryRemaining = static_cast(bs.battery_remaining); + emit batteryRemainingChanged(); + } +} + +//----------------------------------------------------------------------------- +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(cap.available_capacity); + if(_storageFree != a) { + _storageFree = a; + emit storageFreeChanged(); + } + //-- Do we have recording time? + if(cap.recording_time_ms) { + // Resync our _recTime timer to the time info received from the camera component + _recordTime = cap.recording_time_ms; + _recTime = _recTime.addMSecs(_recTime.msecsTo(QTime::currentTime()) - static_cast(cap.recording_time_ms)); + emit recordTimeChanged(); + } + //-- Video/Image Capture Status + uint8_t vs = cap.video_status < static_cast(VIDEO_CAPTURE_STATUS_LAST) ? cap.video_status : static_cast(VIDEO_CAPTURE_STATUS_UNDEFINED); + uint8_t ps = cap.image_status < static_cast(PHOTO_CAPTURE_LAST) ? cap.image_status : static_cast(PHOTO_CAPTURE_STATUS_UNDEFINED); + _setVideoStatus(static_cast(vs)); + _setPhotoStatus(static_cast(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()) { + 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()->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->cameraManager()->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(); + _vehicle->sendMavCommand( + _compID, // Target component + MAV_CMD_VIDEO_START_STREAMING, // Command id + false, // ShowError + pInfo->streamID()); // Stream ID + //-- Update stream status + _requestStreamStatus(static_cast(pInfo->streamID())); + } + emit currentStreamChanged(); + emit _vehicle->cameraManager()->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(_streams[i]); + if(pStream) { + if(pStream->isThermal()) { + return pStream; + } + } + } + } + return nullptr; +} + +//----------------------------------------------------------------------------- +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(_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(_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->cameraManager()->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(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; +} + +//----------------------------------------------------------------------------- +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; +} + +//----------------------------------------------------------------------------- +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) { + 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 + QFile xmlFile(_cacheFile); + + QString ftpPrefix(QStringLiteral("%1://").arg(FTPManager::mavlinkFTPScheme)); + if (!xmlFile.exists() && url.startsWith(ftpPrefix, Qt::CaseInsensitive)) { + qCDebug(CameraControlLog) << "No camera definition file cached, attempt ftp download"; + int ver = static_cast(_info.cam_definition_version); + QString ext = ""; + if (url.endsWith(".lzma", Qt::CaseInsensitive)) { ext = ".lzma"; } + if (url.endsWith(".xz", Qt::CaseInsensitive)) { ext = ".xz"; } + QString fileName = QString::asprintf("%s_%s_%03d.xml%s", + _vendor.toStdString().c_str(), + _modelName.toStdString().c_str(), + ver, + ext.toStdString().c_str()); + connect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &QGCCameraControl::_ftpDownloadComplete); + _vehicle->ftpManager()->download(_compID, url, + qgcApp()->toolbox()->settingsManager()->appSettings()->parameterSavePath().toStdString().c_str(), + fileName); + return; + } + + if (!xmlFile.exists()) { + qCDebug(CameraControlLog) << "No camera definition file cached, attempt http download"; + _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); +} + +//----------------------------------------------------------------------------- +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::RedirectPolicyAttribute, 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(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 (%1) download error: %2 status: %3").arg( + reply->url().toDisplayString(), + reply->errorString(), + reply->attribute(QNetworkRequest::HttpStatusCodeAttribute).toString() + ); + } + emit dataReady(data); + //reply->deleteLater(); +} + +void QGCCameraControl::_ftpDownloadComplete(const QString& fileName, const QString& errorMsg) +{ + qCDebug(CameraControlLog) << "FTP Download completed: " << fileName << ", " << errorMsg; + + disconnect(_vehicle->ftpManager(), &FTPManager::downloadComplete, this, &QGCCameraControl::_ftpDownloadComplete); + + QString outputFileName = fileName; + + if (fileName.endsWith(".lzma", Qt::CaseInsensitive) || fileName.endsWith(".xz", Qt::CaseInsensitive)) { + outputFileName = fileName.left(fileName.lastIndexOf(".")); + if (QGCLZMA::inflateLZMAFile(fileName, outputFileName)) { + QFile(fileName).remove(); + } else { + qCWarning(CameraControlLog) << "Inflate of compressed xml failed" << fileName; + outputFileName.clear(); + } + } + + QFile xmlFile(outputFileName); + + if (!xmlFile.exists()) { + qCDebug(CameraControlLog) << "No camera definition file present after ftp download completed"; + return; + } + if (!xmlFile.open(QIODevice::ReadOnly)) { + qWarning() << "Could not read downloaded camera definition file: " << fileName; + return; + } + + _cached = true; + QByteArray bytes = xmlFile.readAll(); + emit dataReady(bytes); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_dataReady(QByteArray data) +{ + if(data.size()) { + qCDebug(CameraControlLog) << "Parsing camera definition"; + _loadCameraDefinitionFile(data); + } else { + qCDebug(CameraControlLog) << "No camera definition"; + } + _initWhenReady(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_paramDone() +{ + for(const QString& param: _paramIO.keys()) { + if(!_paramIO[param]->paramDone()) { + return; + } + } + //-- All parameters loaded (or timed out) + _paramComplete = true; + emit parametersReady(); + //-- Check for video streaming + _checkForVideoStreams(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraControl::_checkForVideoStreams() +{ + if(_info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM) { + //-- Skip it if using Taisync as it has its own video settings + if(!qgcApp()->toolbox()->videoManager()->isTaisync()) { + connect(&_streamInfoTimer, &QTimer::timeout, this, &QGCCameraControl::_streamTimeout); + _streamInfoTimer.setSingleShot(false); + connect(&_streamStatusTimer, &QTimer::timeout, this, &QGCCameraControl::_streamStatusTimeout); + _streamStatusTimer.setSingleShot(true); + //-- Request all streams + _requestStreamInfo(0); + _streamInfoTimer.start(2000); + } + } +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue) +{ + Q_UNUSED(pFact); + Q_UNUSED(newValue); + return true; +} + +//----------------------------------------------------------------------------- +bool +QGCCameraControl::validateParameter(Fact* pFact, QVariant& newValue) +{ + Q_UNUSED(pFact); + Q_UNUSED(newValue); + return true; +} + +//----------------------------------------------------------------------------- +QStringList +QGCCameraControl::activeSettings() +{ + qCDebug(CameraControlLog) << "Active:" << _activeSettings; + return _activeSettings; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::exposureMode() +{ + return (_paramComplete && _activeSettings.contains(kCAM_EXPMODE)) ? getFact(kCAM_EXPMODE) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::ev() +{ + return (_paramComplete && _activeSettings.contains(kCAM_EV)) ? getFact(kCAM_EV) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::iso() +{ + return (_paramComplete && _activeSettings.contains(kCAM_ISO)) ? getFact(kCAM_ISO) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::shutterSpeed() +{ + return (_paramComplete && _activeSettings.contains(kCAM_SHUTTERSPD)) ? getFact(kCAM_SHUTTERSPD) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::aperture() +{ + return (_paramComplete && _activeSettings.contains(kCAM_APERTURE)) ? getFact(kCAM_APERTURE) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::wb() +{ + return (_paramComplete && _activeSettings.contains(kCAM_WBMODE)) ? getFact(kCAM_WBMODE) : nullptr; +} + +//----------------------------------------------------------------------------- +Fact* +QGCCameraControl::mode() +{ + return _paramComplete && factExists(kCAM_MODE) ? getFact(kCAM_MODE) : nullptr; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo::QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t *si) + : QObject(parent) +{ + memcpy(&_streamInfo, si, sizeof(mavlink_video_stream_information_t)); +} + +//----------------------------------------------------------------------------- +qreal +QGCVideoStreamInfo::aspectRatio() const +{ + qreal ar = 1.0; + if(_streamInfo.resolution_h && _streamInfo.resolution_v) { + ar = static_cast(_streamInfo.resolution_h) / static_cast(_streamInfo.resolution_v); + } + return ar; +} + +//----------------------------------------------------------------------------- +bool +QGCVideoStreamInfo::update(const mavlink_video_stream_status_t* vs) +{ + bool changed = false; + if(_streamInfo.hfov != vs->hfov) { + changed = true; + _streamInfo.hfov = vs->hfov; + } + if(_streamInfo.flags != vs->flags) { + changed = true; + _streamInfo.flags = vs->flags; + } + if(_streamInfo.bitrate != vs->bitrate) { + changed = true; + _streamInfo.bitrate = vs->bitrate; + } + if(_streamInfo.rotation != vs->rotation) { + changed = true; + _streamInfo.rotation = vs->rotation; + } + if(_streamInfo.framerate != vs->framerate) { + changed = true; + _streamInfo.framerate = vs->framerate; + } + if(_streamInfo.resolution_h != vs->resolution_h) { + changed = true; + _streamInfo.resolution_h = vs->resolution_h; + } + if(_streamInfo.resolution_v != vs->resolution_v) { + changed = true; + _streamInfo.resolution_v = vs->resolution_v; + } + if(changed) { + emit infoChanged(); + } + return changed; +} diff --git a/src/Camera/QGCCameraControl.h b/src/Camera/QGCCameraControl.h new file mode 100644 index 0000000..a34194e --- /dev/null +++ b/src/Camera/QGCCameraControl.h @@ -0,0 +1,422 @@ + + +#pragma once + +#include "QGCApplication.h" +#include + +class QDomNode; +class QDomNodeList; +class QGCCameraParamIO; + +Q_DECLARE_LOGGING_CATEGORY(CameraControlLog) +Q_DECLARE_LOGGING_CATEGORY(CameraControlVerboseLog) + +//----------------------------------------------------------------------------- +/// Video Stream Info +/// Encapsulates the contents of a [VIDEO_STREAM_INFORMATION](https://mavlink.io/en/messages/common.html#VIDEO_STREAM_INFORMATION) message +class QGCVideoStreamInfo : public QObject +{ + Q_OBJECT +public: + QGCVideoStreamInfo(QObject* parent, const mavlink_video_stream_information_t* si); + + Q_PROPERTY(QString uri READ uri NOTIFY infoChanged) + Q_PROPERTY(QString name READ name NOTIFY infoChanged) + Q_PROPERTY(int streamID READ streamID NOTIFY infoChanged) + Q_PROPERTY(int type READ type NOTIFY infoChanged) + Q_PROPERTY(qreal aspectRatio READ aspectRatio NOTIFY infoChanged) + Q_PROPERTY(qreal hfov READ hfov NOTIFY infoChanged) + Q_PROPERTY(bool isThermal READ isThermal NOTIFY infoChanged) + + QString uri () { return QString(_streamInfo.uri); } + QString name () { return QString(_streamInfo.name); } + qreal aspectRatio () const; + qreal hfov () const{ return _streamInfo.hfov; } + int type () const{ return _streamInfo.type; } + int streamID () const{ return _streamInfo.stream_id; } + bool isThermal () const{ return _streamInfo.flags & VIDEO_STREAM_STATUS_FLAGS_THERMAL; } + + bool update (const mavlink_video_stream_status_t* vs); + +signals: + void infoChanged (); + +private: + mavlink_video_stream_information_t _streamInfo; +}; + +//----------------------------------------------------------------------------- +/// Camera option exclusions +class QGCCameraOptionExclusion : public QObject +{ +public: + QGCCameraOptionExclusion(QObject* parent, QString param_, QString value_, QStringList exclusions_); + QString param; + QString value; + QStringList exclusions; +}; + +//----------------------------------------------------------------------------- +/// Camera option ranges +class QGCCameraOptionRange : public QObject +{ +public: + QGCCameraOptionRange(QObject* parent, QString param_, QString value_, QString targetParam_, QString condition_, QStringList optNames_, QStringList optValues_); + QString param; + QString value; + QString targetParam; + QString condition; + QStringList optNames; + QStringList optValues; + QVariantList optVariants; +}; + +//----------------------------------------------------------------------------- +/// MAVLink Camera API controller +class QGCCameraControl : public FactGroup +{ + Q_OBJECT + friend class QGCCameraParamIO; +public: + QGCCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = nullptr); + virtual ~QGCCameraControl(); + + //-- cam_mode + enum CameraMode { + CAM_MODE_UNDEFINED = -1, + CAM_MODE_PHOTO = 0, + CAM_MODE_VIDEO = 1, + CAM_MODE_SURVEY = 2, + }; + + //-- Video Capture Status + enum VideoStatus { + VIDEO_CAPTURE_STATUS_STOPPED = 0, + VIDEO_CAPTURE_STATUS_RUNNING, + VIDEO_CAPTURE_STATUS_LAST, + VIDEO_CAPTURE_STATUS_UNDEFINED = 255 + }; + + //-- Photo Capture Status + enum PhotoStatus { + PHOTO_CAPTURE_IDLE = 0, + PHOTO_CAPTURE_IN_PROGRESS, + PHOTO_CAPTURE_INTERVAL_IDLE, + PHOTO_CAPTURE_INTERVAL_IN_PROGRESS, + PHOTO_CAPTURE_LAST, + PHOTO_CAPTURE_STATUS_UNDEFINED = 255 + }; + + //-- Photo Capture Modes + enum PhotoMode { + PHOTO_CAPTURE_SINGLE = 0, + PHOTO_CAPTURE_TIMELAPSE, + }; + + //-- Storage Status + enum StorageStatus { + STORAGE_EMPTY = STORAGE_STATUS_EMPTY, + STORAGE_UNFORMATTED = STORAGE_STATUS_UNFORMATTED, + STORAGE_READY = STORAGE_STATUS_READY, + STORAGE_NOT_SUPPORTED = STORAGE_STATUS_NOT_SUPPORTED + }; + + enum ThermalViewMode { + THERMAL_OFF = 0, + THERMAL_BLEND, + THERMAL_FULL, + THERMAL_PIP, + }; + + Q_ENUM(CameraMode) + Q_ENUM(VideoStatus) + Q_ENUM(PhotoStatus) + Q_ENUM(PhotoMode) + Q_ENUM(StorageStatus) + Q_ENUM(ThermalViewMode) + + Q_PROPERTY(int version READ version NOTIFY infoChanged) + Q_PROPERTY(QString modelName READ modelName NOTIFY infoChanged) + Q_PROPERTY(QString vendor READ vendor NOTIFY infoChanged) + Q_PROPERTY(QString firmwareVersion READ firmwareVersion NOTIFY infoChanged) + Q_PROPERTY(qreal focalLength READ focalLength NOTIFY infoChanged) + Q_PROPERTY(QSizeF sensorSize READ sensorSize NOTIFY infoChanged) + Q_PROPERTY(QSize resolution READ resolution NOTIFY infoChanged) + Q_PROPERTY(bool capturesVideo READ capturesVideo NOTIFY infoChanged) + Q_PROPERTY(bool capturesPhotos READ capturesPhotos NOTIFY infoChanged) + Q_PROPERTY(bool hasModes READ hasModes NOTIFY infoChanged) + Q_PROPERTY(bool hasZoom READ hasZoom NOTIFY infoChanged) + Q_PROPERTY(bool hasFocus READ hasFocus NOTIFY infoChanged) + Q_PROPERTY(bool hasVideoStream READ hasVideoStream NOTIFY infoChanged) + Q_PROPERTY(bool photosInVideoMode READ photosInVideoMode NOTIFY infoChanged) + Q_PROPERTY(bool videoInPhotoMode READ videoInPhotoMode NOTIFY infoChanged) + Q_PROPERTY(bool isBasic READ isBasic NOTIFY infoChanged) + Q_PROPERTY(quint32 storageFree READ storageFree NOTIFY storageFreeChanged) + Q_PROPERTY(QString storageFreeStr READ storageFreeStr NOTIFY storageFreeChanged) + Q_PROPERTY(quint32 storageTotal READ storageTotal NOTIFY storageTotalChanged) + Q_PROPERTY(int batteryRemaining READ batteryRemaining NOTIFY batteryRemainingChanged) + Q_PROPERTY(QString batteryRemainingStr READ batteryRemainingStr NOTIFY batteryRemainingChanged) + Q_PROPERTY(bool paramComplete READ paramComplete NOTIFY parametersReady) + + Q_PROPERTY(qreal zoomLevel READ zoomLevel WRITE setZoomLevel NOTIFY zoomLevelChanged) + Q_PROPERTY(qreal focusLevel READ focusLevel WRITE setFocusLevel NOTIFY focusLevelChanged) + + Q_PROPERTY(Fact* exposureMode READ exposureMode NOTIFY parametersReady) + Q_PROPERTY(Fact* ev READ ev NOTIFY parametersReady) + Q_PROPERTY(Fact* iso READ iso NOTIFY parametersReady) + Q_PROPERTY(Fact* shutterSpeed READ shutterSpeed NOTIFY parametersReady) + Q_PROPERTY(Fact* aperture READ aperture NOTIFY parametersReady) + Q_PROPERTY(Fact* wb READ wb NOTIFY parametersReady) + Q_PROPERTY(Fact* mode READ mode NOTIFY parametersReady) + + Q_PROPERTY(QStringList activeSettings READ activeSettings NOTIFY activeSettingsChanged) + Q_PROPERTY(VideoStatus videoStatus READ videoStatus NOTIFY videoStatusChanged) + Q_PROPERTY(PhotoStatus photoStatus READ photoStatus NOTIFY photoStatusChanged) + Q_PROPERTY(CameraMode cameraMode READ cameraMode WRITE setCameraMode NOTIFY cameraModeChanged) + Q_PROPERTY(StorageStatus storageStatus READ storageStatus NOTIFY storageStatusChanged) + Q_PROPERTY(qreal photoLapse READ photoLapse WRITE setPhotoLapse NOTIFY photoLapseChanged) + Q_PROPERTY(int photoLapseCount READ photoLapseCount WRITE setPhotoLapseCount NOTIFY photoLapseCountChanged) + Q_PROPERTY(PhotoMode photoMode READ photoMode WRITE setPhotoMode NOTIFY photoModeChanged) + Q_PROPERTY(int currentStream READ currentStream WRITE setCurrentStream NOTIFY currentStreamChanged) + Q_PROPERTY(bool autoStream READ autoStream NOTIFY autoStreamChanged) + Q_PROPERTY(QmlObjectListModel* streams READ streams NOTIFY streamsChanged) + Q_PROPERTY(QGCVideoStreamInfo* currentStreamInstance READ currentStreamInstance NOTIFY currentStreamChanged) + Q_PROPERTY(QGCVideoStreamInfo* thermalStreamInstance READ thermalStreamInstance NOTIFY thermalStreamChanged) + Q_PROPERTY(quint32 recordTime READ recordTime NOTIFY recordTimeChanged) + Q_PROPERTY(QString recordTimeStr READ recordTimeStr NOTIFY recordTimeChanged) + Q_PROPERTY(QStringList streamLabels READ streamLabels NOTIFY streamLabelsChanged) + Q_PROPERTY(ThermalViewMode thermalMode READ thermalMode WRITE setThermalMode NOTIFY thermalModeChanged) + Q_PROPERTY(double thermalOpacity READ thermalOpacity WRITE setThermalOpacity NOTIFY thermalOpacityChanged) + + Q_INVOKABLE virtual void setVideoMode (); + Q_INVOKABLE virtual void setPhotoMode (); + Q_INVOKABLE virtual void toggleMode (); + Q_INVOKABLE virtual bool takePhoto (); + Q_INVOKABLE virtual bool stopTakePhoto (); + Q_INVOKABLE virtual bool startVideo (); + Q_INVOKABLE virtual bool stopVideo (); + Q_INVOKABLE virtual bool toggleVideo (); + Q_INVOKABLE virtual void resetSettings (); + Q_INVOKABLE virtual void formatCard (int id = 1); + Q_INVOKABLE virtual void stepZoom (int direction); + Q_INVOKABLE virtual void startZoom (int direction); + Q_INVOKABLE virtual void stopZoom (); + Q_INVOKABLE virtual void stopStream (); + Q_INVOKABLE virtual void resumeStream (); + + virtual int version () { return _version; } + virtual QString modelName () { return _modelName; } + virtual QString vendor () { return _vendor; } + virtual QString firmwareVersion (); + virtual qreal focalLength () { return static_cast(_info.focal_length); } + virtual QSizeF sensorSize () { return QSizeF(static_cast(_info.sensor_size_h), static_cast(_info.sensor_size_v)); } + virtual QSize resolution () { return QSize(_info.resolution_h, _info.resolution_v); } + virtual bool capturesVideo () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO; } + virtual bool capturesPhotos () { return _info.flags & CAMERA_CAP_FLAGS_CAPTURE_IMAGE; } + virtual bool hasModes () { return _info.flags & CAMERA_CAP_FLAGS_HAS_MODES; } + virtual bool hasZoom () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM; } + virtual bool hasFocus () { return _info.flags & CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS; } + virtual bool hasVideoStream () { return _info.flags & CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM; } + virtual bool photosInVideoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE; } + virtual bool videoInPhotoMode () { return _info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE; } + + virtual int compID () { return _compID; } + virtual bool isBasic () { return _settings.size() == 0; } + virtual VideoStatus videoStatus (); + virtual PhotoStatus photoStatus (); + virtual PhotoMode photoMode () { return _photoMode; } + virtual qreal photoLapse () { return _photoLapse; } + virtual int photoLapseCount () { return _photoLapseCount; } + virtual CameraMode cameraMode () { return _cameraMode; } + virtual StorageStatus storageStatus () { return _storageStatus; } + virtual QStringList activeSettings (); + virtual quint32 storageFree () { return _storageFree; } + virtual QString storageFreeStr (); + virtual quint32 storageTotal () { return _storageTotal; } + virtual int batteryRemaining () { return _batteryRemaining; } + virtual QString batteryRemainingStr (); + virtual bool paramComplete () { return _paramComplete; } + virtual qreal zoomLevel () { return _zoomLevel; } + virtual qreal focusLevel () { return _focusLevel; } + + virtual QmlObjectListModel* streams () { return &_streams; } + virtual QGCVideoStreamInfo* currentStreamInstance(); + virtual QGCVideoStreamInfo* thermalStreamInstance(); + virtual int currentStream () { return _currentStream; } + virtual void setCurrentStream (int stream); + virtual bool autoStream (); + virtual quint32 recordTime () { return _recordTime; } + virtual QString recordTimeStr (); + + virtual Fact* exposureMode (); + virtual Fact* ev (); + virtual Fact* iso (); + virtual Fact* shutterSpeed (); + virtual Fact* aperture (); + virtual Fact* wb (); + virtual Fact* mode (); + + /// Stream names to show the user (for selection) + virtual QStringList streamLabels () { return _streamLabels; } + + virtual ThermalViewMode thermalMode () { return _thermalMode; } + virtual void setThermalMode (ThermalViewMode mode); + virtual double thermalOpacity () { return _thermalOpacity; } + virtual void setThermalOpacity (double val); + + virtual void setZoomLevel (qreal level); + virtual void setFocusLevel (qreal level); + virtual void setCameraMode (CameraMode mode); + virtual void setPhotoMode (PhotoMode mode); + virtual void setPhotoLapse (qreal interval); + virtual void setPhotoLapseCount (int count); + + virtual void handleSettings (const mavlink_camera_settings_t& settings); + virtual void handleCaptureStatus (const mavlink_camera_capture_status_t& capStatus); + virtual void handleParamAck (const mavlink_param_ext_ack_t& ack); + virtual void handleParamValue (const mavlink_param_ext_value_t& value); + virtual void handleStorageInfo (const mavlink_storage_information_t& st); + virtual void handleBatteryStatus (const mavlink_battery_status_t& bs); + virtual void handleVideoInfo (const mavlink_video_stream_information_t *vi); + virtual void handleVideoStatus (const mavlink_video_stream_status_t *vs); + + /// Notify controller a parameter has changed + virtual void factChanged (Fact* pFact); + /// Allow controller to modify or invalidate incoming parameter + virtual bool incomingParameter (Fact* pFact, QVariant& newValue); + /// Allow controller to modify or invalidate parameter change + virtual bool validateParameter (Fact* pFact, QVariant& newValue); + + // Known Parameters + static const char* kCAM_EV; + static const char* kCAM_EXPMODE; + static const char* kCAM_ISO; + static const char* kCAM_SHUTTERSPD; + static const char* kCAM_APERTURE; + static const char* kCAM_WBMODE; + static const char* kCAM_MODE; + +signals: + void infoChanged (); + void videoStatusChanged (); + void photoStatusChanged (); + void photoModeChanged (); + void photoLapseChanged (); + void photoLapseCountChanged (); + void cameraModeChanged (); + void activeSettingsChanged (); + void storageFreeChanged (); + void storageTotalChanged (); + void batteryRemainingChanged (); + void dataReady (QByteArray data); + void parametersReady (); + void zoomLevelChanged (); + void focusLevelChanged (); + void streamsChanged (); + void currentStreamChanged (); + void thermalStreamChanged (); + void autoStreamChanged (); + void recordTimeChanged (); + void streamLabelsChanged (); + void thermalModeChanged (); + void thermalOpacityChanged (); + void storageStatusChanged (); + +protected: + virtual void _setVideoStatus (VideoStatus status); + virtual void _setPhotoStatus (PhotoStatus status); + virtual void _setCameraMode (CameraMode mode); + virtual void _requestStreamInfo (uint8_t streamID); + virtual void _requestStreamStatus (uint8_t streamID); + virtual QGCVideoStreamInfo* _findStream (uint8_t streamID, bool report = true); + virtual QGCVideoStreamInfo* _findStream (const QString name); + +protected slots: + virtual void _initWhenReady (); + virtual void _requestCameraSettings (); + virtual void _requestAllParameters (); + virtual void _requestParamUpdates (); + virtual void _requestCaptureStatus (); + virtual void _requestStorageInfo (); + virtual void _downloadFinished (); + virtual void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); + virtual void _dataReady (QByteArray data); + virtual void _paramDone (); + virtual void _streamTimeout (); + virtual void _streamStatusTimeout (); + virtual void _recTimerHandler (); + virtual void _checkForVideoStreams (); + +private: + bool _handleLocalization (QByteArray& bytes); + bool _replaceLocaleStrings (const QDomNode node, QByteArray& bytes); + bool _loadCameraDefinitionFile (QByteArray& bytes); + bool _loadConstants (const QDomNodeList nodeList); + bool _loadSettings (const QDomNodeList nodeList); + void _processRanges (); + bool _processCondition (const QString condition); + bool _processConditionTest (const QString conditionTest); + bool _loadNameValue (QDomNode option, const QString factName, FactMetaData* metaData, QString& optName, QString& optValue, QVariant& optVariant); + bool _loadRanges (QDomNode option, const QString factName, QString paramValue); + void _updateActiveList (); + void _updateRanges (Fact* pFact); + void _httpRequest (const QString& url); + void _handleDefinitionFile (const QString& url); + void _ftpDownloadComplete (const QString& fileName, const QString& errorMsg); + + QStringList _loadExclusions (QDomNode option); + QStringList _loadUpdates (QDomNode option); + QString _getParamName (const char* param_id); + +protected: + Vehicle* _vehicle = nullptr; + int _compID = 0; + mavlink_camera_information_t _info; + int _version = 0; + bool _cached = false; + bool _paramComplete = false; + qreal _zoomLevel = 0.0; + qreal _focusLevel = 0.0; + uint32_t _storageFree = 0; + uint32_t _storageTotal = 0; + int _batteryRemaining = -1; + QNetworkAccessManager* _netManager = nullptr; + QString _modelName; + QString _vendor; + QString _cacheFile; + CameraMode _cameraMode = CAM_MODE_UNDEFINED; + StorageStatus _storageStatus = STORAGE_NOT_SUPPORTED; + PhotoMode _photoMode = PHOTO_CAPTURE_SINGLE; + qreal _photoLapse = 1.0; + int _photoLapseCount = 0; + VideoStatus _video_status = VIDEO_CAPTURE_STATUS_UNDEFINED; + PhotoStatus _photo_status = PHOTO_CAPTURE_STATUS_UNDEFINED; + QStringList _activeSettings; + QStringList _settings; + QTimer _captureStatusTimer; + QList _valueExclusions; + QList _optionRanges; + QMap _originalOptNames; + QMap _originalOptValues; + QMap _paramIO; + int _storageInfoRetries = 0; + int _captureInfoRetries = 0; + bool _resetting = false; + QTimer _recTimer; + QTime _recTime; + uint32_t _recordTime = 0; + //-- Parameters that require a full update + QMap _requestUpdates; + QStringList _updatesToRequest; + //-- Video Streams + int _requestCount = 0; + int _currentStream = 0; + int _expectedCount = 1; + QTimer _streamInfoTimer; + QTimer _streamStatusTimer; + QmlObjectListModel _streams; + QStringList _streamLabels; + ThermalViewMode _thermalMode = THERMAL_BLEND; + double _thermalOpacity = 85.0; +}; diff --git a/src/Camera/QGCCameraIO.cc b/src/Camera/QGCCameraIO.cc new file mode 100644 index 0000000..13d3837 --- /dev/null +++ b/src/Camera/QGCCameraIO.cc @@ -0,0 +1,372 @@ + + +#include "QGCCameraControl.h" +#include "QGCCameraIO.h" + +QGC_LOGGING_CATEGORY(CameraIOLog, "CameraIOLog") +QGC_LOGGING_CATEGORY(CameraIOLogVerbose, "CameraIOLogVerbose") + +//----------------------------------------------------------------------------- +QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicle *vehicle) + : QObject(control) + , _control(control) + , _fact(fact) + , _vehicle(vehicle) + , _sentRetries(0) + , _requestRetries(0) + , _done(false) + , _updateOnSet(false) + , _forceUIUpdate(false) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + _paramWriteTimer.setSingleShot(true); + _paramWriteTimer.setInterval(3000); + _paramRequestTimer.setSingleShot(true); + _paramRequestTimer.setInterval(3500); + if(_fact->writeOnly()) { + //-- Write mode is always "done" as it won't ever read + _done = true; + } else { + connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout); + } + connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout); + connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged); + connect(_fact, &Fact::_containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged); + _pMavlink = qgcApp()->toolbox()->mavlinkProtocol(); + //-- TODO: Even though we don't use anything larger than 32-bit, this should + // probably be updated. + switch (_fact->type()) { + case FactMetaData::valueTypeUint8: + case FactMetaData::valueTypeBool: + _mavParamType = MAV_PARAM_EXT_TYPE_UINT8; + break; + case FactMetaData::valueTypeInt8: + _mavParamType = MAV_PARAM_EXT_TYPE_INT8; + break; + case FactMetaData::valueTypeUint16: + _mavParamType = MAV_PARAM_EXT_TYPE_UINT16; + break; + case FactMetaData::valueTypeInt16: + _mavParamType = MAV_PARAM_EXT_TYPE_INT16; + break; + case FactMetaData::valueTypeUint32: + _mavParamType = MAV_PARAM_EXT_TYPE_UINT32; + break; + case FactMetaData::valueTypeUint64: + _mavParamType = MAV_PARAM_EXT_TYPE_UINT64; + break; + case FactMetaData::valueTypeInt64: + _mavParamType = MAV_PARAM_EXT_TYPE_INT64; + break; + case FactMetaData::valueTypeFloat: + _mavParamType = MAV_PARAM_EXT_TYPE_REAL32; + break; + case FactMetaData::valueTypeDouble: + _mavParamType = MAV_PARAM_EXT_TYPE_REAL64; + break; + //-- String and custom are the same for now + case FactMetaData::valueTypeString: + case FactMetaData::valueTypeCustom: + _mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM; + break; + default: + qWarning() << "Unsupported fact type" << _fact->type() << "for" << _fact->name(); + case FactMetaData::valueTypeInt32: + _mavParamType = MAV_PARAM_EXT_TYPE_INT32; + break; + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::setParamRequest() +{ + if(!_fact->writeOnly()) { + _paramRequestReceived = false; + _requestRetries = 0; + _paramRequestTimer.start(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::_factChanged(QVariant value) +{ + if(!_forceUIUpdate) { + Q_UNUSED(value); + qCDebug(CameraIOLog) << "UI Fact" << _fact->name() << "changed to" << value; + _control->factChanged(_fact); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::_containerRawValueChanged(const QVariant value) +{ + if(!_fact->readOnly()) { + Q_UNUSED(value); + qCDebug(CameraIOLog) << "Update Fact from camera" << _fact->name(); + _sentRetries = 0; + _sendParameter(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::sendParameter(bool updateUI) +{ + qCDebug(CameraIOLog) << "Send Fact" << _fact->name(); + _sentRetries = 0; + _updateOnSet = updateUI; + _sendParameter(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::_sendParameter() +{ + WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink(); + if (!weakLink.expired()) { + SharedLinkInterfacePtr sharedLink = weakLink.lock(); + + mavlink_param_ext_set_t p; + memset(&p, 0, sizeof(mavlink_param_ext_set_t)); + param_ext_union_t union_value; + mavlink_message_t msg; + FactMetaData::ValueType_t factType = _fact->type(); + p.param_type = _mavParamType; + switch (factType) { + case FactMetaData::valueTypeUint8: + case FactMetaData::valueTypeBool: + union_value.param_uint8 = static_cast(_fact->rawValue().toUInt()); + break; + case FactMetaData::valueTypeInt8: + union_value.param_int8 = static_cast(_fact->rawValue().toInt()); + break; + case FactMetaData::valueTypeUint16: + union_value.param_uint16 = static_cast(_fact->rawValue().toUInt()); + break; + case FactMetaData::valueTypeInt16: + union_value.param_int16 = static_cast(_fact->rawValue().toInt()); + break; + case FactMetaData::valueTypeUint32: + union_value.param_uint32 = static_cast(_fact->rawValue().toUInt()); + break; + case FactMetaData::valueTypeInt64: + union_value.param_int64 = static_cast(_fact->rawValue().toLongLong()); + break; + case FactMetaData::valueTypeUint64: + union_value.param_uint64 = static_cast(_fact->rawValue().toULongLong()); + break; + case FactMetaData::valueTypeFloat: + union_value.param_float = _fact->rawValue().toFloat(); + break; + case FactMetaData::valueTypeDouble: + union_value.param_double = _fact->rawValue().toDouble(); + break; + //-- String and custom are the same for now + case FactMetaData::valueTypeString: + case FactMetaData::valueTypeCustom: + { + QByteArray custom = _fact->rawValue().toByteArray(); + memcpy(union_value.bytes, custom.data(), static_cast(std::max(custom.size(), static_cast(MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN)))); + } + break; + default: + qCritical() << "Unsupported fact type" << factType << "for" << _fact->name(); + case FactMetaData::valueTypeInt32: + union_value.param_int32 = static_cast(_fact->rawValue().toInt()); + break; + } + memcpy(&p.param_value[0], &union_value.bytes[0], MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN); + p.target_system = static_cast(_vehicle->id()); + p.target_component = static_cast(_control->compID()); + strncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN); + mavlink_msg_param_ext_set_encode_chan( + static_cast(_pMavlink->getSystemId()), + static_cast(_pMavlink->getComponentId()), + sharedLink->mavlinkChannel(), + &msg, + &p); + _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); + } + _paramWriteTimer.start(); +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::_paramWriteTimeout() +{ + if(++_sentRetries > 3) { + qCWarning(CameraIOLog) << "No response for param set:" << _fact->name(); + _updateOnSet = false; + } else { + //-- Send it again + qCDebug(CameraIOLog) << "Param set retry:" << _fact->name() << _sentRetries; + _sendParameter(); + _paramWriteTimer.start(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack) +{ + _paramWriteTimer.stop(); + if(ack.param_result == PARAM_ACK_ACCEPTED) { + QVariant val = _valueFromMessage(ack.param_value, ack.param_type); + if(_fact->rawValue() != val) { + _fact->_containerSetRawValue(val); + if(_updateOnSet) { + _updateOnSet = false; + _control->factChanged(_fact); + } + } + } else if(ack.param_result == PARAM_ACK_IN_PROGRESS) { + //-- Wait a bit longer for this one + qCDebug(CameraIOLogVerbose) << "Param set in progress:" << _fact->name(); + _paramWriteTimer.start(); + } else { + if(ack.param_result == PARAM_ACK_FAILED) { + if(++_sentRetries < 3) { + //-- Try again + qCWarning(CameraIOLog) << "Param set failed:" << _fact->name() << _sentRetries; + _paramWriteTimer.start(); + } + return; + } else if(ack.param_result == PARAM_ACK_VALUE_UNSUPPORTED) { + qCWarning(CameraIOLog) << "Param set unsuported:" << _fact->name(); + } + //-- If UI changed and value was not set, restore UI + QVariant val = _valueFromMessage(ack.param_value, ack.param_type); + if(_fact->rawValue() != val) { + if(_control->validateParameter(_fact, val)) { + _fact->_containerSetRawValue(val); + } + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value) +{ + _paramRequestTimer.stop(); + QVariant newValue = _valueFromMessage(value.param_value, value.param_type); + if(_control->incomingParameter(_fact, newValue)) { + _fact->_containerSetRawValue(newValue); + } + _paramRequestReceived = true; + if(_forceUIUpdate) { + emit _fact->rawValueChanged(_fact->rawValue()); + emit _fact->valueChanged(_fact->rawValue()); + _forceUIUpdate = false; + } + if(!_done) { + _done = true; + _control->_paramDone(); + } + qCDebug(CameraIOLog) << QString("handleParamValue() %1 %2").arg(_fact->name()).arg(_fact->rawValueString()); +} + +//----------------------------------------------------------------------------- +QVariant +QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type) +{ + QVariant var; + param_ext_union_t u; + memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN); + switch (param_type) { + case MAV_PARAM_EXT_TYPE_REAL32: + var = QVariant(u.param_float); + break; + case MAV_PARAM_EXT_TYPE_UINT8: + var = QVariant(u.param_uint8); + break; + case MAV_PARAM_EXT_TYPE_INT8: + var = QVariant(u.param_int8); + break; + case MAV_PARAM_EXT_TYPE_UINT16: + var = QVariant(u.param_uint16); + break; + case MAV_PARAM_EXT_TYPE_INT16: + var = QVariant(u.param_int16); + break; + case MAV_PARAM_EXT_TYPE_UINT32: + var = QVariant(u.param_uint32); + break; + case MAV_PARAM_EXT_TYPE_INT32: + var = QVariant(u.param_int32); + break; + case MAV_PARAM_EXT_TYPE_UINT64: + var = QVariant(static_cast(u.param_uint64)); + break; + case MAV_PARAM_EXT_TYPE_INT64: + var = QVariant(static_cast(u.param_int64)); + break; + case MAV_PARAM_EXT_TYPE_CUSTOM: + var = QVariant(QByteArray(value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN)); + break; + default: + var = QVariant(0); + qCritical() << "Invalid param_type used for camera setting:" << param_type; + } + return var; +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::_paramRequestTimeout() +{ + if(++_requestRetries > 3) { + qCWarning(CameraIOLog) << "No response for param request:" << _fact->name(); + if(!_done) { + _done = true; + _control->_paramDone(); + } + } else { + //-- Request it again + qCDebug(CameraIOLog) << "Param request retry:" << _fact->name(); + paramRequest(false); + _paramRequestTimer.start(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraParamIO::paramRequest(bool reset) +{ + //-- If it's write only, we don't request it. + if(_fact->writeOnly()) { + if(!_done) { + _done = true; + _control->_paramDone(); + } + return; + } + if(reset) { + _requestRetries = 0; + _forceUIUpdate = true; + } + qCDebug(CameraIOLog) << "Request parameter:" << _fact->name(); + WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink(); + if (!weakLink.expired()) { + SharedLinkInterfacePtr sharedLink = weakLink.lock(); + + char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1]; + memset(param_id, 0, sizeof(param_id)); + strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN); + mavlink_message_t msg; + mavlink_msg_param_ext_request_read_pack_chan( + static_cast(_pMavlink->getSystemId()), + static_cast(_pMavlink->getComponentId()), + sharedLink->mavlinkChannel(), + &msg, + static_cast(_vehicle->id()), + static_cast(_control->compID()), + param_id, + -1); + _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg); + } + _paramRequestTimer.start(); +} diff --git a/src/Camera/QGCCameraIO.h b/src/Camera/QGCCameraIO.h new file mode 100644 index 0000000..8db7d15 --- /dev/null +++ b/src/Camera/QGCCameraIO.h @@ -0,0 +1,72 @@ + +#pragma once + +#include "QGCApplication.h" +#include + +class QGCCameraControl; + +Q_DECLARE_LOGGING_CATEGORY(CameraIOLog) +Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose) + +MAVPACKED( +typedef struct { + union { + float param_float; + double param_double; + int64_t param_int64; + uint64_t param_uint64; + int32_t param_int32; + uint32_t param_uint32; + int16_t param_int16; + uint16_t param_uint16; + int8_t param_int8; + uint8_t param_uint8; + uint8_t bytes[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN]; + }; + uint8_t type; +}) param_ext_union_t; + +//----------------------------------------------------------------------------- +/// Camera parameter handler. +class QGCCameraParamIO : public QObject +{ +public: + QGCCameraParamIO(QGCCameraControl* control, Fact* fact, Vehicle* vehicle); + + void handleParamAck (const mavlink_param_ext_ack_t& ack); + void handleParamValue (const mavlink_param_ext_value_t& value); + void setParamRequest (); + bool paramDone () const { return _done; } + void paramRequest (bool reset = true); + void sendParameter (bool updateUI = false); + + QStringList optNames; + QVariantList optVariants; + +private slots: + void _paramWriteTimeout (); + void _paramRequestTimeout (); + void _factChanged (QVariant value); + void _containerRawValueChanged (const QVariant value); + +private: + void _sendParameter (); + QVariant _valueFromMessage (const char* value, uint8_t param_type); + +private: + QGCCameraControl* _control; + Fact* _fact; + Vehicle* _vehicle; + int _sentRetries; + int _requestRetries; + bool _paramRequestReceived; + QTimer _paramWriteTimer; + QTimer _paramRequestTimer; + bool _done; + bool _updateOnSet; + MAV_PARAM_EXT_TYPE _mavParamType; + MAVLinkProtocol* _pMavlink; + bool _forceUIUpdate; +}; + diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc new file mode 100644 index 0000000..ed53c21 --- /dev/null +++ b/src/Camera/QGCCameraManager.cc @@ -0,0 +1,518 @@ + + +#include "QGCApplication.h" +#include "QGCCameraManager.h" +#include "JoystickManager.h" + +QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog") + +//----------------------------------------------------------------------------- +QGCCameraManager::CameraStruct::CameraStruct(QObject* parent, uint8_t compID_) + : QObject(parent) + , compID(compID_) +{ +} + +//----------------------------------------------------------------------------- +QGCCameraManager::QGCCameraManager(Vehicle *vehicle) + : _vehicle(vehicle) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + qCDebug(CameraManagerLog) << "QGCCameraManager Created"; + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::parameterReadyVehicleAvailableChanged, this, &QGCCameraManager::_vehicleReady); + connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &QGCCameraManager::_mavlinkMessageReceived); + connect(&_cameraTimer, &QTimer::timeout, this, &QGCCameraManager::_cameraTimeout); + _cameraTimer.setSingleShot(false); + _lastZoomChange.start(); + _lastCameraChange.start(); + _cameraTimer.start(500); +} + +//----------------------------------------------------------------------------- +QGCCameraManager::~QGCCameraManager() +{ +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::setCurrentCamera(int sel) +{ + if(sel != _currentCamera && sel >= 0 && sel < _cameras.count()) { + _currentCamera = sel; + emit currentCameraChanged(); + emit streamChanged(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_vehicleReady(bool ready) +{ + qCDebug(CameraManagerLog) << "_vehicleReady(" << ready << ")"; + if(ready) { + if(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle() == _vehicle) { + _vehicleReadyState = true; + JoystickManager *pJoyMgr = qgcApp()->toolbox()->joystickManager(); + _activeJoystickChanged(pJoyMgr->activeJoystick()); + connect(pJoyMgr, &JoystickManager::activeJoystickChanged, this, &QGCCameraManager::_activeJoystickChanged); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_mavlinkMessageReceived(const mavlink_message_t& message) +{ + //-- Only pay attention to camera components, as identified by their compId + if(message.sysid == _vehicle->id() && (message.compid >= MAV_COMP_ID_CAMERA && message.compid <= MAV_COMP_ID_CAMERA6)) { + switch (message.msgid) { + case MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS: + _handleCaptureStatus(message); + break; + case MAVLINK_MSG_ID_STORAGE_INFORMATION: + _handleStorageInfo(message); + break; + case MAVLINK_MSG_ID_HEARTBEAT: + _handleHeartbeat(message); + break; + case MAVLINK_MSG_ID_CAMERA_INFORMATION: + _handleCameraInfo(message); + break; + case MAVLINK_MSG_ID_CAMERA_SETTINGS: + _handleCameraSettings(message); + break; + case MAVLINK_MSG_ID_PARAM_EXT_ACK: + _handleParamAck(message); + break; + case MAVLINK_MSG_ID_PARAM_EXT_VALUE: + _handleParamValue(message); + break; + case MAVLINK_MSG_ID_VIDEO_STREAM_INFORMATION: + _handleVideoStreamInfo(message); + break; + case MAVLINK_MSG_ID_VIDEO_STREAM_STATUS: + _handleVideoStreamStatus(message); + break; + case MAVLINK_MSG_ID_BATTERY_STATUS: + _handleBatteryStatus(message); + break; + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message) +{ + //-- First time hearing from this one? + QString sCompID = QString::number(message.compid); + if(!_cameraInfoRequest.contains(sCompID)) { + qCDebug(CameraManagerLog) << "Hearbeat from " << message.compid; + CameraStruct* pInfo = new CameraStruct(this, message.compid); + pInfo->lastHeartbeat.start(); + _cameraInfoRequest[sCompID] = pInfo; + //-- Request camera info + _requestCameraInfo(message.compid); + } else { + if(_cameraInfoRequest[sCompID]) { + CameraStruct* pInfo = _cameraInfoRequest[sCompID]; + //-- Check if we have indeed received the camera info + if(pInfo->infoReceived) { + //-- We have it. Just update the heartbeat timeout + pInfo->lastHeartbeat.start(); + } else { + //-- Try again. Maybe. + if(pInfo->lastHeartbeat.elapsed() > 2000) { + if(pInfo->tryCount > 10) { + if(!pInfo->gaveUp) { + pInfo->gaveUp = true; + qWarning() << "Giving up requesting camera info from" << _vehicle->id() << message.compid; + } + } else { + pInfo->tryCount++; + //-- Request camera info again. + _requestCameraInfo(message.compid); + } + } + } + } else { + qWarning() << "_cameraInfoRequest[" << sCompID << "] is null"; + } + } +} + +//----------------------------------------------------------------------------- +QGCCameraControl* +QGCCameraManager::currentCameraInstance() +{ + if(_currentCamera < _cameras.count() && _cameras.count()) { + QGCCameraControl* pCamera = qobject_cast(_cameras[_currentCamera]); + return pCamera; + } + return nullptr; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo* +QGCCameraManager::currentStreamInstance() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + QGCVideoStreamInfo* pInfo = pCamera->currentStreamInstance(); + return pInfo; + } + return nullptr; +} + +//----------------------------------------------------------------------------- +QGCVideoStreamInfo* +QGCCameraManager::thermalStreamInstance() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + QGCVideoStreamInfo* pInfo = pCamera->thermalStreamInstance(); + return pInfo; + } + return nullptr; +} + +//----------------------------------------------------------------------------- +QGCCameraControl* +QGCCameraManager::_findCamera(int id) +{ + for(int i = 0; i < _cameras.count(); i++) { + if(_cameras[i]) { + QGCCameraControl* pCamera = qobject_cast(_cameras[i]); + if(pCamera) { + if(pCamera->compID() == id) { + return pCamera; + } + } else { + qCritical() << "Null QGCCameraControl instance"; + } + } + } + //qWarning() << "Camera component id not found:" << id; + return nullptr; +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message) +{ + //-- Have we requested it? + QString sCompID = QString::number(message.compid); + if(_cameraInfoRequest.contains(sCompID) && !_cameraInfoRequest[sCompID]->infoReceived) { + //-- Flag it as done + _cameraInfoRequest[sCompID]->infoReceived = true; + mavlink_camera_information_t info; + mavlink_msg_camera_information_decode(&message, &info); + qCDebug(CameraManagerLog) << "_handleCameraInfo:" << reinterpret_cast(info.model_name) << reinterpret_cast(info.vendor_name) << "Comp ID:" << message.compid; + QGCCameraControl* pCamera = _vehicle->firmwarePlugin()->createCameraControl(&info, _vehicle, message.compid, this); + if(pCamera) { + QQmlEngine::setObjectOwnership(pCamera, QQmlEngine::CppOwnership); + _cameras.append(pCamera); + _cameraLabels << pCamera->modelName(); + emit camerasChanged(); + emit cameraLabelsChanged(); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_cameraTimeout() +{ + //-- Iterate cameras + foreach(QString sCompID, _cameraInfoRequest.keys()) { + if(_cameraInfoRequest[sCompID]) { + CameraStruct* pInfo = _cameraInfoRequest[sCompID]; + //-- Have we received a camera info message? + if(pInfo->infoReceived) { + //-- Has the camera stopped talking to us? + if(pInfo->lastHeartbeat.elapsed() > 5000) { + //-- Camera is gone. Remove it. + bool autoStream = false; + QGCCameraControl* pCamera = _findCamera(pInfo->compID); + if(pCamera) { + qWarning() << "Camera" << pCamera->modelName() << "stopped transmitting. Removing from list."; + int idx = _cameraLabels.indexOf(pCamera->modelName()); + if(idx >= 0) { + _cameraLabels.removeAt(idx); + } + idx = _cameras.indexOf(pCamera); + if(idx >= 0) { + _cameras.removeAt(idx); + } + autoStream = pCamera->autoStream(); + pCamera->deleteLater(); + delete pInfo; + } + _cameraInfoRequest.remove(sCompID); + emit cameraLabelsChanged(); + //-- If we have another camera, switch current camera. + if(_cameras.count()) { + setCurrentCamera(0); + } else { + //-- We're out of cameras + emit camerasChanged(); + if(autoStream) { + emit streamChanged(); + } + } + //-- Exit loop. + return; + } + } + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleCaptureStatus(const mavlink_message_t &message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_camera_capture_status_t cap; + mavlink_msg_camera_capture_status_decode(&message, &cap); + pCamera->handleCaptureStatus(cap); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleStorageInfo(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_storage_information_t st; + mavlink_msg_storage_information_decode(&message, &st); + pCamera->handleStorageInfo(st); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleCameraSettings(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_camera_settings_t settings; + mavlink_msg_camera_settings_decode(&message, &settings); + pCamera->handleSettings(settings); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleParamAck(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_param_ext_ack_t ack; + mavlink_msg_param_ext_ack_decode(&message, &ack); + pCamera->handleParamAck(ack); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleParamValue(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_param_ext_value_t value; + mavlink_msg_param_ext_value_decode(&message, &value); + pCamera->handleParamValue(value); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleVideoStreamInfo(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_video_stream_information_t streamInfo; + mavlink_msg_video_stream_information_decode(&message, &streamInfo); + pCamera->handleVideoInfo(&streamInfo); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleVideoStreamStatus(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_video_stream_status_t streamStatus; + mavlink_msg_video_stream_status_decode(&message, &streamStatus); + pCamera->handleVideoStatus(&streamStatus); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_handleBatteryStatus(const mavlink_message_t& message) +{ + QGCCameraControl* pCamera = _findCamera(message.compid); + if(pCamera) { + mavlink_battery_status_t batteryStatus; + mavlink_msg_battery_status_decode(&message, &batteryStatus); + pCamera->handleBatteryStatus(batteryStatus); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_requestCameraInfo(int compID) +{ + qCDebug(CameraManagerLog) << "_requestCameraInfo(" << compID << ")"; + if(_vehicle) { + _vehicle->sendMavCommand( + compID, // target component + MAV_CMD_REQUEST_CAMERA_INFORMATION, // command id + false, // showError + 1); // Do Request + } +} + +//---------------------------------------------------------------------------------------- +void +QGCCameraManager::_activeJoystickChanged(Joystick* joystick) +{ + qCDebug(CameraManagerLog) << "Joystick changed"; + if(_activeJoystick) { + disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom); + disconnect(_activeJoystick, &Joystick::startContinuousZoom, this, &QGCCameraManager::_startZoom); + disconnect(_activeJoystick, &Joystick::stopContinuousZoom, this, &QGCCameraManager::_stopZoom); + disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera); + disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream); + disconnect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera); + disconnect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording); + disconnect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording); + disconnect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording); + } + _activeJoystick = joystick; + if(_activeJoystick) { + connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom); + connect(_activeJoystick, &Joystick::startContinuousZoom, this, &QGCCameraManager::_startZoom); + connect(_activeJoystick, &Joystick::stopContinuousZoom, this, &QGCCameraManager::_stopZoom); + connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera); + connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream); + connect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera); + connect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording); + connect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording); + connect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_triggerCamera() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->takePhoto(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_startVideoRecording() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->startVideo(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stopVideoRecording() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->stopVideo(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_toggleVideoRecording() +{ + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->toggleVideo(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stepZoom(int direction) +{ + if(_lastZoomChange.elapsed() > 40) { + _lastZoomChange.start(); + qCDebug(CameraManagerLog) << "Step Camera Zoom" << direction; + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->stepZoom(direction); + } + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_startZoom(int direction) +{ + qCDebug(CameraManagerLog) << "Start Camera Zoom" << direction; + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->startZoom(direction); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stopZoom() +{ + qCDebug(CameraManagerLog) << "Stop Camera Zoom"; + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + pCamera->stopZoom(); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stepCamera(int direction) +{ + if(_lastCameraChange.elapsed() > 1000) { + _lastCameraChange.start(); + qCDebug(CameraManagerLog) << "Step Camera" << direction; + int c = _currentCamera + direction; + if(c < 0) c = _cameras.count() - 1; + if(c >= _cameras.count()) c = 0; + setCurrentCamera(c); + } +} + +//----------------------------------------------------------------------------- +void +QGCCameraManager::_stepStream(int direction) +{ + if(_lastCameraChange.elapsed() > 1000) { + _lastCameraChange.start(); + QGCCameraControl* pCamera = currentCameraInstance(); + if(pCamera) { + qCDebug(CameraManagerLog) << "Step Camera Stream" << direction; + int c = pCamera->currentStream() + direction; + if(c < 0) c = pCamera->streams()->count() - 1; + if(c >= pCamera->streams()->count()) c = 0; + pCamera->setCurrentStream(c); + } + } +} + + diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h new file mode 100644 index 0000000..5e51501 --- /dev/null +++ b/src/Camera/QGCCameraManager.h @@ -0,0 +1,112 @@ +/*! + * @file + * @brief Camera Controller + * @author Gus Grubba + * + */ + +/// @file +/// @brief MAVLink Camera API. Camera Manager. +/// @author Gus Grubba + +#pragma once + +#include "QGCApplication.h" +#include +#include "QmlObjectListModel.h" +#include "QGCCameraControl.h" + +#include +#include + +Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog) + +class Joystick; + +//----------------------------------------------------------------------------- +/// Camera Manager +class QGCCameraManager : public QObject +{ + Q_OBJECT +public: + QGCCameraManager(Vehicle* vehicle); + virtual ~QGCCameraManager(); + + Q_PROPERTY(QmlObjectListModel* cameras READ cameras NOTIFY camerasChanged) + Q_PROPERTY(QStringList cameraLabels READ cameraLabels NOTIFY cameraLabelsChanged) + Q_PROPERTY(QGCCameraControl* currentCameraInstance READ currentCameraInstance NOTIFY currentCameraChanged) + Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged) + + //-- Return a list of cameras provided by this vehicle + virtual QmlObjectListModel* cameras () { return &_cameras; } + //-- Camera names to show the user (for selection) + virtual QStringList cameraLabels () { return _cameraLabels; } + //-- Current selected camera + virtual int currentCamera () { return _currentCamera; } + virtual QGCCameraControl* currentCameraInstance(); + //-- Set current camera + virtual void setCurrentCamera (int sel); + //-- Current stream + virtual QGCVideoStreamInfo* currentStreamInstance(); + //-- Current thermal stream + virtual QGCVideoStreamInfo* thermalStreamInstance(); + +signals: + void camerasChanged (); + void cameraLabelsChanged (); + void currentCameraChanged (); + void streamChanged (); + +protected slots: + virtual void _vehicleReady (bool ready); + virtual void _mavlinkMessageReceived (const mavlink_message_t& message); + virtual void _activeJoystickChanged (Joystick* joystick); + virtual void _stepZoom (int direction); + virtual void _startZoom (int direction); + virtual void _stopZoom (); + virtual void _stepCamera (int direction); + virtual void _stepStream (int direction); + virtual void _cameraTimeout (); + virtual void _triggerCamera (); + virtual void _startVideoRecording (); + virtual void _stopVideoRecording (); + virtual void _toggleVideoRecording (); + +protected: + virtual QGCCameraControl* _findCamera (int id); + virtual void _requestCameraInfo (int compID); + virtual void _handleHeartbeat (const mavlink_message_t& message); + virtual void _handleCameraInfo (const mavlink_message_t& message); + virtual void _handleStorageInfo (const mavlink_message_t& message); + virtual void _handleCameraSettings (const mavlink_message_t& message); + virtual void _handleParamAck (const mavlink_message_t& message); + virtual void _handleParamValue (const mavlink_message_t& message); + virtual void _handleCaptureStatus (const mavlink_message_t& message); + virtual void _handleVideoStreamInfo (const mavlink_message_t& message); + virtual void _handleVideoStreamStatus(const mavlink_message_t& message); + virtual void _handleBatteryStatus (const mavlink_message_t& message); + +protected: + + class CameraStruct : public QObject { + public: + CameraStruct(QObject* parent, uint8_t compID_); + QElapsedTimer lastHeartbeat; + bool infoReceived = false; + bool gaveUp = false; + int tryCount = 0; + uint8_t compID = 0; + }; + + Vehicle* _vehicle = nullptr; + Joystick* _activeJoystick = nullptr; + bool _vehicleReadyState = false; + int _currentTask = 0; + QmlObjectListModel _cameras; + QStringList _cameraLabels; + int _currentCamera = 0; + QElapsedTimer _lastZoomChange; + QElapsedTimer _lastCameraChange; + QTimer _cameraTimer; + QMap _cameraInfoRequest; +}; diff --git a/README.md b/src/README.md similarity index 100% rename from README.md rename to src/README.md diff --git a/src/api/QGCCorePlugin.cc b/src/api/QGCCorePlugin.cc new file mode 100644 index 0000000..318c7a9 --- /dev/null +++ b/src/api/QGCCorePlugin.cc @@ -0,0 +1,502 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "QGCApplication.h" +#include "QGCCorePlugin.h" +#include "QGCOptions.h" +#include "QmlComponentInfo.h" +#include "FactMetaData.h" +#include "SettingsManager.h" +#include "AppMessages.h" +#include "QmlObjectListModel.h" +#include "VideoManager.h" +#if defined(QGC_GST_STREAMING) +#include "GStreamer.h" +#include "VideoReceiver.h" +#endif +#include "QGCLoggingCategory.h" +#include "QGCCameraManager.h" +#include "HorizontalFactValueGrid.h" +#include "InstrumentValueData.h" + +#include +#include + +/// @file +/// @brief Core Plugin Interface for QGroundControl - Default Implementation +/// @author Gus Grubba + +class QGCCorePlugin_p +{ +public: + QGCCorePlugin_p() + { + } + + ~QGCCorePlugin_p() + { + if(pGeneral) + delete pGeneral; + if(pCommLinks) + delete pCommLinks; + if(pOfflineMaps) + delete pOfflineMaps; +#if defined(QGC_GST_TAISYNC_ENABLED) + if(pTaisync) + delete pTaisync; +#endif +#if defined(QGC_GST_MICROHARD_ENABLED) + if(pMicrohard) + delete pMicrohard; +#endif + if(pMAVLink) + delete pMAVLink; + if(pConsole) + delete pConsole; +#if defined(QT_DEBUG) + if(pMockLink) + delete pMockLink; + if(pDebug) + delete pDebug; + if(pQmlTest) + delete pQmlTest; +#endif + if(pRemoteID) + delete pRemoteID; + if(defaultOptions) + delete defaultOptions; + } + + QmlComponentInfo* pGeneral = nullptr; + QmlComponentInfo* pCommLinks = nullptr; + QmlComponentInfo* pOfflineMaps = nullptr; +#if defined(QGC_GST_TAISYNC_ENABLED) + QmlComponentInfo* pTaisync = nullptr; +#endif +#if defined(QGC_GST_MICROHARD_ENABLED) + QmlComponentInfo* pMicrohard = nullptr; +#endif + QmlComponentInfo* pMAVLink = nullptr; + QmlComponentInfo* pConsole = nullptr; + QmlComponentInfo* pHelp = nullptr; +#if defined(QT_DEBUG) + QmlComponentInfo* pMockLink = nullptr; + QmlComponentInfo* pDebug = nullptr; + QmlComponentInfo* pQmlTest = nullptr; +#endif + QmlComponentInfo* pRemoteID = nullptr; + + QGCOptions* defaultOptions = nullptr; + QVariantList settingsList; + QVariantList analyzeList; + + QmlObjectListModel _emptyCustomMapItems; +}; + +QGCCorePlugin::~QGCCorePlugin() +{ + if(_p) { + delete _p; + } +} + +QGCCorePlugin::QGCCorePlugin(QGCApplication *app, QGCToolbox* toolbox) + : QGCTool(app, toolbox) + , _showTouchAreas(false) + , _showAdvancedUI(true) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); + _p = new QGCCorePlugin_p; +} + +void QGCCorePlugin::setToolbox(QGCToolbox *toolbox) +{ + QGCTool::setToolbox(toolbox); + + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "QGCCorePlugin", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "QGCOptions", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl", 1, 0, "QGCFlyViewOptions", "Reference only"); +} + +QVariantList &QGCCorePlugin::settingsPages() +{ + if(!_p->pGeneral) { + _p->pGeneral = new QmlComponentInfo(tr("General"), + QUrl::fromUserInput("qrc:/qml/GeneralSettings.qml"), + QUrl::fromUserInput("qrc:/res/gear-white.svg")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pGeneral))); + _p->pCommLinks = new QmlComponentInfo(tr("Comm Links"), + QUrl::fromUserInput("qrc:/qml/LinkSettings.qml"), + QUrl::fromUserInput("qrc:/res/waves.svg")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pCommLinks))); + _p->pOfflineMaps = new QmlComponentInfo(tr("Offline Maps"), + QUrl::fromUserInput("qrc:/qml/OfflineMap.qml"), + QUrl::fromUserInput("qrc:/res/waves.svg")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pOfflineMaps))); +#if defined(QGC_GST_TAISYNC_ENABLED) + _p->pTaisync = new QmlComponentInfo(tr("Taisync"), + QUrl::fromUserInput("qrc:/qml/TaisyncSettings.qml"), + QUrl::fromUserInput("")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pTaisync))); +#endif +#if defined(QGC_GST_MICROHARD_ENABLED) + _p->pMicrohard = new QmlComponentInfo(tr("Microhard"), + QUrl::fromUserInput("qrc:/qml/MicrohardSettings.qml"), + QUrl::fromUserInput("")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pMicrohard))); +#endif + _p->pMAVLink = new QmlComponentInfo(tr("MAVLink"), + QUrl::fromUserInput("qrc:/qml/MavlinkSettings.qml"), + QUrl::fromUserInput("qrc:/res/waves.svg")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pMAVLink))); + _p->pRemoteID = new QmlComponentInfo(tr("Remote ID"), + QUrl::fromUserInput("qrc:/qml/RemoteIDSettings.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pRemoteID))); + _p->pConsole = new QmlComponentInfo(tr("Console"), + QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/AppMessages.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pConsole))); + _p->pHelp = new QmlComponentInfo(tr("Help"), + QUrl::fromUserInput("qrc:/qml/HelpSettings.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pHelp))); +#if defined(QT_DEBUG) + //-- These are always present on Debug builds + _p->pMockLink = new QmlComponentInfo(tr("Mock Link"), + QUrl::fromUserInput("qrc:/qml/MockLink.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pMockLink))); + _p->pDebug = new QmlComponentInfo(tr("Debug"), + QUrl::fromUserInput("qrc:/qml/DebugWindow.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pDebug))); + _p->pQmlTest = new QmlComponentInfo(tr("Palette Test"), + QUrl::fromUserInput("qrc:/qml/QmlTest.qml")); + _p->settingsList.append(QVariant::fromValue(reinterpret_cast(_p->pQmlTest))); +#endif + } + return _p->settingsList; +} + +QVariantList& QGCCorePlugin::analyzePages() +{ + if (!_p->analyzeList.count()) { + _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("Log Download"), QUrl::fromUserInput("qrc:/qml/LogDownloadPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/LogDownloadIcon")))); +#if !defined(__mobile__) + _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("GeoTag Images"), QUrl::fromUserInput("qrc:/qml/GeoTagPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/GeoTagIcon")))); +#endif + _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Console"), QUrl::fromUserInput("qrc:/qml/MavlinkConsolePage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MavlinkConsoleIcon")))); +#if !defined(QGC_DISABLE_MAVLINK_INSPECTOR) + _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("MAVLink Inspector"),QUrl::fromUserInput("qrc:/qml/MAVLinkInspectorPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/MAVLinkInspector")))); +#endif + _p->analyzeList.append(QVariant::fromValue(new QmlComponentInfo(tr("Vibration"), QUrl::fromUserInput("qrc:/qml/VibrationPage.qml"), QUrl::fromUserInput("qrc:/qmlimages/VibrationPageIcon")))); + } + return _p->analyzeList; +} + +int QGCCorePlugin::defaultSettings() +{ + return 0; +} + +QGCOptions* QGCCorePlugin::options() +{ + if (!_p->defaultOptions) { + _p->defaultOptions = new QGCOptions(this); + } + return _p->defaultOptions; +} + +bool QGCCorePlugin::overrideSettingsGroupVisibility(QString name) +{ + Q_UNUSED(name); + + // Always show all + return true; +} + +bool QGCCorePlugin::adjustSettingMetaData(const QString& settingsGroup, FactMetaData& metaData) +{ + if (settingsGroup == AppSettings::settingsGroup) { +#if !defined(QGC_ENABLE_PAIRING) + //-- If we don't support pairing, disable it. + if (metaData.name() == AppSettings::usePairingName) { + metaData.setRawDefaultValue(false); + //-- And hide the option + return false; + } +#endif + + //-- Default Palette + if (metaData.name() == AppSettings::indoorPaletteName) { + QVariant outdoorPalette; +#if defined (__mobile__) + outdoorPalette = 0; +#else + outdoorPalette = 1; +#endif + metaData.setRawDefaultValue(outdoorPalette); + return true; + } + +#if defined (__mobile__) + if (metaData.name() == AppSettings::telemetrySaveName) { + // Mobile devices have limited storage so don't turn on telemtry saving by default + metaData.setRawDefaultValue(false); + return true; + } +#endif + +#ifndef __android__ + if (metaData.name() == AppSettings::androidSaveToSDCardName) { + // This only shows on android builds + return false; + } +#endif + } + + return true; // Show setting in ui +} + +void QGCCorePlugin::setShowTouchAreas(bool show) +{ + if (show != _showTouchAreas) { + _showTouchAreas = show; + emit showTouchAreasChanged(show); + } +} + +void QGCCorePlugin::setShowAdvancedUI(bool show) +{ + if (show != _showAdvancedUI) { + _showAdvancedUI = show; + emit showAdvancedUIChanged(show); + } +} + +void QGCCorePlugin::paletteOverride(QString /*colorName*/, QGCPalette::PaletteColorInfo_t& /*colorInfo*/) +{ + +} + +QString QGCCorePlugin::showAdvancedUIMessage() const +{ + return tr("WARNING: You are about to enter Advanced Mode. " + "If used incorrectly, this may cause your vehicle to malfunction thus voiding your warranty. " + "You should do so only if instructed by customer support. " + "Are you sure you want to enable Advanced Mode?"); +} + +void QGCCorePlugin::factValueGridCreateDefaultSettings(const QString& defaultSettingsGroup) +{ + HorizontalFactValueGrid factValueGrid(defaultSettingsGroup); + + bool includeFWValues = factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassFixedWing || factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassVTOL || factValueGrid.vehicleClass() == QGCMAVLink::VehicleClassAirship; + + factValueGrid.setFontSize(FactValueGrid::LargeFontSize); + + factValueGrid.appendColumn(); + factValueGrid.appendColumn(); + factValueGrid.appendColumn(); + if (includeFWValues) { + factValueGrid.appendColumn(); + } + factValueGrid.appendRow(); + + int rowIndex = 0; + QmlObjectListModel* column = factValueGrid.columns()->value(0); + + InstrumentValueData* value = column->value(rowIndex++); + value->setFact("Vehicle", "AltitudeRelative"); + value->setIcon("arrow-thick-up.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(true); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "DistanceToHome"); + value->setIcon("bookmark copy 3.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(true); + + rowIndex = 0; + column = factValueGrid.columns()->value(1); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "ClimbRate"); + value->setIcon("arrow-simple-up.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(true); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "GroundSpeed"); + value->setIcon("arrow-simple-right.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(true); + + + if (includeFWValues) { + rowIndex = 0; + column = factValueGrid.columns()->value(2); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "AirSpeed"); + value->setText("AirSpd"); + value->setShowUnits(true); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "ThrottlePct"); + value->setText("Thr"); + value->setShowUnits(true); + } + + rowIndex = 0; + column = factValueGrid.columns()->value(includeFWValues ? 3 : 2); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "FlightTime"); + value->setIcon("timer.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(false); + + value = column->value(rowIndex++); + value->setFact("Vehicle", "FlightDistance"); + value->setIcon("travel-walk.svg"); + value->setText(value->fact()->shortDescription()); + value->setShowUnits(true); +} + +QQmlApplicationEngine* QGCCorePlugin::createQmlApplicationEngine(QObject* parent) +{ + QQmlApplicationEngine* qmlEngine = new QQmlApplicationEngine(parent); + qmlEngine->addImportPath("qrc:/qml"); + qmlEngine->rootContext()->setContextProperty("joystickManager", qgcApp()->toolbox()->joystickManager()); + qmlEngine->rootContext()->setContextProperty("debugMessageModel", AppMessages::getModel()); + return qmlEngine; +} + +void QGCCorePlugin::createRootWindow(QQmlApplicationEngine* qmlEngine) +{ + qmlEngine->load(QUrl(QStringLiteral("qrc:/qml/MainRootWindow.qml"))); +} + +bool QGCCorePlugin::mavlinkMessage(Vehicle* vehicle, LinkInterface* link, mavlink_message_t message) +{ + Q_UNUSED(vehicle); + Q_UNUSED(link); + Q_UNUSED(message); + + return true; +} + +QmlObjectListModel* QGCCorePlugin::customMapItems() +{ + return &_p->_emptyCustomMapItems; +} + +VideoManager* QGCCorePlugin::createVideoManager(QGCApplication *app, QGCToolbox *toolbox) +{ + return new VideoManager(app, toolbox); +} + +VideoReceiver* QGCCorePlugin::createVideoReceiver(QObject* parent) +{ +#if defined(QGC_GST_STREAMING) + return GStreamer::createVideoReceiver(parent); +#else + Q_UNUSED(parent) + return nullptr; +#endif +} + +void* QGCCorePlugin::createVideoSink(QObject* parent, QQuickItem* widget) +{ +#if defined(QGC_GST_STREAMING) + return GStreamer::createVideoSink(parent, widget); +#else + Q_UNUSED(parent) + Q_UNUSED(widget) + return nullptr; +#endif +} + +void QGCCorePlugin::releaseVideoSink(void* sink) +{ +#if defined(QGC_GST_STREAMING) + GStreamer::releaseVideoSink(sink); +#else + Q_UNUSED(sink) +#endif +} + +bool QGCCorePlugin::guidedActionsControllerLogging() const +{ + return GuidedActionsControllerLog().isDebugEnabled(); +} + +QString QGCCorePlugin::stableVersionCheckFileUrl() const +{ +#ifdef QGC_CUSTOM_BUILD + // Custom builds must override to turn on and provide their own location + return QString(); +#else + return QString("https://s3-us-west-2.amazonaws.com/qgroundcontrol/latest/QGC.version.txt"); +#endif +} + +const QVariantList& QGCCorePlugin::toolBarIndicators(void) +{ + //-- Default list of indicators for all vehicles. + if(_toolBarIndicatorList.size() == 0) { + _toolBarIndicatorList = QVariantList({ + QVariant::fromValue(QUrl::fromUserInput("qrc:/toolbar/GPSRTKIndicator.qml")), + }); + } + return _toolBarIndicatorList; +} + +QList QGCCorePlugin::firstRunPromptStdIds(void) +{ + QList rgStdIds = { unitsFirstRunPromptId, offlineVehicleFirstRunPromptId }; + return rgStdIds; +} + +QList QGCCorePlugin::firstRunPromptCustomIds(void) +{ + return QList(); +} + +QVariantList QGCCorePlugin::firstRunPromptsToShow(void) +{ + QList rgIdsToShow; + + rgIdsToShow.append(firstRunPromptStdIds()); + rgIdsToShow.append(firstRunPromptCustomIds()); + + QList rgAlreadyShownIds = AppSettings::firstRunPromptsIdsVariantToList(_toolbox->settingsManager()->appSettings()->firstRunPromptIdsShown()->rawValue()); + + for (int idToRemove: rgAlreadyShownIds) { + rgIdsToShow.removeOne(idToRemove); + } + + QVariantList rgVarIdsToShow; + for (int id: rgIdsToShow) { + rgVarIdsToShow.append(id); + } + + return rgVarIdsToShow; +} + +QString QGCCorePlugin::firstRunPromptResource(int id) +{ + switch (id) { + case unitsFirstRunPromptId: + return "/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml"; + case offlineVehicleFirstRunPromptId: + return "/FirstRunPromptDialogs/OfflineVehicleFirstRunPrompt.qml"; + break; + } + + return QString(); +} diff --git a/src/api/QGCCorePlugin.h b/src/api/QGCCorePlugin.h new file mode 100644 index 0000000..791724f --- /dev/null +++ b/src/api/QGCCorePlugin.h @@ -0,0 +1,222 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "QGCToolbox.h" +#include "QGCPalette.h" +#include "QGCMAVLink.h" +#include "QmlObjectListModel.h" + +#include +#include + +/// @file +/// @brief Core Plugin Interface for QGroundControl +/// @author Gus Grubba + +class QGCApplication; +class QGCOptions; +class QGCSettings; +class QGCCorePlugin_p; +class FactMetaData; +class QGeoPositionInfoSource; +class QQmlApplicationEngine; +class Vehicle; +class LinkInterface; +class QmlObjectListModel; +class VideoReceiver; +class VideoSink; +class PlanMasterController; +class QGCCameraManager; +class QGCCameraControl; +class QQuickItem; +class InstrumentValueAreaController; + +#ifndef OPAQUE_PTR_QGCCorePlugin + #define OPAQUE_PTR_QGCCorePlugin + Q_DECLARE_OPAQUE_POINTER(QGCOptions*) +#endif + +class QGCCorePlugin : public QGCTool +{ + Q_OBJECT +public: + QGCCorePlugin(QGCApplication* app, QGCToolbox* toolbox); + ~QGCCorePlugin(); + + Q_PROPERTY(QVariantList settingsPages READ settingsPages NOTIFY settingsPagesChanged) + Q_PROPERTY(QVariantList analyzePages READ analyzePages NOTIFY analyzePagesChanged) + Q_PROPERTY(int defaultSettings READ defaultSettings CONSTANT) + Q_PROPERTY(QGCOptions* options READ options CONSTANT) + Q_PROPERTY(bool showTouchAreas READ showTouchAreas WRITE setShowTouchAreas NOTIFY showTouchAreasChanged) + Q_PROPERTY(bool showAdvancedUI READ showAdvancedUI WRITE setShowAdvancedUI NOTIFY showAdvancedUIChanged) + Q_PROPERTY(QString showAdvancedUIMessage READ showAdvancedUIMessage CONSTANT) + Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor CONSTANT) + Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor CONSTANT) + Q_PROPERTY(QmlObjectListModel* customMapItems READ customMapItems CONSTANT) + Q_PROPERTY(QVariantList toolBarIndicators READ toolBarIndicators NOTIFY toolBarIndicatorsChanged) + Q_PROPERTY(int unitsFirstRunPromptId MEMBER unitsFirstRunPromptId CONSTANT) + Q_PROPERTY(int offlineVehicleFirstRunPromptId MEMBER offlineVehicleFirstRunPromptId CONSTANT) + + Q_INVOKABLE bool guidedActionsControllerLogging() const; + + /// The list of settings under the Settings Menu + /// @return A list of QGCSettings + virtual QVariantList& settingsPages(); + + /// The list of pages/buttons under the Analyze Menu + /// @return A list of QmlPageInfo + virtual QVariantList& analyzePages(); + + /// The default settings panel to show + /// @return The settings index + virtual int defaultSettings(); + + /// Global options + /// @return An instance of QGCOptions + virtual QGCOptions* options(); + + /// Allows the core plugin to override the visibility for a settings group + /// @param name - SettingsGroup name + /// @return true: Show settings ui, false: Hide settings ui + virtual bool overrideSettingsGroupVisibility(QString name); + + /// Allows the core plugin to override the setting meta data before the setting fact is created. + /// @param settingsGroup - QSettings group which contains this item + /// @param metaData - MetaData for setting fact + /// @return true: Setting should be visible in ui, false: Setting should not be shown in ui + virtual bool adjustSettingMetaData(const QString& settingsGroup, FactMetaData& metaData); + + /// Return the resource file which contains the brand image for for Indoor theme. + virtual QString brandImageIndoor() const { return QString(); } + + /// Return the resource file which contains the brand image for for Outdoor theme. + virtual QString brandImageOutdoor() const { return QString(); } + + /// @return The message to show to the user when they a re prompted to confirm turning on advanced ui. + virtual QString showAdvancedUIMessage() const; + + /// @return An instance of an alternate position source (or NULL if not available) + virtual QGeoPositionInfoSource* createPositionSource(QObject* /*parent*/) { return nullptr; } + + /// Allows a plugin to override the specified color name from the palette + virtual void paletteOverride(QString colorName, QGCPalette::PaletteColorInfo_t& colorInfo); + + virtual void factValueGridCreateDefaultSettings(const QString& defaultSettingsGroup); + + /// Allows the plugin to override or get access to the QmlApplicationEngine to do things like add import + /// path or stuff things into the context prior to window creation. + virtual QQmlApplicationEngine* createQmlApplicationEngine(QObject* parent); + + /// Allows the plugin to override the creation of the root (native) window. + virtual void createRootWindow(QQmlApplicationEngine* qmlEngine); + + /// Allows the plugin to override the creation of VideoManager. + virtual VideoManager* createVideoManager(QGCApplication* app, QGCToolbox* toolbox); + /// Allows the plugin to override the creation of VideoReceiver. + virtual VideoReceiver* createVideoReceiver(QObject* parent); + /// Allows the plugin to override the creation of VideoSink. + virtual void* createVideoSink(QObject* parent, QQuickItem* widget); + /// Allows the plugin to override the release of VideoSink. + virtual void releaseVideoSink(void* sink); + + /// Allows the plugin to see all mavlink traffic to a vehicle + /// @return true: Allow vehicle to continue processing, false: Vehicle should not process message + virtual bool mavlinkMessage(Vehicle* vehicle, LinkInterface* link, mavlink_message_t message); + + /// Allows custom builds to add custom items to the FlightMap. Objects put into QmlObjectListModel should derive from QmlComponentInfo and set the url property. + virtual QmlObjectListModel* customMapItems(); + + /// Allows custom builds to add custom items to the plan file before the document is created. + virtual void preSaveToJson (PlanMasterController* /*pController*/, QJsonObject& /*json*/) {} + /// Allows custom builds to add custom items to the plan file after the document is created. + virtual void postSaveToJson (PlanMasterController* /*pController*/, QJsonObject& /*json*/) {} + + /// Allows custom builds to add custom items to the mission section of the plan file before the item is created. + virtual void preSaveToMissionJson (PlanMasterController* /*pController*/, QJsonObject& /*missionJson*/) {} + /// Allows custom builds to add custom items to the mission section of the plan file after the item is created. + virtual void postSaveToMissionJson (PlanMasterController* /*pController*/, QJsonObject& /*missionJson*/) {} + + /// Allows custom builds to load custom items from the plan file before the document is parsed. + virtual void preLoadFromJson (PlanMasterController* /*pController*/, QJsonObject& /*json*/) {} + /// Allows custom builds to load custom items from the plan file after the document is parsed. + virtual void postLoadFromJson (PlanMasterController* /*pController*/, QJsonObject& /*json*/) {} + + /// Returns the url to download the stable version check file. Return QString() to indicate no version check should be performed. + /// Default QGC mainline implemenentation returns QGC Stable file location. Default QGC custom build code returns QString(). + /// Custom builds can override to turn on and provide their own location. + /// The contents of this file should be a single line in the form: + /// v3.4.4 + /// This indicates the latest stable version number. + virtual QString stableVersionCheckFileUrl() const; + + /// Returns the user visible url to show user where to download new stable builds from. + /// Custom builds must override to provide their own location. + virtual QString stableDownloadLocation() const { return QString("qgroundcontrol.com"); } + + /// Returns the complex mission items to display in the Plan UI + /// @param complexMissionItemNames Default set of complex items + /// @return Complex items to be made available to user + virtual QStringList complexMissionItemNames(Vehicle* /*vehicle*/, const QStringList& complexMissionItemNames) { return complexMissionItemNames; } + + /// Returns the standard list of first run prompt ids for possible display. Actual display is based on the + /// current AppSettings::firstRunPromptIds value. The order of this list also determines the order the prompts + /// will be displayed in. + virtual QList firstRunPromptStdIds(void); + + /// Returns the custom build list of first run prompt ids for possible display. Actual display is based on the + /// current AppSettings::firstRunPromptIds value. The order of this list also determines the order the prompts + /// will be displayed in. + virtual QList firstRunPromptCustomIds(void); + + /// Returns the resource which contains the specified first run prompt for display + Q_INVOKABLE virtual QString firstRunPromptResource(int id); + + /// Returns the list of toolbar indicators which are not related to a vehicle + /// signals toolbarIndicatorsChanged + /// @return A list of QUrl with the indicators + virtual const QVariantList& toolBarIndicators(void); + + /// Returns the list of first run prompt ids which need to be displayed according to current settings + Q_INVOKABLE QVariantList firstRunPromptsToShow(void); + + bool showTouchAreas() const { return _showTouchAreas; } + bool showAdvancedUI() const { return _showAdvancedUI; } + void setShowTouchAreas(bool show); + void setShowAdvancedUI(bool show); + + // Override from QGCTool + void setToolbox (QGCToolbox* toolbox); + + // Standard first run prompt ids + static const int unitsFirstRunPromptId = 1; + static const int offlineVehicleFirstRunPromptId = 2; + + // Custom builds can start there first run prompt ids from here + static const int firstRunPromptIdsFirstCustomId = 10000; + +signals: + void settingsPagesChanged (); + void analyzePagesChanged (); + void showTouchAreasChanged (bool showTouchAreas); + void showAdvancedUIChanged (bool showAdvancedUI); + void toolBarIndicatorsChanged (); + +protected: + bool _showTouchAreas; + bool _showAdvancedUI; + Vehicle* _activeVehicle = nullptr; + QGCCameraManager* _cameraManager = nullptr; + QGCCameraControl* _currentCamera = nullptr; + QVariantList _toolBarIndicatorList; + +private: + QGCCorePlugin_p* _p; +}; diff --git a/src/api/QGCOptions.cc b/src/api/QGCOptions.cc new file mode 100644 index 0000000..2e2c05c --- /dev/null +++ b/src/api/QGCOptions.cc @@ -0,0 +1,47 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "QGCOptions.h" + +#include + +/// @file +/// @brief Core Plugin Interface for QGroundControl - Application Options +/// @author Gus Grubba + +QGCOptions::QGCOptions(QObject* parent) + : QObject(parent) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); +} + +QColor QGCOptions::toolbarBackgroundLight() const +{ + return QColor(255,255,255); +} + +QColor QGCOptions::toolbarBackgroundDark() const +{ + return QColor(0,0,0); +} + +QGCFlyViewOptions* QGCOptions::flyViewOptions(void) +{ + if (!_defaultFlyViewOptions) { + _defaultFlyViewOptions = new QGCFlyViewOptions(this); + } + return _defaultFlyViewOptions; +} + +QGCFlyViewOptions::QGCFlyViewOptions(QGCOptions* options, QObject* parent) + : QObject (parent) + , _options (options) +{ + QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership); +} diff --git a/src/api/QGCOptions.h b/src/api/QGCOptions.h new file mode 100644 index 0000000..7b5926d --- /dev/null +++ b/src/api/QGCOptions.h @@ -0,0 +1,170 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include + +class QGCOptions; + +class QGCFlyViewOptions : public QObject +{ + Q_OBJECT +public: + QGCFlyViewOptions(QGCOptions* options, QObject* parent = nullptr); + + Q_PROPERTY(bool showMultiVehicleList READ showMultiVehicleList CONSTANT) + Q_PROPERTY(bool showInstrumentPanel READ showInstrumentPanel CONSTANT) + Q_PROPERTY(bool showMapScale READ showMapScale CONSTANT) + Q_PROPERTY(bool guidedBarShowEmergencyStop READ guidedBarShowEmergencyStop NOTIFY guidedBarShowEmergencyStopChanged) + Q_PROPERTY(bool guidedBarShowOrbit READ guidedBarShowOrbit NOTIFY guidedBarShowOrbitChanged) + Q_PROPERTY(bool guidedBarShowROI READ guidedBarShowROI NOTIFY guidedBarShowROIChanged) + +protected: + virtual bool showMultiVehicleList () const { return true; } + virtual bool showMapScale () const { return true; } + virtual bool showInstrumentPanel () const { return true; } + virtual bool guidedBarShowEmergencyStop () const { return true; } + virtual bool guidedBarShowOrbit () const { return true; } + virtual bool guidedBarShowROI () const { return true; } + + QGCOptions* _options; + +signals: + void guidedBarShowEmergencyStopChanged (bool show); + void guidedBarShowOrbitChanged (bool show); + void guidedBarShowROIChanged (bool show); +}; + +class QGCOptions : public QObject +{ + Q_OBJECT +public: + QGCOptions(QObject* parent = nullptr); + + Q_PROPERTY(bool combineSettingsAndSetup READ combineSettingsAndSetup CONSTANT) + Q_PROPERTY(double toolbarHeightMultiplier READ toolbarHeightMultiplier CONSTANT) + Q_PROPERTY(bool enablePlanViewSelector READ enablePlanViewSelector CONSTANT) + Q_PROPERTY(QUrl preFlightChecklistUrl READ preFlightChecklistUrl CONSTANT) + Q_PROPERTY(bool showSensorCalibrationCompass READ showSensorCalibrationCompass NOTIFY showSensorCalibrationCompassChanged) + Q_PROPERTY(bool showSensorCalibrationGyro READ showSensorCalibrationGyro NOTIFY showSensorCalibrationGyroChanged) + Q_PROPERTY(bool showSensorCalibrationAccel READ showSensorCalibrationAccel NOTIFY showSensorCalibrationAccelChanged) + Q_PROPERTY(bool showSensorCalibrationLevel READ showSensorCalibrationLevel NOTIFY showSensorCalibrationLevelChanged) + Q_PROPERTY(bool showSensorCalibrationAirspeed READ showSensorCalibrationAirspeed NOTIFY showSensorCalibrationAirspeedChanged) + Q_PROPERTY(bool sensorsHaveFixedOrientation READ sensorsHaveFixedOrientation CONSTANT) + Q_PROPERTY(bool wifiReliableForCalibration READ wifiReliableForCalibration CONSTANT) + Q_PROPERTY(bool showFirmwareUpgrade READ showFirmwareUpgrade NOTIFY showFirmwareUpgradeChanged) + Q_PROPERTY(QString firmwareUpgradeSingleURL READ firmwareUpgradeSingleURL CONSTANT) + Q_PROPERTY(bool missionWaypointsOnly READ missionWaypointsOnly NOTIFY missionWaypointsOnlyChanged) + Q_PROPERTY(bool multiVehicleEnabled READ multiVehicleEnabled NOTIFY multiVehicleEnabledChanged) + Q_PROPERTY(bool showOfflineMapExport READ showOfflineMapExport NOTIFY showOfflineMapExportChanged) + Q_PROPERTY(bool showOfflineMapImport READ showOfflineMapImport NOTIFY showOfflineMapImportChanged) + Q_PROPERTY(bool useMobileFileDialog READ useMobileFileDialog CONSTANT) + Q_PROPERTY(bool showMissionStatus READ showMissionStatus CONSTANT) + Q_PROPERTY(bool guidedActionsRequireRCRSSI READ guidedActionsRequireRCRSSI CONSTANT) + Q_PROPERTY(bool showMissionAbsoluteAltitude READ showMissionAbsoluteAltitude NOTIFY showMissionAbsoluteAltitudeChanged) + Q_PROPERTY(bool showSimpleMissionStart READ showSimpleMissionStart NOTIFY showSimpleMissionStartChanged) + Q_PROPERTY(bool disableVehicleConnection READ disableVehicleConnection CONSTANT) + Q_PROPERTY(float devicePixelRatio READ devicePixelRatio NOTIFY devicePixelRatioChanged) + Q_PROPERTY(float devicePixelDensity READ devicePixelDensity NOTIFY devicePixelDensityChanged) + Q_PROPERTY(bool checkFirmwareVersion READ checkFirmwareVersion CONSTANT) + Q_PROPERTY(bool showMavlinkLogOptions READ showMavlinkLogOptions CONSTANT) + Q_PROPERTY(bool enableSaveMainWindowPosition READ enableSaveMainWindowPosition CONSTANT) + Q_PROPERTY(QStringList surveyBuiltInPresetNames READ surveyBuiltInPresetNames CONSTANT) + Q_PROPERTY(bool allowJoystickSelection READ allowJoystickSelection NOTIFY allowJoystickSelectionChanged) + + Q_PROPERTY(QGCFlyViewOptions* flyView READ flyViewOptions CONSTANT) + + /// Should QGC hide its settings menu and colapse it into one single menu (Settings and Vehicle Setup)? + /// @return true if QGC should consolidate both menus into one. + virtual bool combineSettingsAndSetup () { return false; } + + /// Main ToolBar Multiplier. + /// @return Factor to use when computing toolbar height + virtual double toolbarHeightMultiplier () { return 1.0; } + + /// Enable Plan View Selector (Mission, Fence or Rally) + /// @return True or false + virtual bool enablePlanViewSelector () { return true; } + + /// Should the mission status indicator (Plan View) be shown? + /// @return Yes or no + virtual bool showMissionStatus () { return true; } + + /// Provides an optional, custom preflight checklist + virtual QUrl preFlightChecklistUrl () const { return QUrl::fromUserInput("qrc:/qml/PreFlightCheckList.qml"); } + + /// Allows replacing the toolbar Light Theme color + virtual QColor toolbarBackgroundLight () const; + /// Allows replacing the toolbar Dark Theme color + virtual QColor toolbarBackgroundDark () const; + /// By returning false you can hide the following sensor calibration pages + virtual bool showSensorCalibrationCompass () const { return true; } + virtual bool showSensorCalibrationGyro () const { return true; } + virtual bool showSensorCalibrationAccel () const { return true; } + virtual bool showSensorCalibrationLevel () const { return true; } + virtual bool showSensorCalibrationAirspeed () const { return true; } + virtual bool wifiReliableForCalibration () const { return false; } + virtual bool sensorsHaveFixedOrientation () const { return false; } + virtual bool showFirmwareUpgrade () const { return true; } + virtual bool missionWaypointsOnly () const { return false; } ///< true: Only allow waypoints and complex items in Plan + virtual bool multiVehicleEnabled () const { return true; } ///< false: multi vehicle support is disabled + virtual bool guidedActionsRequireRCRSSI () const { return false; } ///< true: Guided actions will be disabled is there is no RC RSSI + virtual bool showOfflineMapExport () const { return true; } + virtual bool showOfflineMapImport () const { return true; } + virtual bool showMissionAbsoluteAltitude () const { return true; } + virtual bool showSimpleMissionStart () const { return false; } + virtual bool disableVehicleConnection () const { return false; } ///< true: vehicle connection is disabled + virtual bool checkFirmwareVersion () const { return true; } + virtual bool showMavlinkLogOptions () const { return true; } + virtual bool allowJoystickSelection () const { return true; } ///< false: custom build has automatically enabled a specific joystick + /// Desktop builds save the main application size and position on close (and restore it on open) + virtual bool enableSaveMainWindowPosition () const { return true; } + virtual QStringList surveyBuiltInPresetNames () const { return QStringList(); } // Built in presets cannot be deleted + +#if defined(__mobile__) + virtual bool useMobileFileDialog () const { return true;} +#else + virtual bool useMobileFileDialog () const { return false;} +#endif + + /// If returned QString in non-empty it means that firmware upgrade will run in a mode which only + /// supports downloading a single firmware file from the URL. It also supports custom install through + /// the Advanced options. + virtual QString firmwareUpgradeSingleURL () const { return QString(); } + + /// Device specific pixel ratio/density (for when Qt doesn't properly read it from the hardware) + virtual float devicePixelRatio () const { return 0.0f; } + virtual float devicePixelDensity () const { return 0.0f; } + + virtual QGCFlyViewOptions* flyViewOptions (); + +signals: + void showSensorCalibrationCompassChanged (bool show); + void showSensorCalibrationGyroChanged (bool show); + void showSensorCalibrationAccelChanged (bool show); + void showSensorCalibrationLevelChanged (bool show); + void showSensorCalibrationAirspeedChanged (bool show); + void showFirmwareUpgradeChanged (bool show); + void missionWaypointsOnlyChanged (bool missionWaypointsOnly); + void multiVehicleEnabledChanged (bool multiVehicleEnabled); + void allowJoystickSelectionChanged (bool allow); + void showOfflineMapExportChanged (); + void showOfflineMapImportChanged (); + void showMissionAbsoluteAltitudeChanged (); + void showSimpleMissionStartChanged (); + void devicePixelRatioChanged (); + void devicePixelDensityChanged (); + +protected: + QGCFlyViewOptions* _defaultFlyViewOptions = nullptr; +}; diff --git a/src/api/QGCSettings.cc b/src/api/QGCSettings.cc new file mode 100644 index 0000000..c296d64 --- /dev/null +++ b/src/api/QGCSettings.cc @@ -0,0 +1,21 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "QGCSettings.h" + +/// @file +/// @brief Core Plugin Interface for QGroundControl. Settings element. +/// @author Gus Grubba + +QGCSettings::QGCSettings(QString title, QUrl url, QUrl icon) + : _title(title) + , _url(url) + , _icon(icon) +{ +} diff --git a/src/api/QGCSettings.h b/src/api/QGCSettings.h new file mode 100644 index 0000000..593a178 --- /dev/null +++ b/src/api/QGCSettings.h @@ -0,0 +1,37 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +/// @file +/// @brief Core Plugin Interface for QGroundControl. Settings element. +/// @author Gus Grubba + +class QGCSettings : public QObject +{ + Q_OBJECT +public: + QGCSettings(QString title, QUrl url, QUrl icon = QUrl()); + + Q_PROPERTY(QString title READ title CONSTANT) + Q_PROPERTY(QUrl url READ url CONSTANT) + Q_PROPERTY(QUrl icon READ icon CONSTANT) + + virtual QString title () { return _title; } + virtual QUrl url () { return _url; } + virtual QUrl icon () { return _icon; } + +protected: + QString _title; + QUrl _url; + QUrl _icon; +}; diff --git a/src/api/QmlComponentInfo.cc b/src/api/QmlComponentInfo.cc new file mode 100644 index 0000000..35bb33c --- /dev/null +++ b/src/api/QmlComponentInfo.cc @@ -0,0 +1,19 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "QmlComponentInfo.h" + +QmlComponentInfo::QmlComponentInfo(QString title, QUrl url, QUrl icon, QObject* parent) + : QObject (parent) + , _title (title) + , _url (url) + , _icon (icon) +{ + +} diff --git a/src/api/QmlComponentInfo.h b/src/api/QmlComponentInfo.h new file mode 100644 index 0000000..30c0459 --- /dev/null +++ b/src/api/QmlComponentInfo.h @@ -0,0 +1,35 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +/// Represents a Qml component which can be loaded from a resource. +class QmlComponentInfo : public QObject +{ + Q_OBJECT + +public: + QmlComponentInfo(QString title, QUrl url, QUrl icon = QUrl(), QObject* parent = nullptr); + + Q_PROPERTY(QString title READ title CONSTANT) ///< Title for page + Q_PROPERTY(QUrl url READ url CONSTANT) ///< Qml source code + Q_PROPERTY(QUrl icon READ icon CONSTANT) ///< Icon for page + + virtual QString title () { return _title; } + virtual QUrl url () { return _url; } + virtual QUrl icon () { return _icon; } + +protected: + QString _title; + QUrl _url; + QUrl _icon; +};