diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 61516930996..5b67480504f 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -420,6 +420,7 @@
src/MissionManager/VTOLLandingPattern.FactMetaData.json
src/Settings/Viewer3D.SettingsGroup.json
src/Settings/GimbalController.SettingsGroup.json
+ src/Camera/CameraMetaData.json
src/Comms/MockLink/APMArduSubMockLink.params
diff --git a/src/Camera/CMakeLists.txt b/src/Camera/CMakeLists.txt
index a5c9c92969a..cffb09263b6 100644
--- a/src/Camera/CMakeLists.txt
+++ b/src/Camera/CMakeLists.txt
@@ -1,6 +1,8 @@
find_package(Qt6 REQUIRED COMPONENTS Core Network Qml Xml)
qt_add_library(Camera STATIC
+ CameraMetaData.cc
+ CameraMetaData.h
MavlinkCameraControl.cc
MavlinkCameraControl.h
QGCCameraIO.cc
@@ -24,6 +26,7 @@ target_link_libraries(Camera
FirmwarePlugin
Joystick
Settings
+ Utilities
Vehicle
VideoManager
PUBLIC
@@ -36,3 +39,8 @@ target_link_libraries(Camera
target_include_directories(Camera PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
+# qt_add_resources(Camera "Camera_res"
+# PREFIX "/"
+# FILES
+# CameraMetaData.json
+# )
diff --git a/src/Camera/CameraMetaData.cc b/src/Camera/CameraMetaData.cc
new file mode 100644
index 00000000000..4ad4b233f4a
--- /dev/null
+++ b/src/Camera/CameraMetaData.cc
@@ -0,0 +1,41 @@
+/****************************************************************************
+ *
+ * (c) 2009-2024 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include "CameraMetaData.h"
+#include "QGCLoggingCategory.h"
+
+QGC_LOGGING_CATEGORY(CameraMetaDataLog, "qgc.camera.camerametadata")
+
+CameraMetaData::CameraMetaData(const QString &canonicalName,
+ const QString &brand,
+ const QString &model,
+ double sensorWidth,
+ double sensorHeight,
+ double imageWidth,
+ double imageHeight,
+ double focalLength,
+ bool landscape,
+ bool fixedOrientation,
+ double minTriggerInterval,
+ const QString &deprecatedTranslatedName)
+ : canonicalName(canonicalName)
+ , brand(brand)
+ , model(model)
+ , sensorWidth(sensorWidth)
+ , sensorHeight(sensorHeight)
+ , imageWidth(imageWidth)
+ , imageHeight(imageHeight)
+ , focalLength(focalLength)
+ , landscape(landscape)
+ , fixedOrientation(fixedOrientation)
+ , minTriggerInterval(minTriggerInterval)
+ , deprecatedTranslatedName(deprecatedTranslatedName)
+{
+ // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this;
+}
diff --git a/src/FirmwarePlugin/CameraMetaData.h b/src/Camera/CameraMetaData.h
similarity index 54%
rename from src/FirmwarePlugin/CameraMetaData.h
rename to src/Camera/CameraMetaData.h
index ced383001fb..8a5650b6340 100644
--- a/src/FirmwarePlugin/CameraMetaData.h
+++ b/src/Camera/CameraMetaData.h
@@ -9,28 +9,14 @@
#pragma once
-#include
+#include
+
+Q_DECLARE_LOGGING_CATEGORY(CameraMetaDataLog)
/// Set of meta data which describes a camera available on the vehicle
-class CameraMetaData : public QObject
+class CameraMetaData
{
- Q_OBJECT
-
-public:
- CameraMetaData(const QString& canonicalName,
- const QString& brand,
- const QString& model,
- double sensorWidth,
- double sensorHeight,
- double imageWidth,
- double imageHeight,
- double focalLength,
- bool landscape,
- bool fixedOrientation,
- double minTriggerInterval,
- const QString& deprecatedTranslatedName,
- QObject* parent = nullptr);
-
+ Q_GADGET
Q_PROPERTY(QString canonicalName MEMBER canonicalName CONSTANT)
Q_PROPERTY(QString deprecatedTranslatedName MEMBER deprecatedTranslatedName CONSTANT)
Q_PROPERTY(QString brand MEMBER brand CONSTANT)
@@ -44,21 +30,36 @@ class CameraMetaData : public QObject
Q_PROPERTY(bool fixedOrientation MEMBER fixedOrientation CONSTANT)
Q_PROPERTY(double minTriggerInterval MEMBER minTriggerInterval CONSTANT)
- QString canonicalName; ///< Canonical name saved in plan files. Not translated.
- QString brand; ///< Camera brand. Used for grouping.
- QString model; ///< Camerar model
- double sensorWidth; ///< Sensor size in millimeters
- double sensorHeight; ///< Sensor size in millimeters
- double imageWidth; ///< Image size in pixels
- double imageHeight; ///< Image size in pixels
- double focalLength; ///< Focal length in millimeters
- bool landscape; ///< true: camera is in landscape orientation
- bool fixedOrientation; ///< true: camera is in fixed orientation
- double minTriggerInterval; ///< Minimum time in seconds between each photo taken, 0 for not specified
+public:
+ CameraMetaData(const QString &canonicalName,
+ const QString &brand,
+ const QString &model,
+ double sensorWidth,
+ double sensorHeight,
+ double imageWidth,
+ double imageHeight,
+ double focalLength,
+ bool landscape,
+ bool fixedOrientation,
+ double minTriggerInterval,
+ const QString &deprecatedTranslatedName);
+
+ const QString canonicalName; ///< Canonical name saved in plan files. Not translated.
+ const QString brand; ///< Camera brand. Used for grouping.
+ const QString model; ///< Camerar model
+ const double sensorWidth; ///< Sensor size in millimeters
+ const double sensorHeight; ///< Sensor size in millimeters
+ const double imageWidth; ///< Image size in pixels
+ const double imageHeight; ///< Image size in pixels
+ const double focalLength; ///< Focal length in millimeters
+ const bool landscape; ///< true: camera is in landscape orientation
+ const bool fixedOrientation; ///< true: camera is in fixed orientation
+ const double minTriggerInterval; ///< Minimum time in seconds between each photo taken, 0 for not specified
/// In older builds camera names were incorrect marked for translation. This leads to plan files which have are language
/// dependant which is not a good thing. Newer plan files use the canonical name which is not translated. In order to support
/// loading older plan files we continue to include the incorrect translation so we can match against them as needed.
/// Newly added CameraMetaData entries should leave this value empty.
- QString deprecatedTranslatedName;
+ const QString deprecatedTranslatedName;
};
+Q_DECLARE_METATYPE(CameraMetaData)
diff --git a/src/Camera/CameraMetaData.json b/src/Camera/CameraMetaData.json
new file mode 100644
index 00000000000..48231dac59f
--- /dev/null
+++ b/src/Camera/CameraMetaData.json
@@ -0,0 +1,498 @@
+{
+ "comment": "Camera MetaData",
+ "version": 1,
+ "fileType": "CameraMetaData",
+
+ "cameraMetaData": [
+ {
+ "canonicalName": "Canon S100 PowerShot",
+ "brand": "Canon",
+ "model": "S100 PowerShot",
+ "sensorWidth": 7.6,
+ "sensorHeight": 5.7,
+ "imageWidth": 4000,
+ "imageHeight": 3000,
+ "focalLength": 5.2,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Canon S100 PowerShot"
+ },
+ {
+ "canonicalName": "Canon EOS-M 22mm",
+ "brand": "Canon",
+ "model": "EOS-M 22mm",
+ "sensorWidth": 22.3,
+ "sensorHeight": 14.9,
+ "imageWidth": 5184,
+ "imageHeight": 3456,
+ "focalLength": 22,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Canon EOS-M 22mm"
+ },
+ {
+ "canonicalName": "Canon G9 X PowerShot",
+ "brand": "Canon",
+ "model": "G9 X PowerShot",
+ "sensorWidth": 13.2,
+ "sensorHeight": 8.8,
+ "imageWidth": 5488,
+ "imageHeight": 3680,
+ "focalLength": 10.2,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Canon G9 X PowerShot"
+ },
+ {
+ "canonicalName": "Canon SX260 HS PowerShot",
+ "brand": "Canon",
+ "model": "SX260 HS PowerShot",
+ "sensorWidth": 6.17,
+ "sensorHeight": 4.55,
+ "imageWidth": 4000,
+ "imageHeight": 3000,
+ "focalLength": 4.5,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Canon SX260 HS PowerShot"
+ },
+ {
+ "canonicalName": "GoPro Hero 4",
+ "brand": "GoPro",
+ "model": "Hero 4",
+ "sensorWidth": 6.17,
+ "sensorHeight": 4.55,
+ "imageWidth": 4000,
+ "imageHeight": 3000,
+ "focalLength": 2.98,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "GoPro Hero 4"
+ },
+ {
+ "canonicalName": "Parrot Sequioa RGB",
+ "brand": "Parrot",
+ "model": "Sequioa RGB",
+ "sensorWidth": 6.17,
+ "sensorHeight": 4.63,
+ "imageWidth": 4608,
+ "imageHeight": 3456,
+ "focalLength": 4.9,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1,
+ "deprecatedTranslatedName": "Parrot Sequioa RGB"
+ },
+ {
+ "canonicalName": "Parrot Sequioa Monochrome",
+ "brand": "Parrot",
+ "model": "Sequioa Monochrome",
+ "sensorWidth": 4.8,
+ "sensorHeight": 3.6,
+ "imageWidth": 1280,
+ "imageHeight": 960,
+ "focalLength": 4.0,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0.8,
+ "deprecatedTranslatedName": "Parrot Sequioa Monochrome"
+ },
+ {
+ "canonicalName": "RedEdge",
+ "brand": "RedEdge",
+ "model": "RedEdge",
+ "sensorWidth": 4.8,
+ "sensorHeight": 3.6,
+ "imageWidth": 1280,
+ "imageHeight": 960,
+ "focalLength": 5.5,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "RedEdge"
+ },
+ {
+ "canonicalName": "Ricoh GR II",
+ "brand": "Ricoh",
+ "model": "GR II",
+ "sensorWidth": 23.7,
+ "sensorHeight": 15.7,
+ "imageWidth": 4928,
+ "imageHeight": 3264,
+ "focalLength": 18.3,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Ricoh GR II"
+ },
+ {
+ "canonicalName": "Sentera Double 4K Sensor",
+ "brand": "Sentera",
+ "model": "Double 4K Sensor",
+ "sensorWidth": 6.2,
+ "sensorHeight": 4.65,
+ "imageWidth": 4000,
+ "imageHeight": 3000,
+ "focalLength": 5.4,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0.8,
+ "deprecatedTranslatedName": "Sentera Double 4K Sensor"
+ },
+ {
+ "canonicalName": "Sentera NDVI Single Sensor",
+ "brand": "Sentera",
+ "model": "NDVI Single Sensor",
+ "sensorWidth": 4.68,
+ "sensorHeight": 3.56,
+ "imageWidth": 1248,
+ "imageHeight": 952,
+ "focalLength": 4.14,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0.5,
+ "deprecatedTranslatedName": "Sentera NDVI Single Sensor"
+ },
+ {
+ "canonicalName": "Sentera 6X Sensor",
+ "brand": "Sentera",
+ "model": "6X Sensor",
+ "sensorWidth": 6.57,
+ "sensorHeight": 4.93,
+ "imageWidth": 1904,
+ "imageHeight": 1428,
+ "focalLength": 8.0,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0.2,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sentera 65R Sensor",
+ "brand": "Sentera",
+ "model": "65R Sensor",
+ "sensorWidth": 29.9,
+ "sensorHeight": 22.4,
+ "imageWidth": 9344,
+ "imageHeight": 7000,
+ "focalLength": 27.4,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0.3,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sony a6000 16mm",
+ "brand": "Sony",
+ "model": "a6000 16mm",
+ "sensorWidth": 23.5,
+ "sensorHeight": 15.6,
+ "imageWidth": 6000,
+ "imageHeight": 4000,
+ "focalLength": 16,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": "Sony a6000 16mm"
+ },
+ {
+ "canonicalName": "Sony a6000 35mm",
+ "brand": "Sony",
+ "model": "a6000 35mm",
+ "sensorWidth": 23.5,
+ "sensorHeight": 15.6,
+ "imageWidth": 6000,
+ "imageHeight": 4000,
+ "focalLength": 35,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sony a6300 Zeiss 21mm f/2.8",
+ "brand": "Sony",
+ "model": "a6300 Zeiss 21mm f/2.8",
+ "sensorWidth": 23.5,
+ "sensorHeight": 15.6,
+ "imageWidth": 6000,
+ "imageHeight": 4000,
+ "focalLength": 21,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": "Sony a6300 Zeiss 21mm f/2.8"
+ },
+ {
+ "canonicalName": "Sony a6300 Sony 28mm f/2.0",
+ "brand": "Sony",
+ "model": "a6300 Sony 28mm f/2.0",
+ "sensorWidth": 23.5,
+ "sensorHeight": 15.6,
+ "imageWidth": 6000,
+ "imageHeight": 4000,
+ "focalLength": 28,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": "Sony a6300 Sony 28mm f/2.0"
+ },
+ {
+ "canonicalName": "Sony a7R II Zeiss 21mm f/2.8",
+ "brand": "Sony",
+ "model": "a7R II Zeiss 21mm f/2.8",
+ "sensorWidth": 35.814,
+ "sensorHeight": 23.876,
+ "imageWidth": 7952,
+ "imageHeight": 5304,
+ "focalLength": 21,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": "Sony a7R II Zeiss 21mm f/2.8"
+ },
+ {
+ "canonicalName": "Sony a7R II Sony 28mm f/2.0",
+ "brand": "Sony",
+ "model": "a7R II Sony 28mm f/2.0",
+ "sensorWidth": 35.814,
+ "sensorHeight": 23.876,
+ "imageWidth": 7952,
+ "imageHeight": 5304,
+ "focalLength": 28,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": "Sony a7R II Sony 28mm f/2.0"
+ },
+ {
+ "canonicalName": "Sony a7r III 35mm",
+ "brand": "Sony",
+ "model": "a7r III 35mm",
+ "sensorWidth": 35.9,
+ "sensorHeight": 24.0,
+ "imageWidth": 7952,
+ "imageHeight": 5304,
+ "focalLength": 35,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sony a7r IV 35mm",
+ "brand": "Sony",
+ "model": "a7r IV 35mm",
+ "sensorWidth": 35.7,
+ "sensorHeight": 23.8,
+ "imageWidth": 9504,
+ "imageHeight": 6336,
+ "focalLength": 35,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sony DSC-QX30U @ 4.3mm f/3.5",
+ "brand": "Sony",
+ "model": "DSC-QX30U @ 4.3mm f/3.5",
+ "sensorWidth": 7.82,
+ "sensorHeight": 5.865,
+ "imageWidth": 5184,
+ "imageHeight": 3888,
+ "focalLength": 4.3,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 2.0,
+ "deprecatedTranslatedName": "Sony DSC-QX30U @ 4.3mm f/3.5"
+ },
+ {
+ "canonicalName": "Sony DSC-RX0",
+ "brand": "Sony",
+ "model": "DSC-RX0",
+ "sensorWidth": 13.2,
+ "sensorHeight": 8.8,
+ "imageWidth": 4800,
+ "imageHeight": 3200,
+ "focalLength": 7.7,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Sony DSC-RX0"
+ },
+ {
+ "canonicalName": "Sony DSC-RX1R II 35mm",
+ "brand": "Sony",
+ "model": "DSC-RX1R II 35mm",
+ "sensorWidth": 35.9,
+ "sensorHeight": 24.0,
+ "imageWidth": 7952,
+ "imageHeight": 5304,
+ "focalLength": 35,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Sony ILCE-QX1",
+ "brand": "Sony",
+ "model": "ILCE-QX1",
+ "sensorWidth": 23.2,
+ "sensorHeight": 15.4,
+ "imageWidth": 5456,
+ "imageHeight": 3632,
+ "focalLength": 16,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Sony ILCE-QX1"
+ },
+ {
+ "canonicalName": "Sony NEX-5R 20mm",
+ "brand": "Sony",
+ "model": "NEX-5R 20mm",
+ "sensorWidth": 23.2,
+ "sensorHeight": 15.4,
+ "imageWidth": 4912,
+ "imageHeight": 3264,
+ "focalLength": 20,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1,
+ "deprecatedTranslatedName": "Sony NEX-5R 20mm"
+ },
+ {
+ "canonicalName": "Sony RX100 II 28mm",
+ "brand": "Sony",
+ "model": "RX100 II 28mm",
+ "sensorWidth": 13.2,
+ "sensorHeight": 8.8,
+ "imageWidth": 5472,
+ "imageHeight": 3648,
+ "focalLength": 10.4,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Sony RX100 II 28mm"
+ },
+ {
+ "canonicalName": "Yuneec CGOET",
+ "brand": "Yuneec",
+ "model": "CGOET",
+ "sensorWidth": 5.6405,
+ "sensorHeight": 3.1813,
+ "imageWidth": 1920,
+ "imageHeight": 1080,
+ "focalLength": 3.5,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.3,
+ "deprecatedTranslatedName": "Yuneec CGOET"
+ },
+ {
+ "canonicalName": "Yuneec E10T",
+ "brand": "Yuneec",
+ "model": "E10T",
+ "sensorWidth": 5.6405,
+ "sensorHeight": 3.1813,
+ "imageWidth": 1920,
+ "imageHeight": 1080,
+ "focalLength": 23,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.3,
+ "deprecatedTranslatedName": "Yuneec E10T"
+ },
+ {
+ "canonicalName": "Yuneec E50",
+ "brand": "Yuneec",
+ "model": "E50",
+ "sensorWidth": 6.2372,
+ "sensorHeight": 4.7058,
+ "imageWidth": 4000,
+ "imageHeight": 3000,
+ "focalLength": 7.2,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.3,
+ "deprecatedTranslatedName": "Yuneec E50"
+ },
+ {
+ "canonicalName": "Yuneec E90",
+ "brand": "Yuneec",
+ "model": "E90",
+ "sensorWidth": 13.3056,
+ "sensorHeight": 8.656,
+ "imageWidth": 5472,
+ "imageHeight": 3648,
+ "focalLength": 8.29,
+ "landscape": true,
+ "fixedOrientation": true,
+ "minTriggerInterval": 1.3,
+ "deprecatedTranslatedName": "Yuneec E90"
+ },
+ {
+ "canonicalName": "Flir Duo R",
+ "brand": "Flir",
+ "model": "Duo R",
+ "sensorWidth": 160,
+ "sensorHeight": 120,
+ "imageWidth": 1920,
+ "imageHeight": 1080,
+ "focalLength": 1.9,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 0,
+ "deprecatedTranslatedName": "Flir Duo R"
+ },
+ {
+ "canonicalName": "Flir Duo Pro R",
+ "brand": "Flir",
+ "model": "Duo Pro R",
+ "sensorWidth": 10.88,
+ "sensorHeight": 8.704,
+ "imageWidth": 640,
+ "imageHeight": 512,
+ "focalLength": 19,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.0,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Workswell Wiris Security Thermal Camera",
+ "brand": "Workswell",
+ "model": "Wiris Security",
+ "sensorWidth": 13.6,
+ "sensorHeight": 10.2,
+ "imageWidth": 800,
+ "imageHeight": 600,
+ "focalLength": 35,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.8,
+ "deprecatedTranslatedName": ""
+ },
+ {
+ "canonicalName": "Workswell Wiris Security Visual Camera",
+ "brand": "Workswell",
+ "model": "Wiris Security",
+ "sensorWidth": 4.826,
+ "sensorHeight": 3.556,
+ "imageWidth": 1920,
+ "imageHeight": 1080,
+ "focalLength": 4.3,
+ "landscape": true,
+ "fixedOrientation": false,
+ "minTriggerInterval": 1.8,
+ "deprecatedTranslatedName": ""
+ }
+ ]
+}
diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc
index c1cf3be3af2..7c264f7579b 100644
--- a/src/Camera/QGCCameraManager.cc
+++ b/src/Camera/QGCCameraManager.cc
@@ -16,10 +16,18 @@
#include "FirmwarePlugin.h"
#include "QGCLoggingCategory.h"
#include "Joystick.h"
+#include "CameraMetaData.h"
+#include "JsonHelper.h"
+#include
+#include
+#include
+#include
#include
-QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog")
+QGC_LOGGING_CATEGORY(CameraManagerLog, "qgc.camera.qgccameramanager")
+
+QVariantList QGCCameraManager::_cameraList;
//-----------------------------------------------------------------------------
QGCCameraManager::CameraStruct::CameraStruct(QObject* parent, uint8_t compID_, Vehicle* vehicle_)
@@ -36,6 +44,8 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
{
qCDebug(CameraManagerLog) << "QGCCameraManager Created";
+ (void) qRegisterMetaType("CameraMetaData");
+
QQmlEngine::setObjectOwnership(this, QQmlEngine::CppOwnership);
_addCameraControlToLists(_simulatedCameraControl);
@@ -52,6 +62,9 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
QGCCameraManager::~QGCCameraManager()
{
+ for (QVariant cam : _cameraList) {
+ delete cam.value();
+ }
}
void QGCCameraManager::setCurrentCamera(int sel)
@@ -555,3 +568,87 @@ QGCCameraManager::_stepStream(int direction)
}
}
}
+
+const QVariantList &QGCCameraManager::cameraList()
+{
+ if (_cameraList.isEmpty()) {
+ const QList cams = _parseCameraMetaData(QStringLiteral(":/json/CameraMetaData.json"));
+ _cameraList.reserve(cams.size());
+
+ for (CameraMetaData* cam : cams) {
+ _cameraList << QVariant::fromValue(cam);
+ }
+ }
+
+ return _cameraList;
+}
+
+QList QGCCameraManager::_parseCameraMetaData(const QString &jsonFilePath)
+{
+ QList cameraList;
+
+ QString errorString;
+ int version;
+ const QJsonObject jsonObject = JsonHelper::openInternalQGCJsonFile(jsonFilePath, "CameraMetaData", 1, 1, version, errorString);
+ if (!errorString.isEmpty()) {
+ qCWarning(CameraManagerLog) << "Internal Error:" << errorString;
+ return cameraList;
+ }
+
+ static const QList rootKeyInfoList = {
+ { "cameraMetaData", QJsonValue::Array, true }
+ };
+ if (!JsonHelper::validateKeys(jsonObject, rootKeyInfoList, errorString)) {
+ qCWarning(CameraManagerLog) << errorString;
+ return cameraList;
+ }
+
+ static const QList cameraKeyInfoList = {
+ { "canonicalName", QJsonValue::String, true },
+ { "brand", QJsonValue::String, true },
+ { "model", QJsonValue::String, true },
+ { "sensorWidth", QJsonValue::Double, true },
+ { "sensorHeight", QJsonValue::Double, true },
+ { "imageWidth", QJsonValue::Double, true },
+ { "imageHeight", QJsonValue::Double, true },
+ { "focalLength", QJsonValue::Double, true },
+ { "landscape", QJsonValue::Bool, true },
+ { "fixedOrientation", QJsonValue::Bool, true },
+ { "minTriggerInterval", QJsonValue::Double, true },
+ { "deprecatedTranslatedName", QJsonValue::String, true },
+ };
+ const QJsonArray cameraInfo = jsonObject["cameraMetaData"].toArray();
+ for (const QJsonValue &jsonValue : cameraInfo) {
+ if (!jsonValue.isObject()) {
+ qCWarning(CameraManagerLog) << "Entry in CameraMetaData array is not object";
+ return cameraList;
+ }
+
+ const QJsonObject obj = jsonValue.toObject();
+ if (!JsonHelper::validateKeys(obj, cameraKeyInfoList, errorString)) {
+ qCWarning(CameraManagerLog) << errorString;
+ return cameraList;
+ }
+
+ const QString canonicalName = obj["canonicalName"].toString();
+ const QString brand = obj["brand"].toString();
+ const QString model = obj["model"].toString();
+ const double sensorWidth = obj["sensorWidth"].toDouble();
+ const double sensorHeight = obj["sensorHeight"].toDouble();
+ const double imageWidth = obj["imageWidth"].toDouble();
+ const double imageHeight = obj["imageHeight"].toDouble();
+ const double focalLength = obj["focalLength"].toDouble();
+ const bool landscape = obj["landscape"].toBool();
+ const bool fixedOrientation = obj["fixedOrientation"].toBool();
+ const double minTriggerInterval = obj["minTriggerInterval"].toDouble();
+ const QString deprecatedTranslatedName = obj["deprecatedTranslatedName"].toString();
+
+ CameraMetaData *const metaData = new CameraMetaData(
+ canonicalName, brand, model, sensorWidth, sensorHeight,
+ imageWidth, imageHeight, focalLength, landscape,
+ fixedOrientation, minTriggerInterval, deprecatedTranslatedName);
+ cameraList.append(metaData);
+ }
+
+ return cameraList;
+}
diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h
index d5671658e41..8af5c0521ca 100644
--- a/src/Camera/QGCCameraManager.h
+++ b/src/Camera/QGCCameraManager.h
@@ -12,21 +12,27 @@
#include "QmlObjectListModel.h"
#include "MavlinkCameraControl.h"
-#include
-#include
#include
#include
+#include
+#include
+#include
Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog)
class Joystick;
class SimulatedCameraControl;
+class Vehicle;
+class CameraMetaData;
+class QGCCameraManagerTest;
//-----------------------------------------------------------------------------
/// Camera Manager
class QGCCameraManager : public QObject
{
Q_OBJECT
+
+ friend class QGCCameraManagerTest;
public:
QGCCameraManager(Vehicle* vehicle);
virtual ~QGCCameraManager();
@@ -36,7 +42,6 @@ class QGCCameraManager : public QObject
Q_PROPERTY(MavlinkCameraControl* currentCameraInstance READ currentCameraInstance NOTIFY currentCameraChanged)
Q_PROPERTY(int currentCamera READ currentCamera WRITE setCurrentCamera NOTIFY currentCameraChanged)
-
virtual QmlObjectListModel* cameras () { return &_cameras; } ///< List of cameras provided by current vehicle
virtual QStringList cameraLabels () { return _cameraLabels; } ///< Camera names to show the user (for selection)
virtual int currentCamera () { return _currentCameraIndex; } ///< Current selected camera
@@ -45,6 +50,9 @@ class QGCCameraManager : public QObject
virtual QGCVideoStreamInfo* currentStreamInstance();
virtual QGCVideoStreamInfo* thermalStreamInstance();
+ /// Returns a list of CameraMetaData objects for available cameras on the vehicle.
+ virtual const QVariantList &cameraList();
+
// This is public to avoid some circular include problems caused by statics
class CameraStruct : public QObject {
public:
@@ -77,8 +85,6 @@ protected slots:
virtual void _toggleVideoRecording ();
protected:
-
-
virtual MavlinkCameraControl* _findCamera(int id);
virtual void _requestCameraInfo (CameraStruct* cameraInfo);
virtual void _handleHeartbeat (const mavlink_message_t& message);
@@ -94,6 +100,8 @@ protected slots:
virtual void _handleTrackingImageStatus(const mavlink_message_t& message);
virtual void _addCameraControlToLists(MavlinkCameraControl* cameraControl);
+ static QList _parseCameraMetaData(const QString &jsonFilePath);
+
Vehicle* _vehicle = nullptr;
Joystick* _activeJoystick = nullptr;
bool _vehicleReadyState = false;
@@ -106,4 +114,5 @@ protected slots:
QTimer _camerasLostHeartbeatTimer;
QMap _cameraInfoRequest;
SimulatedCameraControl* _simulatedCameraControl = nullptr;
+ static QVariantList _cameraList; ///< Standard QGC camera list
};
diff --git a/src/FirmwarePlugin/CMakeLists.txt b/src/FirmwarePlugin/CMakeLists.txt
index 9bbd1257bc2..48df5a6f83e 100644
--- a/src/FirmwarePlugin/CMakeLists.txt
+++ b/src/FirmwarePlugin/CMakeLists.txt
@@ -8,8 +8,6 @@ endif()
find_package(Qt6 REQUIRED COMPONENTS Core Positioning)
qt_add_library(FirmwarePlugin STATIC
- CameraMetaData.cc
- CameraMetaData.h
FirmwarePlugin.cc
FirmwarePlugin.h
FirmwarePluginFactory.cc
diff --git a/src/FirmwarePlugin/CameraMetaData.cc b/src/FirmwarePlugin/CameraMetaData.cc
deleted file mode 100644
index 10cdbb44a16..00000000000
--- a/src/FirmwarePlugin/CameraMetaData.cc
+++ /dev/null
@@ -1,40 +0,0 @@
-/****************************************************************************
- *
- * (c) 2009-2024 QGROUNDCONTROL PROJECT
- *
- * QGroundControl is licensed according to the terms in the file
- * COPYING.md in the root of the source code directory.
- *
- ****************************************************************************/
-
-#include "CameraMetaData.h"
-
-CameraMetaData::CameraMetaData(const QString& canonicalName,
- const QString& brand,
- const QString& model,
- double sensorWidth,
- double sensorHeight,
- double imageWidth,
- double imageHeight,
- double focalLength,
- bool landscape,
- bool fixedOrientation,
- double minTriggerInterval,
- const QString& deprecatedTranslatedName,
- QObject* parent)
- : QObject (parent)
- , canonicalName (canonicalName)
- , brand (brand)
- , model (model)
- , sensorWidth (sensorWidth)
- , sensorHeight (sensorHeight)
- , imageWidth (imageWidth)
- , imageHeight (imageHeight)
- , focalLength (focalLength)
- , landscape (landscape)
- , fixedOrientation (fixedOrientation)
- , minTriggerInterval (minTriggerInterval)
- , deprecatedTranslatedName (deprecatedTranslatedName)
-{
-
-}
diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc
index 739061ebba6..cab741a7ce7 100644
--- a/src/FirmwarePlugin/FirmwarePlugin.cc
+++ b/src/FirmwarePlugin/FirmwarePlugin.cc
@@ -11,7 +11,6 @@
#include "QGCApplication.h"
#include "GenericAutoPilotPlugin.h"
#include "AutoPilotPlugin.h"
-#include "CameraMetaData.h"
#include "QGCFileDownload.h"
#include "QGCCameraManager.h"
#include "RadioComponentController.h"
@@ -28,8 +27,6 @@ QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog")
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
-QVariantList FirmwarePlugin::_cameraList;
-
FirmwarePlugin::FirmwarePlugin(void)
{
qmlRegisterType ("QGroundControl.Controllers", 1, 0, "RadioComponentController");
@@ -337,588 +334,6 @@ const QVariantList& FirmwarePlugin::modeIndicators(const Vehicle*)
return _modeIndicatorList;
}
-const QVariantList& FirmwarePlugin::cameraList(const Vehicle*)
-{
- if (_cameraList.size() == 0) {
- CameraMetaData* metaData;
-
- metaData = new CameraMetaData(
- // Canon S100 @ 5.2mm f/2
- "Canon S100 PowerShot", // canonical name saved in plan file
- tr("Canon"), // brand
- tr("S100 PowerShot"), // model
- 7.6, // sensorWidth
- 5.7, // sensorHeight
- 4000, // imageWidth
- 3000, // imageHeight
- 5.2, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Canon S100 PowerShot"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- //tr("Canon EOS-M 22mm f/2"),
- "Canon EOS-M 22mm",
- tr("Canon"),
- tr("EOS-M 22mm"),
- 22.3, // sensorWidth
- 14.9, // sensorHeight
- 5184, // imageWidth
- 3456, // imageHeight
- 22, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Canon EOS-M 22mm"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- // Canon G9X @ 10.2mm f/2
- "Canon G9 X PowerShot",
- tr("Canon"),
- tr("G9 X PowerShot"),
- 13.2, // sensorWidth
- 8.8, // sensorHeight
- 5488, // imageWidth
- 3680, // imageHeight
- 10.2, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Canon G9 X PowerShot"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- // Canon SX260 HS @ 4.5mm f/3.5
- "Canon SX260 HS PowerShot",
- tr("Canon"),
- tr("SX260 HS PowerShot"),
- 6.17, // sensorWidth
- 4.55, // sensorHeight
- 4000, // imageWidth
- 3000, // imageHeight
- 4.5, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Canon SX260 HS PowerShot"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "GoPro Hero 4",
- tr("GoPro"),
- tr("Hero 4"),
- 6.17, // sensorWidth
- 4.55, // sendsorHeight
- 4000, // imageWidth
- 3000, // imageHeight
- 2.98, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0, // minTriggerInterval
- tr("GoPro Hero 4"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Parrot Sequioa RGB",
- tr("Parrot"),
- tr("Sequioa RGB"),
- 6.17, // sensorWidth
- 4.63, // sendsorHeight
- 4608, // imageWidth
- 3456, // imageHeight
- 4.9, // focalLength
- true, // landscape
- false, // fixedOrientation
- 1, // minTriggerInterval
- tr("Parrot Sequioa RGB"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Parrot Sequioa Monochrome",
- tr("Parrot"),
- tr("Sequioa Monochrome"),
- 4.8, // sensorWidth
- 3.6, // sendsorHeight
- 1280, // imageWidth
- 960, // imageHeight
- 4.0, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0.8, // minTriggerInterval
- tr("Parrot Sequioa Monochrome"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "RedEdge",
- tr("RedEdge"),
- tr("RedEdge"),
- 4.8, // sensorWidth
- 3.6, // sendsorHeight
- 1280, // imageWidth
- 960, // imageHeight
- 5.5, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0, // minTriggerInterval
- tr("RedEdge"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- // Ricoh GR II 18.3mm f/2.8
- "Ricoh GR II",
- tr("Ricoh"),
- tr("GR II"),
- 23.7, // sensorWidth
- 15.7, // sendsorHeight
- 4928, // imageWidth
- 3264, // imageHeight
- 18.3, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0, // minTriggerInterval
- tr("Ricoh GR II"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sentera Double 4K Sensor",
- tr("Sentera"),
- tr("Double 4K Sensor"),
- 6.2, // sensorWidth
- 4.65, // sendsorHeight
- 4000, // imageWidth
- 3000, // imageHeight
- 5.4, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0.8, // minTriggerInterval
- tr("Sentera Double 4K Sensor"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sentera NDVI Single Sensor",
- tr("Sentera"),
- tr("NDVI Single Sensor"),
- 4.68, // sensorWidth
- 3.56, // sendsorHeight
- 1248, // imageWidth
- 952, // imageHeight
- 4.14, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0.5, // minTriggerInterval
- tr("Sentera NDVI Single Sensor"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this);
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sentera 6X Sensor",
- tr("Sentera"),
- tr("6X Sensor"),
- 6.57, // sensorWidth
- 4.93, // sendsorHeight
- 1904, // imageWidth
- 1428, // imageHeight
- 8.0, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0.2, // minimum trigger interval
- tr(""), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sentera 65R Sensor",
- tr("Sentera"),
- tr("65R Sensor"),
- 29.9, // sensorWidth
- 22.4, // sendsorHeight
- 9344, // imageWidth
- 7000, // imageHeight
- 27.4, // focalLength
- true, // landscape
- false, // fixedOrientation
- 0.3, // minTriggerInterval
- tr(""), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-6000-body-kit#product_details_default
- // Sony a6000 Sony 16mm f/2.8"
- "Sony a6000 16mm",
- tr("Sony"),
- tr("a6000 16mm"),
- 23.5, // sensorWidth
- 15.6, // sensorHeight
- 6000, // imageWidth
- 4000, // imageHeight
- 16, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- tr("Sony a6000 16mm"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a6000 35mm",
- tr("Sony"),
- tr("a6000 35mm"),
- 23.5, // sensorWidth
- 15.6, // sensorHeight
- 6000, // imageWidth
- 4000, // imageHeight
- 35, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- "",
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a6300 Zeiss 21mm f/2.8",
- tr("Sony"),
- tr("a6300 Zeiss 21mm f/2.8"),
- 23.5, // sensorWidth
- 15.6, // sensorHeight
- 6000, // imageWidth
- 4000, // imageHeight
- 21, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- tr("Sony a6300 Zeiss 21mm f/2.8"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a6300 Sony 28mm f/2.0",
- tr("Sony"),
- tr("a6300 Sony 28mm f/2.0"),
- 23.5, // sensorWidth
- 15.6, // sensorHeight
- 6000, // imageWidth
- 4000, // imageHeight
- 28, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- tr("Sony a6300 Sony 28mm f/2.0"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a7R II Zeiss 21mm f/2.8",
- tr("Sony"),
- tr("a7R II Zeiss 21mm f/2.8"),
- 35.814, // sensorWidth
- 23.876, // sensorHeight
- 7952, // imageWidth
- 5304, // imageHeight
- 21, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- tr("Sony a7R II Zeiss 21mm f/2.8"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a7R II Sony 28mm f/2.0",
- tr("Sony"),
- tr("a7R II Sony 28mm f/2.0"),
- 35.814, // sensorWidth
- 23.876, // sensorHeight
- 7952, // imageWidth
- 5304, // imageHeight
- 28, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- tr("Sony a7R II Sony 28mm f/2.0"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a7r III 35mm",
- tr("Sony"),
- tr("a7r III 35mm"),
- 35.9, // sensorWidth
- 24.0, // sensorHeight
- 7952, // imageWidth
- 5304, // imageHeight
- 35, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- "",
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony a7r IV 35mm",
- tr("Sony"),
- tr("a7r IV 35mm"),
- 35.7, // sensorWidth
- 23.8, // sensorHeight
- 9504, // imageWidth
- 6336, // imageHeight
- 35, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- "",
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony DSC-QX30U @ 4.3mm f/3.5",
- tr("Sony"),
- tr("DSC-QX30U @ 4.3mm f/3.5"),
- 7.82, // sensorWidth
- 5.865, // sensorHeight
- 5184, // imageWidth
- 3888, // imageHeight
- 4.3, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 2.0, // minimum trigger interval
- tr("Sony DSC-QX30U @ 4.3mm f/3.5"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony DSC-RX0",
- tr("Sony"),
- tr("DSC-RX0"),
- 13.2, // sensorWidth
- 8.8, // sensorHeight
- 4800, // imageWidth
- 3200, // imageHeight
- 7.7, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Sony DSC-RX0"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Sony DSC-RX1R II 35mm",
- tr("Sony"),
- tr("DSC-RX1R II 35mm"),
- 35.9, // sensorWidth
- 24.0, // sensorHeight
- 7952, // imageWidth
- 5304, // imageHeight
- 35, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- "",
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-qx1-body-kit/specifications
- //-- http://www.sony.com/electronics/camera-lenses/sel16f28/specifications
- //tr("Sony ILCE-QX1 Sony 16mm f/2.8"),
- "Sony ILCE-QX1",
- tr("Sony"),
- tr("ILCE-QX1"),
- 23.2, // sensorWidth
- 15.4, // sensorHeight
- 5456, // imageWidth
- 3632, // imageHeight
- 16, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Sony ILCE-QX1"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- //-- http://www.sony.co.uk/electronics/interchangeable-lens-cameras/ilce-qx1-body-kit/specifications
- // Sony NEX-5R Sony 20mm f/2.8"
- "Sony NEX-5R 20mm",
- tr("Sony"),
- tr("NEX-5R 20mm"),
- 23.2, // sensorWidth
- 15.4, // sensorHeight
- 4912, // imageWidth
- 3264, // imageHeight
- 20, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1, // minimum trigger interval
- tr("Sony NEX-5R 20mm"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- // Sony RX100 II @ 10.4mm f/1.8
- "Sony RX100 II 28mm",
- tr("Sony"),
- tr("RX100 II 28mm"),
- 13.2, // sensorWidth
- 8.8, // sensorHeight
- 5472, // imageWidth
- 3648, // imageHeight
- 10.4, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Sony RX100 II 28mm"),// SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Yuneec CGOET",
- tr("Yuneec"),
- tr("CGOET"),
- 5.6405, // sensorWidth
- 3.1813, // sensorHeight
- 1920, // imageWidth
- 1080, // imageHeight
- 3.5, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.3, // minimum trigger interval
- tr("Yuneec CGOET"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Yuneec E10T",
- tr("Yuneec"),
- tr("E10T"),
- 5.6405, // sensorWidth
- 3.1813, // sensorHeight
- 1920, // imageWidth
- 1080, // imageHeight
- 23, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.3, // minimum trigger interval
- tr("Yuneec E10T"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Yuneec E50",
- tr("Yuneec"),
- tr("E50"),
- 6.2372, // sensorWidth
- 4.7058, // sensorHeight
- 4000, // imageWidth
- 3000, // imageHeight
- 7.2, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.3, // minimum trigger interval
- tr("Yuneec E50"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Yuneec E90",
- tr("Yuneec"),
- tr("E90"),
- 13.3056, // sensorWidth
- 8.656, // sensorHeight
- 5472, // imageWidth
- 3648, // imageHeight
- 8.29, // focalLength
- true, // true: landscape orientation
- true, // true: camera is fixed orientation
- 1.3, // minimum trigger interval
- tr("Yuneec E90"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Flir Duo R",
- tr("Flir"),
- tr("Duo R"),
- 160, // sensorWidth
- 120, // sensorHeight
- 1920, // imageWidth
- 1080, // imageHeight
- 1.9, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 0, // minimum trigger interval
- tr("Flir Duo R"), // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Flir Duo Pro R",
- tr("Flir"),
- tr("Duo Pro R"),
- 10.88, // sensorWidth
- 8.704, // sensorHeight
- 640, // imageWidth
- 512, // imageHeight
- 19, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.0, // minimum trigger interval
- "", // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Workswell Wiris Security Thermal Camera",
- tr("Workswell"),
- tr("Wiris Security"),
- 13.6, // sensorWidth
- 10.2, // sensorHeight
- 800, // imageWidth
- 600, // imageHeight
- 35, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.8, // minimum trigger interval
- "", // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
-
- metaData = new CameraMetaData(
- "Workswell Wiris Security Visual Camera",
- tr("Workswell"),
- tr("Wiris Security"),
- 4.826, // sensorWidth
- 3.556, // sensorHeight
- 1920, // imageWidth
- 1080, // imageHeight
- 4.3, // focalLength
- true, // true: landscape orientation
- false, // true: camera is fixed orientation
- 1.8, // minimum trigger interval
- "", // SHOULD BE BLANK FOR NEWLY ADDED CAMERAS. Deprecated translation from older builds.
- this); // parent
- _cameraList.append(QVariant::fromValue(metaData));
- }
-
- return _cameraList;
-}
-
QMap* FirmwarePlugin::factGroups(void) {
// Generic plugin has no FactGroups
return nullptr;
diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h
index 7591280b2d6..176b6cb6758 100644
--- a/src/FirmwarePlugin/FirmwarePlugin.h
+++ b/src/FirmwarePlugin/FirmwarePlugin.h
@@ -307,10 +307,6 @@ class FirmwarePlugin : public QObject
/// @return A list of QUrl with the indicators
virtual const QVariantList& modeIndicators(const Vehicle* vehicle);
- /// Returns a list of CameraMetaData objects for available cameras on the vehicle.
- /// TODO: This should go into QGCCameraManager
- virtual const QVariantList& cameraList(const Vehicle* vehicle);
-
/// Creates vehicle camera manager.
virtual QGCCameraManager* createCameraManager(Vehicle *vehicle);
@@ -386,6 +382,4 @@ class FirmwarePlugin : public QObject
protected:
QVariantList _toolIndicatorList;
QVariantList _modeIndicatorList;
-
- static QVariantList _cameraList; ///< Standard QGC camera list
};
diff --git a/src/MissionManager/CMakeLists.txt b/src/MissionManager/CMakeLists.txt
index 916c33171e5..523ca6bda17 100644
--- a/src/MissionManager/CMakeLists.txt
+++ b/src/MissionManager/CMakeLists.txt
@@ -83,6 +83,7 @@ target_link_libraries(MissionManager
PRIVATE
Qt6::Qml
API
+ Camera
FirmwarePlugin
Geo
PUBLIC
diff --git a/src/PlanView/CameraCalcCamera.qml b/src/PlanView/CameraCalcCamera.qml
index 10e2b322b84..a336e922333 100644
--- a/src/PlanView/CameraCalcCamera.qml
+++ b/src/PlanView/CameraCalcCamera.qml
@@ -17,7 +17,6 @@ ColumnLayout {
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
- property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
Component.onCompleted: {
cameraBrandCombo.selectCurrentBrand()
diff --git a/src/PlanView/CameraCalcGrid.qml b/src/PlanView/CameraCalcGrid.qml
index 152ae9f6f12..b953081f2e5 100644
--- a/src/PlanView/CameraCalcGrid.qml
+++ b/src/PlanView/CameraCalcGrid.qml
@@ -20,9 +20,7 @@ Column {
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
- property var _cameraList: [ ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
- property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
property bool _cameraComboFilled: false
readonly property int _gridTypeManual: 0
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 2a2d189cb5e..0e2fde413c8 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -3259,8 +3259,8 @@ const QVariantList& Vehicle::modeIndicators()
const QVariantList& Vehicle::staticCameraList() const
{
- if (_firmwarePlugin) {
- return _firmwarePlugin->cameraList(this);
+ if (_cameraManager) {
+ return _cameraManager->cameraList();
}
static QVariantList emptyList;
return emptyList;
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index e943e7bfd85..dcc08d2789f 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -41,6 +41,9 @@ add_qgc_test(AudioOutputTest)
# add_subdirectory(AutoPilotPlugins)
# add_qgc_test(RadioConfigTest)
+add_subdirectory(Camera)
+add_qgc_test(QGCCameraManagerTest)
+
add_subdirectory(Comms)
add_qgc_test(QGCSerialPortInfoTest)
@@ -132,6 +135,7 @@ target_link_libraries(qgctest
ADSBTest
AnalyzeViewTest
AudioTest
+ CameraTest
CommsTest
CompressionTest
FactSystemTest
diff --git a/test/Camera/CMakeLists.txt b/test/Camera/CMakeLists.txt
new file mode 100644
index 00000000000..e31dafcc697
--- /dev/null
+++ b/test/Camera/CMakeLists.txt
@@ -0,0 +1,17 @@
+find_package(Qt6 REQUIRED COMPONENTS Core Test)
+
+qt_add_library(CameraTest
+ STATIC
+ QGCCameraManagerTest.cc
+ QGCCameraManagerTest.h
+)
+
+target_link_libraries(CameraTest
+ PRIVATE
+ Qt6::Test
+ Camera
+ PUBLIC
+ qgcunittest
+)
+
+target_include_directories(CameraTest PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
diff --git a/test/Camera/QGCCameraManagerTest.cc b/test/Camera/QGCCameraManagerTest.cc
new file mode 100644
index 00000000000..c856e82f7b5
--- /dev/null
+++ b/test/Camera/QGCCameraManagerTest.cc
@@ -0,0 +1,22 @@
+/****************************************************************************
+ *
+ * (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 "QGCCameraManagerTest.h"
+#include "QGCCameraManager.h"
+
+#include
+
+void QGCCameraManagerTest::_testCameraList()
+{
+ const QList cameraList = QGCCameraManager::_parseCameraMetaData(QStringLiteral(":/json/CameraMetaData.json"));
+
+ QVERIFY(!cameraList.isEmpty());
+
+ qDeleteAll(cameraList);
+}
diff --git a/test/Camera/QGCCameraManagerTest.h b/test/Camera/QGCCameraManagerTest.h
new file mode 100644
index 00000000000..30b1ff8b73b
--- /dev/null
+++ b/test/Camera/QGCCameraManagerTest.h
@@ -0,0 +1,20 @@
+/****************************************************************************
+ *
+ * (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 "UnitTest.h"
+
+class QGCCameraManagerTest : public UnitTest
+{
+ Q_OBJECT
+
+private slots:
+ void _testCameraList();
+};
diff --git a/test/UnitTestList.cc b/test/UnitTestList.cc
index 604041f9325..56df9209c70 100644
--- a/test/UnitTestList.cc
+++ b/test/UnitTestList.cc
@@ -28,6 +28,9 @@
// AutoPilotPlugins
// #include "RadioConfigTest.h"
+// Camera
+#include "QGCCameraManagerTest.h"
+
// Comms
#include "QGCSerialPortInfoTest.h"
@@ -129,6 +132,9 @@ int runTests(bool stress, QStringView unitTestOptions)
// AutoPilotPlugins
// UT_REGISTER_TEST(RadioConfigTest)
+ // Camera
+ UT_REGISTER_TEST(QGCCameraManagerTest)
+
// Comms
UT_REGISTER_TEST(QGCSerialPortInfoTest)