diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 031ab5cc04239082650f053388c259050bc7727b..1790a4a5018274cbb5ae5ae7863f42f6965ac720 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -14,13 +14,14 @@ #include "SettingsManager.h" #include "AppSettings.h" #include "QGCFileDownload.h" +#include "QGCCameraManager.h" #include #include 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."); @@ -195,22 +196,16 @@ QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const switch (vehicleType) { case MAV_TYPE_GENERIC: return QStringLiteral(":/json/MavCmdInfoCommon.json"); - break; case MAV_TYPE_FIXED_WING: return QStringLiteral(":/json/MavCmdInfoFixedWing.json"); - break; case MAV_TYPE_QUADROTOR: return QStringLiteral(":/json/MavCmdInfoMultiRotor.json"); - break; case MAV_TYPE_VTOL_QUADROTOR: return QStringLiteral(":/json/MavCmdInfoVTOL.json"); - break; case MAV_TYPE_SUBMARINE: return QStringLiteral(":/json/MavCmdInfoSub.json"); - break; case MAV_TYPE_GROUND_ROVER: return QStringLiteral(":/json/MavCmdInfoRover.json"); - break; default: qWarning() << "FirmwarePlugin::missionCommandOverrides called with bad MAV_TYPE:" << vehicleType; return QString(); @@ -751,9 +746,9 @@ bool FirmwarePlugin::_setFlightModeAndValidate(Vehicle* vehicle, const QString& void FirmwarePlugin::batteryConsumptionData(Vehicle* vehicle, int& mAhBattery, double& hoverAmps, double& cruiseAmps) const { Q_UNUSED(vehicle); - mAhBattery = 0; - hoverAmps = 0; - cruiseAmps = 0; + mAhBattery = 0; + hoverAmps = 0; + cruiseAmps = 0; } QString FirmwarePlugin::autoDisarmParameter(Vehicle* vehicle) @@ -789,17 +784,12 @@ bool FirmwarePlugin::isVtol(const Vehicle* vehicle) const QGCCameraManager* FirmwarePlugin::createCameraManager(Vehicle* vehicle) { - Q_UNUSED(vehicle); - return nullptr; + return new QGCCameraManager(vehicle); } QGCCameraControl* FirmwarePlugin::createCameraControl(const mavlink_camera_information_t *info, Vehicle *vehicle, int compID, QObject* parent) { - Q_UNUSED(info); - Q_UNUSED(vehicle); - Q_UNUSED(compID); - Q_UNUSED(parent); - return nullptr; + return new QGCCameraControl(info, vehicle, compID, parent); } uint32_t FirmwarePlugin::highLatencyCustomModeTo32Bits(uint16_t hlCustomMode) diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 57006f56826d286e3e0bb46359e925534748ed96..df1ebbab7427b548075339d0532cfc22deca5ff3 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -210,12 +210,12 @@ public: /// Loads the specified parameter meta data file. /// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to /// 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 /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData /// @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 /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData @@ -267,11 +267,11 @@ public: /// TODO: This should go into QGCCameraManager 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); - /// Camera control. Returns NULL if not supported. - virtual QGCCameraControl* createCameraControl(const mavlink_camera_information_t* info, Vehicle* vehicle, int compID, QObject* parent = NULL); + /// Camera control. + 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 virtual QMap* factGroups(void); @@ -312,7 +312,7 @@ public: /// Allows the Firmware plugin to override the facts meta data. /// @param vehicleType - Type of current vehicle /// @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 static const QString px4FollowMeFlightMode; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 9b5f3f56825c56bf368e6decbd6a48301387b9b6..5373488a22f00b9020e3fe6b5d0cf61204b81649 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -576,16 +576,6 @@ bool PX4FirmwarePlugin::vehicleYawsToNextWaypointInMission(const Vehicle* vehicl 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) { union px4_custom_mode px4_cm; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index c70b43a0b504ad05107665f1d95c4b2b60d9299f..edee88893d0ae7788c5f846f6620aacd41cbe152 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -67,8 +67,6 @@ public: QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } bool vehicleYawsToNextWaypointInMission(const Vehicle* vehicle) const override; 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; bool supportsTerrainFrame (void) const override { return false; }