Unverified Commit 90e5110a authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7293 from mavlink/cameraAPI

Camera API for all firmware types
parents 909b5147 1ca73ff2
...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 3.6.0 - Daily Build
* Making the camera API available to all firmwares, not just PX4.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page. * ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.
* Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans. * Major rewrite and bug fix pass through Structure Scan. Previous version had such bad problems that it can no longer be supported. Plans with Structure Scan will need to be recreated. New QGC will not load old Structure Scan plans.
......
...@@ -14,13 +14,14 @@ ...@@ -14,13 +14,14 @@
#include "SettingsManager.h" #include "SettingsManager.h"
#include "AppSettings.h" #include "AppSettings.h"
#include "QGCFileDownload.h" #include "QGCFileDownload.h"
#include "QGCCameraManager.h"
#include <QRegularExpression> #include <QRegularExpression>
#include <QDebug> #include <QDebug>
QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog") QGC_LOGGING_CATEGORY(FirmwarePluginLog, "FirmwarePluginLog")
static FirmwarePluginFactoryRegister* _instance = NULL; static FirmwarePluginFactoryRegister* _instance = nullptr;
const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle."); const QString guided_mode_not_supported_by_vehicle = QObject::tr("Guided mode not supported by Vehicle.");
...@@ -195,22 +196,16 @@ QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const ...@@ -195,22 +196,16 @@ QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const
switch (vehicleType) { switch (vehicleType) {
case MAV_TYPE_GENERIC: case MAV_TYPE_GENERIC:
return QStringLiteral(":/json/MavCmdInfoCommon.json"); return QStringLiteral(":/json/MavCmdInfoCommon.json");
break;
case MAV_TYPE_FIXED_WING: case MAV_TYPE_FIXED_WING:
return QStringLiteral(":/json/MavCmdInfoFixedWing.json"); return QStringLiteral(":/json/MavCmdInfoFixedWing.json");
break;
case MAV_TYPE_QUADROTOR: case MAV_TYPE_QUADROTOR:
return QStringLiteral(":/json/MavCmdInfoMultiRotor.json"); return QStringLiteral(":/json/MavCmdInfoMultiRotor.json");
break;
case MAV_TYPE_VTOL_QUADROTOR: case MAV_TYPE_VTOL_QUADROTOR:
return QStringLiteral(":/json/MavCmdInfoVTOL.json"); return QStringLiteral(":/json/MavCmdInfoVTOL.json");
break;
case MAV_TYPE_SUBMARINE: case MAV_TYPE_SUBMARINE:
return QStringLiteral(":/json/MavCmdInfoSub.json"); return QStringLiteral(":/json/MavCmdInfoSub.json");
break;
case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_GROUND_ROVER:
return QStringLiteral(":/json/MavCmdInfoRover.json"); return QStringLiteral(":/json/MavCmdInfoRover.json");
break;
default: default:
qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType;
return QString(); return QString();
...@@ -751,9 +746,9 @@ bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& ...@@ -751,9 +746,9 @@ bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString&
void FirmwarePlugin::batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const void FirmwarePlugin::batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const
{ {
Q_UNUSED(vehicle); Q_UNUSED(vehicle);
mAhBattery = 0; mAhBattery = 0;
hoverAmps = 0; hoverAmps = 0;
cruiseAmps = 0; cruiseAmps = 0;
} }
QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle) QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle)
...@@ -789,17 +784,12 @@ bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const ...@@ -789,17 +784,12 @@ bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const
QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle) QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{ {
Q_UNUSED(vehicle); return new QGCCameraManager(vehicle);
return nullptr;
} }
QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent) QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent)
{ {
Q_UNUSED(info); return new QGCCameraControl(info, vehicle, compID, parent);
Q_UNUSED(vehicle);
Q_UNUSED(compID);
Q_UNUSED(parent);
return nullptr;
} }
uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
......
...@@ -210,12 +210,12 @@ public: ...@@ -210,12 +210,12 @@ public:
/// Loads the specified parameter meta data file. /// Loads the specified parameter meta data file.
/// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to /// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to
/// call deleteParameterMetaData when no longer needed. /// call deleteParameterMetaData when no longer needed.
virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; } virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return nullptr; }
/// Returns the FactMetaData associated with the parameter name /// Returns the FactMetaData associated with the parameter name
/// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
/// @param name Parameter name /// @param name Parameter name
virtual FactMetaData* getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(name); Q_UNUSED(vehicleType); return NULL; } virtual FactMetaData* getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(name); Q_UNUSED(vehicleType); return nullptr; }
/// Adds the parameter meta data to the Fact /// Adds the parameter meta data to the Fact
/// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
...@@ -267,11 +267,11 @@ public: ...@@ -267,11 +267,11 @@ public:
/// TODO: This should go into QGCCameraManager /// TODO: This should go into QGCCameraManager
virtual const QVariantList& cameraList(const Vehicle* vehicle); virtual const QVariantList& cameraList(const Vehicle* vehicle);
/// Creates vehicle camera manager. Returns NULL if not supported. /// Creates vehicle camera manager.
virtual QGCCameraManager* createCameraManager(Vehicle *vehicle); virtual QGCCameraManager* createCameraManager(Vehicle *vehicle);
/// Camera control. Returns NULL if not supported. /// Camera control.
virtual QGCCameraControl* createCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL); virtual QGCCameraControl* createCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = nullptr);
/// Returns a pointer to a dictionary of firmware-specific FactGroups /// Returns a pointer to a dictionary of firmware-specific FactGroups
virtual QMap<QString, FactGroup*>* factGroups(void); virtual QMap<QString, FactGroup*>* factGroups(void);
...@@ -312,7 +312,7 @@ public: ...@@ -312,7 +312,7 @@ public:
/// Allows the Firmware plugin to override the facts meta data. /// Allows the Firmware plugin to override the facts meta data.
/// @param vehicleType - Type of current vehicle /// @param vehicleType - Type of current vehicle
/// @param metaData - MetaData for fact /// @param metaData - MetaData for fact
virtual void adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) {Q_UNUSED(vehicleType); Q_UNUSED(metaData);}; virtual void adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) {Q_UNUSED(vehicleType); Q_UNUSED(metaData);}
// FIXME: Hack workaround for non pluginize FollowMe support // FIXME: Hack workaround for non pluginize FollowMe support
static const QString px4FollowMeFlightMode; static const QString px4FollowMeFlightMode;
......
...@@ -576,16 +576,6 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl ...@@ -576,16 +576,6 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl
return true; return true;
} }
QGCCameraManager* PX4FirmwarePlugin::createCameraManager(Vehicle* vehicle)
{
return new QGCCameraManager(vehicle);
}
QGCCameraControl* PX4FirmwarePlugin::createCameraControl(const mavlink_camera_information_t* info, Vehicle *vehicle, int compID, QObject* parent)
{
return new QGCCameraControl(info, vehicle, compID, parent);
}
uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) uint32_t PX4FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode)
{ {
union px4_custom_mode px4_cm; union px4_custom_mode px4_cm;
......
...@@ -67,8 +67,6 @@ public: ...@@ -67,8 +67,6 @@ public:
QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); }
bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override; bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override;
QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); }
QGCCameraManager* createCameraManager (Vehicle* vehicle) override;
QGCCameraControl* createCameraControl (const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL) override;
uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) override; uint32_t highLatencyCustomModeTo32Bits (uint16_t hlCustomMode) override;
bool supportsTerrainFrame (void) const override { return false; } bool supportsTerrainFrame (void) const override { return false; }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment