From 891490c970446108c004d31aca2902700ff7d844 Mon Sep 17 00:00:00 2001 From: Holden Date: Fri, 25 Oct 2024 06:16:06 -0400 Subject: [PATCH] QmlControls: Fix Parenting of Several Classes --- src/QmlControls/CustomAction.cc | 37 +++++++++- src/QmlControls/CustomAction.h | 60 +++++++-------- .../EditPositionDialogController.cc | 74 ++++++++++--------- .../EditPositionDialogController.h | 66 ++++++++--------- src/QmlControls/ParameterEditorController.cc | 9 ++- src/QmlControls/ParameterEditorController.h | 9 +-- src/QmlControls/QGCFileDialogController.cc | 11 +++ src/QmlControls/QGCFileDialogController.h | 5 +- src/QmlControls/RCChannelMonitorController.cc | 17 +++-- src/QmlControls/RCChannelMonitorController.h | 10 +-- src/QmlControls/RCToParamDialogController.cc | 38 ++++++---- src/QmlControls/RCToParamDialogController.h | 50 ++++++------- src/QmlControls/ScreenToolsController.cc | 8 +- src/QmlControls/ScreenToolsController.h | 7 +- 14 files changed, 238 insertions(+), 163 deletions(-) diff --git a/src/QmlControls/CustomAction.cc b/src/QmlControls/CustomAction.cc index 849cef3054cb..f31a45b1ad82 100644 --- a/src/QmlControls/CustomAction.cc +++ b/src/QmlControls/CustomAction.cc @@ -10,7 +10,42 @@ #include "CustomAction.h" #include "Vehicle.h" -void CustomAction::sendTo(Vehicle* vehicle) { +CustomAction::CustomAction(QObject *parent) + : QObject(parent) +{ + // qCDebug() << Q_FUNC_INFO << this; +} + +CustomAction::CustomAction( + const QString &label, + const QString &description, + MAV_CMD mavCmd, + MAV_COMPONENT compId, + float param1, + float param2, + float param3, + float param4, + float param5, + float param6, + float param7, + QObject *parent +) : QObject(parent) + , _label(label) + , _description(description) + , _mavCmd(mavCmd) + , _compId(compId) + , _params{ param1, param2, param3, param4, param5, param6, param7 } +{ + // qCDebug() << Q_FUNC_INFO << this; +}; + +CustomAction::~CustomAction() +{ + // qCDebug() << Q_FUNC_INFO << this; +} + +void CustomAction::sendTo(Vehicle *vehicle) +{ if (vehicle) { const bool showError = true; vehicle->sendMavCommand(_compId, _mavCmd, showError, _params[0], _params[1], _params[2], _params[3], _params[4], _params[5], _params[6]); diff --git a/src/QmlControls/CustomAction.h b/src/QmlControls/CustomAction.h index 6ccb1c370bc1..fc25a5218f02 100644 --- a/src/QmlControls/CustomAction.h +++ b/src/QmlControls/CustomAction.h @@ -18,42 +18,36 @@ class Vehicle; class CustomAction: public QObject { Q_OBJECT - - Q_PROPERTY(QString label READ label CONSTANT) - Q_PROPERTY(QString description READ description CONSTANT) + Q_PROPERTY(QString label READ label CONSTANT) + Q_PROPERTY(QString description READ description CONSTANT) public: - CustomAction() { CustomAction(QString(), QString(), MAV_CMD(0), MAV_COMPONENT(0), 0, 0, 0, 0, 0, 0, 0); } // this is required for QML reflection + explicit CustomAction(QObject *parent = nullptr); CustomAction( - QString label, - QString description, - MAV_CMD mavCmd, - MAV_COMPONENT compId, - float param1, - float param2, - float param3, - float param4, - float param5, - float param6, - float param7, - QObject* parent = nullptr) - : QObject (parent) - , _label (label) - , _description (description) - , _mavCmd (mavCmd) - , _compId (compId) - , _params { param1, param2, param3, param4, param5, param6, param7 } - {}; - - Q_INVOKABLE void sendTo(Vehicle* vehicle); - - QString label () const { return _label; } - QString description() const { return _description; } + const QString &label, + const QString &description, + MAV_CMD mavCmd, + MAV_COMPONENT compId, + float param1, + float param2, + float param3, + float param4, + float param5, + float param6, + float param7, + QObject *parent = nullptr + ); + ~CustomAction(); + + Q_INVOKABLE void sendTo(Vehicle *vehicle); + + const QString& label() const { return _label; } + const QString& description() const { return _description; } private: - QString _label; - QString _description; - MAV_CMD _mavCmd; - MAV_COMPONENT _compId; - float _params[7]; + const QString _label; + const QString _description; + const MAV_CMD _mavCmd = MAV_CMD_ENUM_END; + const MAV_COMPONENT _compId = MAV_COMPONENT_ENUM_END; + const float _params[7]{}; }; diff --git a/src/QmlControls/EditPositionDialogController.cc b/src/QmlControls/EditPositionDialogController.cc index fbdaa041973c..4d16f82a50ab 100644 --- a/src/QmlControls/EditPositionDialogController.cc +++ b/src/QmlControls/EditPositionDialogController.cc @@ -16,26 +16,34 @@ QMap EditPositionDialogController::_metaDataMap; -EditPositionDialogController::EditPositionDialogController(void) - : _latitudeFact (0, _latitudeFactName, FactMetaData::valueTypeDouble) - , _longitudeFact (0, _longitudeFactName, FactMetaData::valueTypeDouble) - , _zoneFact (0, _zoneFactName, FactMetaData::valueTypeUint8) - , _hemisphereFact (0, _hemisphereFactName, FactMetaData::valueTypeUint8) - , _eastingFact (0, _eastingFactName, FactMetaData::valueTypeDouble) - , _northingFact (0, _northingFactName, FactMetaData::valueTypeDouble) - , _mgrsFact (0, _mgrsFactName, FactMetaData::valueTypeString) +EditPositionDialogController::EditPositionDialogController(QObject *parent) + : QObject(parent) + , _latitudeFact(new Fact(0, _latitudeFactName, FactMetaData::valueTypeDouble, this)) + , _longitudeFact(new Fact(0, _longitudeFactName, FactMetaData::valueTypeDouble, this)) + , _zoneFact(new Fact(0, _zoneFactName, FactMetaData::valueTypeUint8, this)) + , _hemisphereFact(new Fact(0, _hemisphereFactName, FactMetaData::valueTypeUint8, this)) + , _eastingFact(new Fact(0, _eastingFactName, FactMetaData::valueTypeDouble, this)) + , _northingFact(new Fact(0, _northingFactName, FactMetaData::valueTypeDouble, this)) + , _mgrsFact(new Fact(0, _mgrsFactName, FactMetaData::valueTypeString, this)) { + // qCDebug() << Q_FUNC_INFO << this; + if (_metaDataMap.isEmpty()) { _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/EditPositionDialog.FactMetaData.json"), nullptr /* QObject parent */); } - _latitudeFact.setMetaData (_metaDataMap[_latitudeFactName]); - _longitudeFact.setMetaData (_metaDataMap[_longitudeFactName]); - _zoneFact.setMetaData (_metaDataMap[_zoneFactName]); - _hemisphereFact.setMetaData (_metaDataMap[_hemisphereFactName]); - _eastingFact.setMetaData (_metaDataMap[_eastingFactName]); - _northingFact.setMetaData (_metaDataMap[_northingFactName]); - _mgrsFact.setMetaData (_metaDataMap[_mgrsFactName]); + _latitudeFact->setMetaData (_metaDataMap[_latitudeFactName]); + _longitudeFact->setMetaData (_metaDataMap[_longitudeFactName]); + _zoneFact->setMetaData (_metaDataMap[_zoneFactName]); + _hemisphereFact->setMetaData (_metaDataMap[_hemisphereFactName]); + _eastingFact->setMetaData (_metaDataMap[_eastingFactName]); + _northingFact->setMetaData (_metaDataMap[_northingFactName]); + _mgrsFact->setMetaData (_metaDataMap[_mgrsFactName]); +} + +EditPositionDialogController::~EditPositionDialogController() +{ + // qCDebug() << Q_FUNC_INFO << this; } void EditPositionDialogController::setCoordinate(QGeoCoordinate coordinate) @@ -46,53 +54,53 @@ void EditPositionDialogController::setCoordinate(QGeoCoordinate coordinate) } } -void EditPositionDialogController::initValues(void) +void EditPositionDialogController::initValues() { - _latitudeFact.setRawValue(_coordinate.latitude()); - _longitudeFact.setRawValue(_coordinate.longitude()); + _latitudeFact->setRawValue(_coordinate.latitude()); + _longitudeFact->setRawValue(_coordinate.longitude()); double easting, northing; int zone = QGCGeo::convertGeoToUTM(_coordinate, easting, northing); if (zone >= 1 && zone <= 60) { - _zoneFact.setRawValue(zone); - _hemisphereFact.setRawValue(_coordinate.latitude() < 0); - _eastingFact.setRawValue(easting); - _northingFact.setRawValue(northing); + _zoneFact->setRawValue(zone); + _hemisphereFact->setRawValue(_coordinate.latitude() < 0); + _eastingFact->setRawValue(easting); + _northingFact->setRawValue(northing); } QString mgrs = QGCGeo::convertGeoToMGRS(_coordinate); if (!mgrs.isEmpty()) { - _mgrsFact.setRawValue(mgrs); + _mgrsFact->setRawValue(mgrs); } } -void EditPositionDialogController::setFromGeo(void) +void EditPositionDialogController::setFromGeo() { - _coordinate.setLatitude(_latitudeFact.rawValue().toDouble()); - _coordinate.setLongitude(_longitudeFact.rawValue().toDouble()); + _coordinate.setLatitude(_latitudeFact->rawValue().toDouble()); + _coordinate.setLongitude(_longitudeFact->rawValue().toDouble()); emit coordinateChanged(_coordinate); } -void EditPositionDialogController::setFromUTM(void) +void EditPositionDialogController::setFromUTM() { - qDebug() << _eastingFact.rawValue().toDouble() << _northingFact.rawValue().toDouble() << _zoneFact.rawValue().toInt() << (_hemisphereFact.rawValue().toInt() == 1); - if (QGCGeo::convertUTMToGeo(_eastingFact.rawValue().toDouble(), _northingFact.rawValue().toDouble(), _zoneFact.rawValue().toInt(), _hemisphereFact.rawValue().toInt() == 1, _coordinate)) { - qDebug() << _eastingFact.rawValue().toDouble() << _northingFact.rawValue().toDouble() << _zoneFact.rawValue().toInt() << (_hemisphereFact.rawValue().toInt() == 1) << _coordinate; + // qCDebug() << _eastingFact->rawValue().toDouble() << _northingFact->rawValue().toDouble() << _zoneFact->rawValue().toInt() << (_hemisphereFact->rawValue().toInt() == 1); + if (QGCGeo::convertUTMToGeo(_eastingFact->rawValue().toDouble(), _northingFact->rawValue().toDouble(), _zoneFact->rawValue().toInt(), _hemisphereFact->rawValue().toInt() == 1, _coordinate)) { + // qCDebug() << _eastingFact->rawValue().toDouble() << _northingFact->rawValue().toDouble() << _zoneFact->rawValue().toInt() << (_hemisphereFact->rawValue().toInt() == 1) << _coordinate; emit coordinateChanged(_coordinate); } else { initValues(); } } -void EditPositionDialogController::setFromMGRS(void) +void EditPositionDialogController::setFromMGRS() { - if (QGCGeo::convertMGRSToGeo(_mgrsFact.rawValue().toString(), _coordinate)) { + if (QGCGeo::convertMGRSToGeo(_mgrsFact->rawValue().toString(), _coordinate)) { emit coordinateChanged(_coordinate); } else { initValues(); } } -void EditPositionDialogController::setFromVehicle(void) +void EditPositionDialogController::setFromVehicle() { _coordinate = qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->coordinate(); emit coordinateChanged(_coordinate); diff --git a/src/QmlControls/EditPositionDialogController.h b/src/QmlControls/EditPositionDialogController.h index 2b41856b5f3a..c7266154ed6c 100644 --- a/src/QmlControls/EditPositionDialogController.h +++ b/src/QmlControls/EditPositionDialogController.h @@ -17,10 +17,6 @@ class EditPositionDialogController : public QObject { Q_OBJECT - -public: - EditPositionDialogController(void); - Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) Q_PROPERTY(Fact* latitude READ latitude CONSTANT) Q_PROPERTY(Fact* longitude READ longitude CONSTANT) @@ -30,44 +26,48 @@ class EditPositionDialogController : public QObject Q_PROPERTY(Fact* northing READ northing CONSTANT) Q_PROPERTY(Fact* mgrs READ mgrs CONSTANT) - QGeoCoordinate coordinate(void) const { return _coordinate; } - Fact* latitude (void) { return &_latitudeFact; } - Fact* longitude (void) { return &_longitudeFact; } - Fact* zone (void) { return &_zoneFact; } - Fact* hemisphere(void) { return &_hemisphereFact; } - Fact* easting (void) { return &_eastingFact; } - Fact* northing (void) { return &_northingFact; } - Fact* mgrs (void) { return &_mgrsFact; } +public: + EditPositionDialogController(QObject *parent = nullptr); + ~EditPositionDialogController(); + + Q_INVOKABLE void initValues(); + Q_INVOKABLE void setFromGeo(); + Q_INVOKABLE void setFromUTM(); + Q_INVOKABLE void setFromMGRS(); + Q_INVOKABLE void setFromVehicle(); void setCoordinate(QGeoCoordinate coordinate); + QGeoCoordinate coordinate() const { return _coordinate; } - Q_INVOKABLE void initValues(void); - Q_INVOKABLE void setFromGeo(void); - Q_INVOKABLE void setFromUTM(void); - Q_INVOKABLE void setFromMGRS(void); - Q_INVOKABLE void setFromVehicle(void); + Fact *latitude() { return _latitudeFact; } + Fact *longitude() { return _longitudeFact; } + Fact *zone() { return _zoneFact; } + Fact *hemisphere() { return _hemisphereFact; } + Fact *easting() { return _eastingFact; } + Fact *northing() { return _northingFact; } + Fact *mgrs() { return _mgrsFact; } signals: void coordinateChanged(QGeoCoordinate coordinate); private: - static QMap _metaDataMap; - QGeoCoordinate _coordinate; - Fact _latitudeFact; - Fact _longitudeFact; - Fact _zoneFact; - Fact _hemisphereFact; - Fact _eastingFact; - Fact _northingFact; - Fact _mgrsFact; + Fact *_latitudeFact = nullptr; + Fact *_longitudeFact = nullptr; + Fact *_zoneFact = nullptr; + Fact *_hemisphereFact = nullptr; + Fact *_eastingFact = nullptr; + Fact *_northingFact = nullptr; + Fact *_mgrsFact = nullptr; + + static QMap _metaDataMap; - static constexpr const char* _latitudeFactName = "Latitude"; - static constexpr const char* _longitudeFactName = "Longitude"; - static constexpr const char* _zoneFactName = "Zone"; - static constexpr const char* _hemisphereFactName = "Hemisphere"; - static constexpr const char* _eastingFactName = "Easting"; - static constexpr const char* _northingFactName = "Northing"; - static constexpr const char* _mgrsFactName = "MGRS"; + static constexpr const char *_latitudeFactName = "Latitude"; + static constexpr const char *_longitudeFactName = "Longitude"; + static constexpr const char *_zoneFactName = "Zone"; + static constexpr const char *_hemisphereFactName = "Hemisphere"; + static constexpr const char *_eastingFactName = "Easting"; + static constexpr const char *_northingFactName = "Northing"; + static constexpr const char *_mgrsFactName = "MGRS"; }; diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index a2863f402886..daa18b35fe67 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -13,9 +13,12 @@ #include "AppSettings.h" #include "Vehicle.h" -ParameterEditorController::ParameterEditorController(void) - : _parameterMgr(_vehicle->parameterManager()) +ParameterEditorController::ParameterEditorController(QObject *parent) + : FactPanelController(parent) + , _parameterMgr(_vehicle->parameterManager()) { + // qCDebug() << Q_FUNC_INFO << this; + _buildLists(); connect(this, &ParameterEditorController::currentCategoryChanged, this, &ParameterEditorController::_currentCategoryChanged); @@ -31,7 +34,7 @@ ParameterEditorController::ParameterEditorController(void) ParameterEditorController::~ParameterEditorController() { - + // qCDebug() << Q_FUNC_INFO << this; } void ParameterEditorController::_buildListsForComponent(int compId) diff --git a/src/QmlControls/ParameterEditorController.h b/src/QmlControls/ParameterEditorController.h index fd860b227fe1..8922763f278e 100644 --- a/src/QmlControls/ParameterEditorController.h +++ b/src/QmlControls/ParameterEditorController.h @@ -83,11 +83,6 @@ class ParameterEditorDiff : public QObject class ParameterEditorController : public FactPanelController { Q_OBJECT - -public: - ParameterEditorController(void); - ~ParameterEditorController(); - Q_PROPERTY(QString searchText MEMBER _searchText NOTIFY searchTextChanged) Q_PROPERTY(QmlObjectListModel* categories READ categories CONSTANT) Q_PROPERTY(QObject* currentCategory READ currentCategory WRITE setCurrentCategory NOTIFY currentCategoryChanged) @@ -100,6 +95,10 @@ class ParameterEditorController : public FactPanelController Q_PROPERTY(bool diffMultipleComponents MEMBER _diffMultipleComponents NOTIFY diffMultipleComponentsChanged) Q_PROPERTY(QmlObjectListModel* diffList READ diffList CONSTANT) +public: + ParameterEditorController(QObject *parent = nullptr); + ~ParameterEditorController(); + Q_INVOKABLE QStringList searchParameters(const QString& searchText, bool searchInName=true, bool searchInDescriptions=true); Q_INVOKABLE void saveToFile (const QString& filename); diff --git a/src/QmlControls/QGCFileDialogController.cc b/src/QmlControls/QGCFileDialogController.cc index c590ff08150c..6e08e4e1e20a 100644 --- a/src/QmlControls/QGCFileDialogController.cc +++ b/src/QmlControls/QGCFileDialogController.cc @@ -16,6 +16,17 @@ QGC_LOGGING_CATEGORY(QGCFileDialogControllerLog, "QGCFileDialogControllerLog") +QGCFileDialogController::QGCFileDialogController(QObject *parent) + : QObject(parent) +{ + // qCDebug(QGCFileDialogControllerLog) << Q_FUNC_INFO << this; +} + +QGCFileDialogController::~QGCFileDialogController() +{ + // qCDebug(QGCFileDialogControllerLog) << Q_FUNC_INFO << this; +} + QStringList QGCFileDialogController::getFiles(const QString& directoryPath, const QStringList& nameFilters) { qCDebug(QGCFileDialogControllerLog) << "getFiles" << directoryPath << nameFilters; diff --git a/src/QmlControls/QGCFileDialogController.h b/src/QmlControls/QGCFileDialogController.h index 36383b64f822..198be780a47f 100644 --- a/src/QmlControls/QGCFileDialogController.h +++ b/src/QmlControls/QGCFileDialogController.h @@ -21,6 +21,9 @@ class QGCFileDialogController : public QObject Q_OBJECT public: + QGCFileDialogController(QObject *parent= nullptr); + ~QGCFileDialogController(); + /// Return all file in the specified path which match the specified extension Q_INVOKABLE QStringList getFiles(const QString& directoryPath, const QStringList& nameFilters); @@ -30,7 +33,7 @@ class QGCFileDialogController : public QObject /// Check for file existence of specified fully qualified file name Q_INVOKABLE bool fileExists(const QString& filename); - + /// Deletes the file specified by the fully qualified file name Q_INVOKABLE void deleteFile(const QString& filename); diff --git a/src/QmlControls/RCChannelMonitorController.cc b/src/QmlControls/RCChannelMonitorController.cc index df686dcf4055..d30f19bbf6d6 100644 --- a/src/QmlControls/RCChannelMonitorController.cc +++ b/src/QmlControls/RCChannelMonitorController.cc @@ -11,16 +11,23 @@ #include "RCChannelMonitorController.h" #include "Vehicle.h" -RCChannelMonitorController::RCChannelMonitorController(void) - : _chanCount(0) +RCChannelMonitorController::RCChannelMonitorController(QObject *parent) + : FactPanelController(parent) { - connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RCChannelMonitorController::_rcChannelsChanged); + // qCDebug() << Q_FUNC_INFO << this; + + (void) connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RCChannelMonitorController::_rcChannelsChanged); +} + +RCChannelMonitorController::~RCChannelMonitorController() +{ + // qCDebug() << Q_FUNC_INFO << this; } void RCChannelMonitorController::_rcChannelsChanged(int channelCount, int pwmValues[QGCMAVLink::maxRcChannels]) { - for (int channel=0; channel RCToParamDialogController::_metaDataMap; -RCToParamDialogController::RCToParamDialogController(void) - : _scaleFact (0, _scaleFactName, FactMetaData::valueTypeDouble) - , _centerFact (0, _centerFactName, FactMetaData::valueTypeDouble) - , _minFact (0, _minFactName, FactMetaData::valueTypeDouble) - , _maxFact (0, _maxFactName, FactMetaData::valueTypeDouble) +RCToParamDialogController::RCToParamDialogController(QObject *parent) + : QObject(parent) + , _scaleFact(new Fact(0, _scaleFactName, FactMetaData::valueTypeDouble, this)) + , _centerFact(new Fact(0, _centerFactName, FactMetaData::valueTypeDouble, this)) + , _minFact(new Fact(0, _minFactName, FactMetaData::valueTypeDouble, this)) + , _maxFact(new Fact(0, _maxFactName, FactMetaData::valueTypeDouble, this)) { + // qCDebug() << Q_FUNC_INFO << this; + if (_metaDataMap.isEmpty()) { _metaDataMap = FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/RCToParamDialog.FactMetaData.json"), nullptr /* QObject parent */); } - _scaleFact.setMetaData (_metaDataMap[_scaleFactName], true /* setDefaultFromMetaData */); - _centerFact.setMetaData (_metaDataMap[_centerFactName]); - _minFact.setMetaData (_metaDataMap[_minFactName]); - _maxFact.setMetaData (_metaDataMap[_maxFactName]); + _scaleFact->setMetaData(_metaDataMap[_scaleFactName], true /* setDefaultFromMetaData */); + _centerFact->setMetaData(_metaDataMap[_centerFactName]); + _minFact->setMetaData(_metaDataMap[_minFactName]); + _maxFact->setMetaData(_metaDataMap[_maxFactName]); +} + +RCToParamDialogController::~RCToParamDialogController() +{ + // qCDebug() << Q_FUNC_INFO << this;` } -void RCToParamDialogController::setTuningFact(Fact* tuningFact) +void RCToParamDialogController::setTuningFact(Fact *tuningFact) { _tuningFact = tuningFact; emit tuningFactChanged(tuningFact); - _centerFact.setRawValue(_tuningFact->rawValue().toDouble()); - _minFact.setRawValue(_tuningFact->rawMin().toDouble()); - _maxFact.setRawValue(_tuningFact->rawMax().toDouble()); + _centerFact->setRawValue(_tuningFact->rawValue().toDouble()); + _minFact->setRawValue(_tuningFact->rawMin().toDouble()); + _maxFact->setRawValue(_tuningFact->rawMax().toDouble()); - connect(_tuningFact, &Fact::vehicleUpdated, this, &RCToParamDialogController::_parameterUpdated); + (void) connect(_tuningFact, &Fact::vehicleUpdated, this, &RCToParamDialogController::_parameterUpdated); qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->parameterManager()->refreshParameter(ParameterManager::defaultComponentId, _tuningFact->name()); } -void RCToParamDialogController::_parameterUpdated(void) +void RCToParamDialogController::_parameterUpdated() { _ready = true; emit readyChanged(true); diff --git a/src/QmlControls/RCToParamDialogController.h b/src/QmlControls/RCToParamDialogController.h index 4d9318185f45..11361f2b1f90 100644 --- a/src/QmlControls/RCToParamDialogController.h +++ b/src/QmlControls/RCToParamDialogController.h @@ -16,43 +16,43 @@ class RCToParamDialogController : public QObject { Q_OBJECT - -public: - RCToParamDialogController(void); - Q_PROPERTY(Fact* tuningFact READ tuningFact WRITE setTuningFact NOTIFY tuningFactChanged) - Q_PROPERTY(bool ready MEMBER _ready NOTIFY readyChanged) // true: editing can begin, false: still waiting for param update from vehicle Q_PROPERTY(Fact* scale READ scale CONSTANT) Q_PROPERTY(Fact* center READ center CONSTANT) Q_PROPERTY(Fact* min READ min CONSTANT) Q_PROPERTY(Fact* max READ max CONSTANT) + Q_PROPERTY(bool ready MEMBER _ready NOTIFY readyChanged) // true: editing can begin, false: still waiting for param update from vehicle - Fact* tuningFact (void) { return _tuningFact; } - Fact* scale (void) { return &_scaleFact; } - Fact* center (void) { return &_centerFact; } - Fact* min (void) { return &_minFact; } - Fact* max (void) { return &_maxFact; } - void setTuningFact (Fact* tuningFact); +public: + RCToParamDialogController(QObject *parent = nullptr); + ~RCToParamDialogController(); + + Fact *tuningFact() { return _tuningFact; } + Fact *scale() { return _scaleFact; } + Fact *center() { return _centerFact; } + Fact *min() { return _minFact; } + Fact *max() { return _maxFact; } + void setTuningFact(Fact *tuningFact); signals: - void tuningFactChanged (Fact* fact); - void readyChanged (bool ready); + void tuningFactChanged(Fact *fact); + void readyChanged(bool ready); private slots: - void _parameterUpdated(void); + void _parameterUpdated(); private: + Fact *_tuningFact = nullptr; + Fact *_scaleFact = nullptr; + Fact *_centerFact = nullptr; + Fact *_minFact = nullptr; + Fact *_maxFact = nullptr; + bool _ready = false; + static QMap _metaDataMap; - Fact* _tuningFact = nullptr; - bool _ready = false; - Fact _scaleFact; - Fact _centerFact; - Fact _minFact; - Fact _maxFact; - - static constexpr const char* _scaleFactName = "Scale"; - static constexpr const char* _centerFactName = "CenterValue"; - static constexpr const char* _minFactName = "MinValue"; - static constexpr const char* _maxFactName = "MaxValue"; + static constexpr const char *_scaleFactName = "Scale"; + static constexpr const char *_centerFactName = "CenterValue"; + static constexpr const char *_minFactName = "MinValue"; + static constexpr const char *_maxFactName = "MaxValue"; }; diff --git a/src/QmlControls/ScreenToolsController.cc b/src/QmlControls/ScreenToolsController.cc index f33c571854fe..6c3868723eec 100644 --- a/src/QmlControls/ScreenToolsController.cc +++ b/src/QmlControls/ScreenToolsController.cc @@ -23,9 +23,15 @@ #include #endif -ScreenToolsController::ScreenToolsController() +ScreenToolsController::ScreenToolsController(QQuickItem *parent) + : QQuickItem(parent) { + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; +} +ScreenToolsController::~ScreenToolsController() +{ + // qCDebug(AudioOutputLog) << Q_FUNC_INFO << this; } bool diff --git a/src/QmlControls/ScreenToolsController.h b/src/QmlControls/ScreenToolsController.h index 53979bdded6f..1b1473fe8823 100644 --- a/src/QmlControls/ScreenToolsController.h +++ b/src/QmlControls/ScreenToolsController.h @@ -24,9 +24,6 @@ class ScreenToolsController : public QQuickItem { Q_OBJECT -public: - ScreenToolsController(); - Q_PROPERTY(bool isAndroid READ isAndroid CONSTANT) Q_PROPERTY(bool isiOS READ isiOS CONSTANT) Q_PROPERTY(bool isMobile READ isMobile CONSTANT) @@ -41,6 +38,10 @@ class ScreenToolsController : public QQuickItem Q_PROPERTY(QString fixedFontFamily READ fixedFontFamily CONSTANT) Q_PROPERTY(QString normalFontFamily READ normalFontFamily CONSTANT) +public: + ScreenToolsController(QQuickItem *parent = nullptr); + ~ScreenToolsController(); + // Returns current mouse position Q_INVOKABLE int mouseX(void) { return QCursor::pos().x(); } Q_INVOKABLE int mouseY(void) { return QCursor::pos().y(); }