Skip to content

Commit

Permalink
QmlControls: Fix Parenting of Several Classes
Browse files Browse the repository at this point in the history
  • Loading branch information
HTRamsey committed Oct 25, 2024
1 parent 34cdb6b commit 891490c
Show file tree
Hide file tree
Showing 14 changed files with 238 additions and 163 deletions.
37 changes: 36 additions & 1 deletion src/QmlControls/CustomAction.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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]);
Expand Down
60 changes: 27 additions & 33 deletions src/QmlControls/CustomAction.h
Original file line number Diff line number Diff line change
Expand Up @@ -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]{};
};
74 changes: 41 additions & 33 deletions src/QmlControls/EditPositionDialogController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,26 +16,34 @@

QMap<QString, FactMetaData*> 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)
Expand All @@ -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);
Expand Down
66 changes: 33 additions & 33 deletions src/QmlControls/EditPositionDialogController.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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<QString, FactMetaData*> _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<QString, FactMetaData*> _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";
};
9 changes: 6 additions & 3 deletions src/QmlControls/ParameterEditorController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand All @@ -31,7 +34,7 @@ ParameterEditorController::ParameterEditorController(void)

ParameterEditorController::~ParameterEditorController()
{

// qCDebug() << Q_FUNC_INFO << this;
}

void ParameterEditorController::_buildListsForComponent(int compId)
Expand Down
9 changes: 4 additions & 5 deletions src/QmlControls/ParameterEditorController.h
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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);
Expand Down
11 changes: 11 additions & 0 deletions src/QmlControls/QGCFileDialogController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
Loading

0 comments on commit 891490c

Please sign in to comment.