diff --git a/src/Camera/CMakeLists.txt b/src/Camera/CMakeLists.txt index a5c9c92969a..182f879c4b5 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 diff --git a/src/Camera/CameraMetaData.cc b/src/Camera/CameraMetaData.cc new file mode 100644 index 00000000000..2af8af11049 --- /dev/null +++ b/src/Camera/CameraMetaData.cc @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * (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, + 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) +{ + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; +} diff --git a/src/FirmwarePlugin/CameraMetaData.h b/src/Camera/CameraMetaData.h similarity index 56% rename from src/FirmwarePlugin/CameraMetaData.h rename to src/Camera/CameraMetaData.h index ced383001fb..3fed0b7cabd 100644 --- a/src/FirmwarePlugin/CameraMetaData.h +++ b/src/Camera/CameraMetaData.h @@ -9,28 +9,15 @@ #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 { 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_PROPERTY(QString canonicalName MEMBER canonicalName CONSTANT) Q_PROPERTY(QString deprecatedTranslatedName MEMBER deprecatedTranslatedName CONSTANT) Q_PROPERTY(QString brand MEMBER brand CONSTANT) @@ -44,21 +31,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, + QObject *parent = nullptr); + + 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; }; diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc index 3934997ff0f..d9f160fd900 100644 --- a/src/Camera/QGCCameraManager.cc +++ b/src/Camera/QGCCameraManager.cc @@ -16,11 +16,14 @@ #include "FirmwarePlugin.h" #include "QGCLoggingCategory.h" #include "Joystick.h" +#include "CameraMetaData.h" #include QGC_LOGGING_CATEGORY(CameraManagerLog, "CameraManagerLog") +QVariantList QGCCameraManager::_cameraList; + //----------------------------------------------------------------------------- QGCCameraManager::CameraStruct::CameraStruct(QObject* parent, uint8_t compID_, Vehicle* vehicle_) : QObject (parent) @@ -556,3 +559,585 @@ QGCCameraManager::_stepStream(int direction) } } } + +const QVariantList &QGCCameraManager::cameraList() +{ + if (_cameraList.isEmpty()) { + CameraMetaData *metaData = nullptr; + + 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; +} diff --git a/src/Camera/QGCCameraManager.h b/src/Camera/QGCCameraManager.h index d5671658e41..3463045cf75 100644 --- a/src/Camera/QGCCameraManager.h +++ b/src/Camera/QGCCameraManager.h @@ -12,15 +12,17 @@ #include "QmlObjectListModel.h" #include "MavlinkCameraControl.h" -#include -#include #include #include +#include +#include +#include Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog) class Joystick; class SimulatedCameraControl; +class Vehicle; //----------------------------------------------------------------------------- /// Camera Manager @@ -36,7 +38,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 +46,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: @@ -106,4 +110,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/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 27145ba2df8..1f705ebb80b 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3263,8 +3263,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;