Commit 8da5e19a authored by Valentin Platzgummer's avatar Valentin Platzgummer

measurement works mostly, some smaller issues left

parent 5a5b161e
...@@ -261,19 +261,18 @@ ...@@ -261,19 +261,18 @@
<file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file> <file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/Common/RadioComponent.qml</file> <file alias="RadioComponent.qml">src/AutoPilotPlugins/Common/RadioComponent.qml</file>
<file alias="SerialSettings.qml">src/ui/preferences/SerialSettings.qml</file> <file alias="SerialSettings.qml">src/ui/preferences/SerialSettings.qml</file>
<file alias="CircularGeneratorEditor.qml">src/MeasurementComplexItem/qml/CircularGeneratorEditor.qml</file> <file alias="MeasurementComplexItem/CircularGeneratorEditor.qml">src/MeasurementComplexItem/qml/CircularGeneratorEditor.qml</file>
<file alias="QGroundControl/Controls/CircularGeneratorMapVisual.qml">src/MeasurementComplexItem/qml/CircularGeneratorMapVisual.qml</file> <file alias="QGroundControl/Controls/CircularGeneratorMapVisual.qml">src/MeasurementComplexItem/qml/CircularGeneratorMapVisual.qml</file>
<file alias="MeasurementItemEditor.qml">src/MeasurementComplexItem/qml/MeasurementItemEditor.qml</file> <file alias="MeasurementItemEditor.qml">src/MeasurementComplexItem/qml/MeasurementItemEditor.qml</file>
<file alias="QGroundControl/Controls/MeasurementItemMapVisual.qml">src/MeasurementComplexItem/qml/MeasurementItemMapVisual.qml</file> <file alias="QGroundControl/Controls/MeasurementItemMapVisual.qml">src/MeasurementComplexItem/qml/MeasurementItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/CoordinateIndicator.qml">src/MeasurementComplexItem/qml/CoordinateIndicator.qml</file> <file alias="QGroundControl/Controls/CoordinateIndicator.qml">src/MeasurementComplexItem/qml/CoordinateIndicator.qml</file>
<file alias="QGroundControl/Controls/CoordinateIndicatorDrag.qml">src/MeasurementComplexItem/qml/CoordinateIndicatorDrag.qml</file> <file alias="QGroundControl/Controls/CoordinateIndicatorDrag.qml">src/MeasurementComplexItem/qml/CoordinateIndicatorDrag.qml</file>
<file alias="QGroundControl/Controls/DragCoordinate.qml">src/MeasurementComplexItem/qml/DragCoordinate.qml</file> <file alias="QGroundControl/Controls/DragCoordinate.qml">src/MeasurementComplexItem/qml/DragCoordinate.qml</file>
<file alias="LinearGeneratorEditor.qml">src/MeasurementComplexItem/qml/LinearGeneratorEditor.qml</file> <file alias="MeasurementComplexItem/LinearGeneratorEditor.qml">src/MeasurementComplexItem/qml/LinearGeneratorEditor.qml</file>
<file alias="ProgressIndicator.qml">src/MeasurementComplexItem/qml/ProgressIndicator.qml</file>
<file alias="QGroundControl/Controls/GeoAreaVisualLoader.qml">src/MeasurementComplexItem/qml/GeoAreaVisualLoader.qml</file> <file alias="QGroundControl/Controls/GeoAreaVisualLoader.qml">src/MeasurementComplexItem/qml/GeoAreaVisualLoader.qml</file>
<file alias="MeasurementAreaEditor.qml">src/MeasurementComplexItem/qml/MeasurementAreaEditor.qml</file> <file alias="MeasurementComplexItem/MeasurementAreaEditor.qml">src/MeasurementComplexItem/qml/MeasurementAreaEditor.qml</file>
<file alias="QGroundControl/Controls/MeasurementAreaMapVisual.qml">src/MeasurementComplexItem/qml/MeasurementAreaMapVisual.qml</file> <file alias="QGroundControl/Controls/MeasurementAreaMapVisual.qml">src/MeasurementComplexItem/qml/MeasurementAreaMapVisual.qml</file>
<file alias="SafeAreaEditor.qml">src/MeasurementComplexItem/qml/SafeAreaEditor.qml</file> <file alias="MeasurementComplexItem/SafeAreaEditor.qml">src/MeasurementComplexItem/qml/SafeAreaEditor.qml</file>
<file alias="QGroundControl/Controls/SafeAreaMapVisual.qml">src/MeasurementComplexItem/qml/SafeAreaMapVisual.qml</file> <file alias="QGroundControl/Controls/SafeAreaMapVisual.qml">src/MeasurementComplexItem/qml/SafeAreaMapVisual.qml</file>
<file alias="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file> <file alias="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file>
<file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file> <file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file>
...@@ -290,6 +289,10 @@ ...@@ -290,6 +289,10 @@
<file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file> <file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file>
<file alias="VTOLLandingPatternEditor.qml">src/PlanView/VTOLLandingPatternEditor.qml</file> <file alias="VTOLLandingPatternEditor.qml">src/PlanView/VTOLLandingPatternEditor.qml</file>
<file>src/MeasurementComplexItem/qml/GeoAreaEditorLoader.qml</file> <file>src/MeasurementComplexItem/qml/GeoAreaEditorLoader.qml</file>
<file alias="QGroundControl/Controls/ItemDragger.qml">src/MeasurementComplexItem/qml/ItemDragger.qml</file>
<file alias="MeasurementComplexItem/AreaDataEditor.qml">src/MeasurementComplexItem/qml/AreaDataEditor.qml</file>
<file alias="MeasurementComplexItem/ParameterEditor.qml">src/MeasurementComplexItem/qml/ParameterEditor.qml</file>
<file alias="MeasurementComplexItem/qmldir">src/MeasurementComplexItem/qml/MeasurementComplexItem.qmldir</file>
</qresource> </qresource>
<qresource prefix="/FirstRunPromptDialogs"> <qresource prefix="/FirstRunPromptDialogs">
<file alias="UnitsFirstRunPrompt.qml">src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml</file> <file alias="UnitsFirstRunPrompt.qml">src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml</file>
......
This diff is collapsed.
...@@ -18,6 +18,8 @@ public: ...@@ -18,6 +18,8 @@ public:
AreaData &operator=(const AreaData &other); AreaData &operator=(const AreaData &other);
Q_PROPERTY(QmlObjectListModel *areaList READ areaList NOTIFY areaListChanged) Q_PROPERTY(QmlObjectListModel *areaList READ areaList NOTIFY areaListChanged)
Q_PROPERTY(bool showErrorMessages READ showErrorMessages WRITE
setShowErrorMessages NOTIFY showErrorMessagesChanged)
// Member Methodes // Member Methodes
//! //!
...@@ -27,7 +29,8 @@ public: ...@@ -27,7 +29,8 @@ public:
//! //!
//! \brief remove //! \brief remove
//! \param areaData Removes the area. //! \param areaData Removes the area.
//! \note Deletes the area if it has no parent. //! \note Deletes the area if it has either no parent or the parent is this
//! object.
void remove(GeoArea *areaData); void remove(GeoArea *areaData);
void clear(); void clear();
//! //!
...@@ -46,8 +49,7 @@ public: ...@@ -46,8 +49,7 @@ public:
//! \note Origin might change if the list of areas changes. //! \note Origin might change if the list of areas changes.
const QGeoCoordinate &origin() const; const QGeoCoordinate &origin() const;
Q_INVOKABLE bool isValid() const; Q_INVOKABLE bool isCorrect();
Q_INVOKABLE bool tryMakeValid();
//! //!
//! \brief initialize Initializes the areas in a valid way, such that they //! \brief initialize Initializes the areas in a valid way, such that they
//! area inside the bounding box. \param bottomLeft bottom left corner of the //! area inside the bounding box. \param bottomLeft bottom left corner of the
...@@ -65,18 +67,33 @@ public: ...@@ -65,18 +67,33 @@ public:
//! either. //! either.
//! //!
Q_INVOKABLE bool initialized(); Q_INVOKABLE bool initialized();
Q_INVOKABLE void intersection();
bool operator==(const AreaData &other) const; bool operator==(const AreaData &other) const;
bool operator!=(const AreaData &other) const; bool operator!=(const AreaData &other) const;
QString errorString() const; // Contains a message about the last error.
bool showErrorMessages() const;
void setShowErrorMessages(bool showErrorMessages);
signals: signals:
void areaListChanged(); void areaListChanged();
void originChanged(); void originChanged();
void error(); // Emitted if errorString() contains a new message.
void showErrorMessagesChanged();
private slots:
void _updateOrigin();
private: private:
void _setOrigin(const QGeoCoordinate &origin); void _setOrigin(const QGeoCoordinate &origin);
QGeoCoordinate _newOrigin(); void _processError(const QString &str);
bool _areasCorrect();
bool _getAreas(MeasurementArea **measurementArea, SafeArea **safeArea);
QGeoCoordinate _origin; QGeoCoordinate _origin;
QmlObjectListModel _areaList; QmlObjectListModel _areaList;
bool _initialized;
QString _errorString;
bool _showErrorMessages;
}; };
...@@ -62,7 +62,7 @@ QString CircularGenerator::abbreviation() { return QStringLiteral("C. Gen."); } ...@@ -62,7 +62,7 @@ QString CircularGenerator::abbreviation() { return QStringLiteral("C. Gen."); }
bool CircularGenerator::get(Generator &generator) { bool CircularGenerator::get(Generator &generator) {
if (this->_d) { if (this->_d) {
if (this->_d->isValid()) { if (this->_d->isCorrect()) {
// Prepare data. // Prepare data.
auto origin = this->_d->origin(); auto origin = this->_d->origin();
origin.setAltitude(0); origin.setAltitude(0);
...@@ -200,7 +200,7 @@ void CircularGenerator::resetReference() { ...@@ -200,7 +200,7 @@ void CircularGenerator::resetReference() {
} }
void CircularGenerator::establishConnections() { void CircularGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) { if (this->_d != nullptr && !this->_connectionsEstablished) {
auto measurementArea = auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList()); getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList()); auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
...@@ -233,7 +233,7 @@ void CircularGenerator::establishConnections() { ...@@ -233,7 +233,7 @@ void CircularGenerator::establishConnections() {
} }
void CircularGenerator::deleteConnections() { void CircularGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) { if (this->_d != nullptr && this->_connectionsEstablished) {
auto measurementArea = auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList()); getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList()); auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......
...@@ -8,16 +8,26 @@ GeneratorBase::GeneratorBase(QObject *parent) ...@@ -8,16 +8,26 @@ GeneratorBase::GeneratorBase(QObject *parent)
GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent) GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent)
: QObject(parent), _d(d) { : QObject(parent), _d(d) {
establishConnections(); establishConnections();
connect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
} }
GeneratorBase::~GeneratorBase() {} GeneratorBase::~GeneratorBase() {}
GeneratorBase::Data GeneratorBase::data() const { return _d; } GeneratorBase::Data GeneratorBase::data() const { return _d; }
void GeneratorBase::setData(const Data &d) { void GeneratorBase::setData(Data d) {
deleteConnections(); if (d != nullptr) {
_d = d; if (_d != nullptr) {
establishConnections(); disconnect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
}
deleteConnections();
_d = d;
establishConnections();
connect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
}
} }
void GeneratorBase::establishConnections() {} void GeneratorBase::establishConnections() {}
...@@ -27,6 +37,7 @@ void GeneratorBase::deleteConnections() {} ...@@ -27,6 +37,7 @@ void GeneratorBase::deleteConnections() {}
void GeneratorBase::_areaListChangedHandler() { void GeneratorBase::_areaListChangedHandler() {
deleteConnections(); deleteConnections();
establishConnections(); establishConnections();
emit generatorChanged();
} }
} // namespace routing } // namespace routing
...@@ -33,7 +33,7 @@ public: ...@@ -33,7 +33,7 @@ public:
virtual bool get(Generator &generator) = 0; virtual bool get(Generator &generator) = 0;
Data data() const; Data data() const;
void setData(const Data &d); void setData(Data d);
signals: signals:
void generatorChanged(); void generatorChanged();
......
...@@ -48,7 +48,7 @@ QString LinearGenerator::abbreviation() { return QStringLiteral("L. Gen."); } ...@@ -48,7 +48,7 @@ QString LinearGenerator::abbreviation() { return QStringLiteral("L. Gen."); }
bool LinearGenerator::get(Generator &generator) { bool LinearGenerator::get(Generator &generator) {
if (_d) { if (_d) {
if (this->_d->isValid()) { if (this->_d->isCorrect()) {
// Prepare data. // Prepare data.
auto origin = this->_d->origin(); auto origin = this->_d->origin();
origin.setAltitude(0); origin.setAltitude(0);
...@@ -148,7 +148,7 @@ Fact *LinearGenerator::alpha() { return &_alpha; } ...@@ -148,7 +148,7 @@ Fact *LinearGenerator::alpha() { return &_alpha; }
Fact *LinearGenerator::minLength() { return &_minLength; } Fact *LinearGenerator::minLength() { return &_minLength; }
void LinearGenerator::establishConnections() { void LinearGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) { if (this->_d != nullptr && !this->_connectionsEstablished) {
auto measurementArea = auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList()); getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList()); auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
...@@ -178,7 +178,7 @@ void LinearGenerator::establishConnections() { ...@@ -178,7 +178,7 @@ void LinearGenerator::establishConnections() {
} }
void LinearGenerator::deleteConnections() { void LinearGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) { if (this->_d != nullptr && this->_connectionsEstablished) {
auto measurementArea = auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList()); getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList()); auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......
...@@ -376,72 +376,76 @@ void MeasurementComplexItem::_setAreaData( ...@@ -376,72 +376,76 @@ void MeasurementComplexItem::_setAreaData(
} }
} }
bool MeasurementComplexItem::_updateRoute() { void MeasurementComplexItem::_updateRoute() {
// Reset data. if (!editing()) {
this->_route.clear(); // Reset data.
this->_variantVector.clear(); this->_route.clear();
this->_variantNames.clear(); this->_variantVector.clear();
emit variantNamesChanged(); this->_variantNames.clear();
emit variantNamesChanged();
if (this->_pAreaData->isValid()) {
if (this->_pAreaData->isCorrect()) {
// Prepare data.
auto origin = this->_pAreaData->origin(); // Prepare data.
origin.setAltitude(0); auto origin = this->_pAreaData->origin();
if (!origin.isValid()) { origin.setAltitude(0);
qCDebug(MeasurementComplexItemLog) if (!origin.isValid()) {
<< "_updateWorker(): origin invalid." << origin;
return false;
}
// Convert safe area.
auto serviceArea =
getGeoArea<const SafeArea *>(*this->_pAreaData->areaList());
auto geoSafeArea = serviceArea->coordinateList();
if (!(geoSafeArea.size() >= 3)) {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea;
return false;
}
for (auto &v : geoSafeArea) {
if (v.isValid()) {
v.setAltitude(0);
} else {
qCDebug(MeasurementComplexItemLog) qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area contains invalid coordinate." << "_updateWorker(): origin invalid." << origin;
<< geoSafeArea; return;
return false;
} }
}
// Routing par. // Convert safe area.
RoutingParameter par; auto serviceArea =
par.numSolutions = 5; getGeoArea<const SafeArea *>(*this->_pAreaData->areaList());
auto &safeAreaENU = par.safeArea; auto geoSafeArea = serviceArea->coordinateList();
snake::areaToEnu(origin, geoSafeArea, safeAreaENU); if (!(geoSafeArea.size() >= 3)) {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea;
return;
}
for (auto &v : geoSafeArea) {
if (v.isValid()) {
v.setAltitude(0);
} else {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area contains invalid coordinate."
<< geoSafeArea;
return;
}
}
// Create generator. // Routing par.
if (this->_pGenerator != nullptr) { RoutingParameter par;
routing::GeneratorBase::Generator g; // Transect generator. par.numSolutions = 5;
if (this->_pGenerator->get(g)) { auto &safeAreaENU = par.safeArea;
// Start/Restart routing worker. snake::areaToEnu(origin, geoSafeArea, safeAreaENU);
this->_pWorker->route(par, g);
return true; // Create generator.
if (this->_pGenerator != nullptr) {
routing::GeneratorBase::Generator g; // Transect generator.
if (this->_pGenerator->get(g)) {
// Start/Restart routing worker.
this->_pWorker->route(par, g);
_setState(STATE::ROUTING);
return;
} else {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): generator creation failed.";
return;
}
} else { } else {
qCDebug(MeasurementComplexItemLog) qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): generator creation failed."; << "_updateWorker(): pGenerator == nullptr, number of registered "
return false; "generators: "
<< this->_generatorList.size();
return;
} }
} else { } else {
qCDebug(MeasurementComplexItemLog) qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): pGenerator == nullptr, number of registered " << "_updateWorker(): plan data invalid.";
"generators: " return;
<< this->_generatorList.size();
return false;
} }
} else {
qCDebug(MeasurementComplexItemLog) << "_updateWorker(): plan data invalid.";
return false;
} }
} }
...@@ -471,7 +475,7 @@ void MeasurementComplexItem::_changeVariant() { ...@@ -471,7 +475,7 @@ void MeasurementComplexItem::_changeVariant() {
} }
auto &newVariantCoordinates = this->_variantVector[variant]; auto &newVariantCoordinates = this->_variantVector[variant];
this->_route.swap(newVariantCoordinates); this->_route.swap(newVariantCoordinates);
emit routeChanged();
} else { // error } else { // error
qCDebug(MeasurementComplexItemLog) qCDebug(MeasurementComplexItemLog)
<< "Variant out of bounds (variant =" << variant << ")."; << "Variant out of bounds (variant =" << variant << ").";
...@@ -497,6 +501,7 @@ void MeasurementComplexItem::_reverseRoute() { ...@@ -497,6 +501,7 @@ void MeasurementComplexItem::_reverseRoute() {
auto &t = this->_route; auto &t = this->_route;
std::reverse(t.begin(), t.end()); std::reverse(t.begin(), t.end());
} }
emit routeChanged();
} }
} }
...@@ -661,27 +666,35 @@ int MeasurementComplexItem::generatorIndex() { ...@@ -661,27 +666,35 @@ int MeasurementComplexItem::generatorIndex() {
return this->_generatorList.indexOf(this->_pGenerator); return this->_generatorList.indexOf(this->_pGenerator);
} }
void MeasurementComplexItem::editingStart() { void MeasurementComplexItem::startEditing() {
if (!_editing(this->_state)) { if (!editing()) {
*_pEditorData = *_pAreaData; *_pEditorData = *_pAreaData;
_setAreaData(_pEditorData); _setAreaData(_pEditorData);
_setState(STATE::EDITING); _setState(STATE::EDITING);
} }
} }
void MeasurementComplexItem::editingStop() { void MeasurementComplexItem::stopEditing() {
if (_editing(this->_state)) { if (editing()) {
if (_pEditorData->isValid()) { bool correct = _pEditorData->isCorrect();
if (correct) {
*_pAreaData = *_pEditorData; *_pAreaData = *_pEditorData;
} }
_setAreaData(_pAreaData); _setAreaData(_pAreaData);
_setState(STATE::IDLE); _setState(STATE::IDLE);
if (_pEditorData->isValid() && *_pEditorData != *_pAreaData) { if (correct && *_pEditorData != *_pAreaData) {
_updateRoute(); _updateRoute();
} }
} }
} }
void MeasurementComplexItem::abortEditing() {
if (editing()) {
_setAreaData(_pAreaData);
_setState(STATE::IDLE);
}
}
void MeasurementComplexItem::_storeRoutingData( void MeasurementComplexItem::_storeRoutingData(
MeasurementComplexItem::PtrRoutingData pRoute) { MeasurementComplexItem::PtrRoutingData pRoute) {
if (this->_state == STATE::ROUTING) { if (this->_state == STATE::ROUTING) {
...@@ -781,10 +794,11 @@ void MeasurementComplexItem::_storeRoutingData( ...@@ -781,10 +794,11 @@ void MeasurementComplexItem::_storeRoutingData(
this->_variant.setCookedValue(QVariant(0)); this->_variant.setCookedValue(QVariant(0));
connect(&this->_variant, &Fact::rawValueChanged, this, connect(&this->_variant, &Fact::rawValueChanged, this,
&MeasurementComplexItem::_changeVariant); &MeasurementComplexItem::_changeVariant);
this->_changeVariant();
this->_setState(STATE::IDLE); this->_route.swap(this->_variantVector.first());
emit routeChanged(); emit routeChanged();
this->_setState(STATE::IDLE);
} else { } else {
qCDebug(MeasurementComplexItemLog) qCDebug(MeasurementComplexItemLog)
<< "_setTransects(): failed, variantVector empty."; << "_setTransects(): failed, variantVector empty.";
......
...@@ -105,19 +105,26 @@ public: ...@@ -105,19 +105,26 @@ public:
// Editing. // Editing.
//! //!
//! \brief editingStart Starts area data editing. //! \brief startEditing Starts area data editing.
//! //!
//! Starts area data editing. Route will not be updated bewteen a call //! Starts area data editing. Route will not be updated bewteen a call
//! sequence of editingStart() and editingStop(). //! sequence of editingStart() and editingStop().
//! //!
void editingStart(); Q_INVOKABLE void startEditing();
//! //!
//! \brief editingStop Stops area editing. //! \brief stopEditing Stops area editing.
//! //!
//! Stops area editing. Will reset area data to the state before //! Stops area editing. Will reset area data to the state before
//! editingStart() if it is invalid. Triggers a route update. //! editingStart() if it is invalid. Triggers a route update.
//! //!
void editingStop(); Q_INVOKABLE void stopEditing();
//!
//! \brief abortEditing Aborts area editing.
//!
//! Will reset area data to the state before
//! editingStart().
//!
Q_INVOKABLE void abortEditing();
// Property getters // Property getters
const AreaData *areaData() const; const AreaData *areaData() const;
...@@ -156,7 +163,7 @@ private slots: ...@@ -156,7 +163,7 @@ private slots:
// Worker functions. // Worker functions.
void _storeRoutingData(PtrRoutingData pRoute); void _storeRoutingData(PtrRoutingData pRoute);
bool _updateRoute(); void _updateRoute();
void _changeVariant(); void _changeVariant();
void _reverseRoute(); void _reverseRoute();
......
This diff is collapsed.
#pragma once
#include "QmlObjectListModel.h"
#include <QObject>
#include <QScopedPointer>
#include <QSharedPointer>
#include "Geometry/WimaCorridor.h"
#include "Geometry/WimaCorridorData.h"
#include "Geometry/WimaJoinedArea.h"
#include "Geometry/WimaJoinedAreaData.h"
#include "Geometry/WimaMeasurementArea.h"
#include "Geometry/WimaMeasurementAreaData.h"
#include "Geometry/WimaServiceArea.h"
#include "Geometry/WimaServiceAreaData.h"
#include "WimaPlanData.h"
#include "Snake/NemoInterface.h"
#include "JsonHelper.h"
class MissionController;
class PlanMasterController;
namespace wima_planer_detail {
class WimaStateMachine;
}
class WimaPlaner : public QObject {
Q_OBJECT
enum FileType { WimaFile, PlanFile };
public:
WimaPlaner(QObject *parent = nullptr);
~WimaPlaner();
template <class T> WimaPlaner(T t, QObject *parent = nullptr) = delete;
template <class T> WimaPlaner(T t) = delete;
Q_PROPERTY(PlanMasterController *masterController READ masterController WRITE
setMasterController NOTIFY masterControllerChanged)
Q_PROPERTY(MissionController *missionController READ missionController WRITE
setMissionController NOTIFY missionControllerChanged)
Q_PROPERTY(QmlObjectListModel *visualItems READ visualItems NOTIFY
visualItemsChanged)
Q_PROPERTY(int currentPolygonIndex READ currentPolygonIndex WRITE
setCurrentPolygonIndex NOTIFY currentPolygonIndexChanged)
Q_PROPERTY(QString currentFile READ currentFile NOTIFY currentFileChanged)
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT)
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT)
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
Q_PROPERTY(QGeoCoordinate joinedAreaCenter READ joinedAreaCenter CONSTANT)
Q_PROPERTY(NemoInterface *nemoInterface READ nemoInterface CONSTANT)
Q_PROPERTY(bool synchronized READ synchronized NOTIFY synchronizedChanged)
Q_PROPERTY(bool needsUpdate READ needsUpdate NOTIFY needsUpdateChanged)
Q_PROPERTY(bool readyForSynchronization READ readyForSynchronization NOTIFY
readyForSynchronizationChanged)
Q_PROPERTY(bool surveyReady READ surveyReady NOTIFY surveyReadyChanged)
Q_PROPERTY(bool progressLocked READ progressLocked WRITE setProgressLocked
NOTIFY progressLockedChanged)
// Property accessors
PlanMasterController *masterController(void);
MissionController *missionController(void);
QmlObjectListModel *visualItems(void);
int currentPolygonIndex(void) const;
QString currentFile(void) const;
QStringList loadNameFilters(void) const;
QStringList saveNameFilters(void) const;
QString fileExtension(void) const;
QGeoCoordinate joinedAreaCenter(void) const;
NemoInterface *nemoInterface(void);
bool synchronized();
bool needsUpdate();
bool readyForSynchronization();
bool surveyReady();
bool progressLocked();
// Property setters
void setMasterController(PlanMasterController *masterController);
void setMissionController(MissionController *missionController);
/// Sets the integer index pointing to the current polygon. Current polygon is
/// set interactive.
void setCurrentPolygonIndex(int index);
void setProgressLocked(bool l);
Q_INVOKABLE bool addMeasurementArea();
/// Removes an area from _visualItems
/// @param index Index of the area to be removed
Q_INVOKABLE void removeArea(int index);
Q_INVOKABLE bool addServiceArea();
Q_INVOKABLE bool addCorridor();
/// Remove all areas from WimaPlaner and all mission items from
/// MissionController
Q_INVOKABLE void removeAll();
/// Recalculates vehicle corridor, flight path, etc.
Q_INVOKABLE void update();
/// Pushes the generated mission data to the wimaController.
Q_INVOKABLE void synchronize();
Q_INVOKABLE void saveToCurrent();
Q_INVOKABLE void saveToFile(const QString &filename);
Q_INVOKABLE bool loadFromCurrent();
Q_INVOKABLE bool loadFromFile(const QString &filename);
Q_INVOKABLE void resetAllInteractive(void);
Q_INVOKABLE void setInteractive(void);
QJsonDocument saveToJson(FileType fileType);
// static Members
static const char *wimaFileExtension;
static const char *areaItemsName;
static const char *missionItemsName;
signals:
void masterControllerChanged(void);
void missionControllerChanged(void);
void visualItemsChanged(void);
void currentPolygonIndexChanged(int index);
void currentFileChanged();
void wimaBridgeChanged();
void synchronizedChanged(void);
void needsUpdateChanged(void);
void readyForSynchronizationChanged(void);
void surveyReadyChanged(void);
void progressLockedChanged();
private slots:
void updatePolygonInteractivity(int index);
void _update();
void CSDestroyedHandler();
void CSVisualTransectPointsChangedHandler();
void mAreaPathChangedHandler();
void mAreaTilesChangedHandler();
void mAreaProgressChangedHandler();
void mAreaProgressAcceptedHandler();
void mAreaReadyChangedHandler();
void sAreaPathChangedHandler();
void corridorPathChangedHandler();
void depotChangedHandler();
void missionControllerVisualItemsChangedHandler();
void missionControllerWaypointPathChangedHandler();
void missionControllerNewItemsFromVehicleHandler();
void missionControllerMissionItemCountChangedHandler();
void nemoInterfaceProgressChangedHandler();
#ifndef NDEBUG
void autoLoadMission(void);
#endif
private:
signals:
void joinedAreaValidChanged();
void stateChanged();
private:
// Member Functions
bool toPlanData(AreaData &planData);
bool shortestPath(const QGeoCoordinate &start,
const QGeoCoordinate &destination,
QVector<QGeoCoordinate> &path);
void setSynchronized(bool s);
void enableAreaMonitoring();
void disableAreaMonitoring();
void enableMissionControllerMonitoring();
void disableMissionControllerMonitoring();
bool areasMonitored();
bool missionControllerMonitored();
// Member Variables
PlanMasterController *_masterController;
MissionController *_missionController;
int _currentAreaIndex;
QString _currentFile;
WimaMeasurementArea _measurementArea;
WimaServiceArea _serviceArea;
WimaCorridor _corridor;
WimaJoinedArea _joinedArea;
QmlObjectListModel _visualItems; // all areas
CircularSurvey *_survey;
#ifndef NDEBUG
QTimer _autoLoadTimer; // timer to auto load mission after some time, prevents
// seg. faults
#endif
NemoInterface _nemoInterface;
// State
QScopedPointer<wima_planer_detail::WimaStateMachine> _stateMachine;
bool _areasMonitored;
bool _missionControllerMonitored;
bool _progressLocked;
bool _synchronized; // true if planData is synchronized with
// wimaController
};
This diff is collapsed.
#pragma once
#include <QDataStream>
#include <QObject>
namespace wima_planer_detail {
enum class STATE {
NEEDS_INIT,
WAITING_FOR_TILE_UPDATE,
NEEDS_J_AREA_UPDATE,
NEEDS_SURVEY_UPDATE,
WAITING_FOR_SURVEY_UPDATE,
NEEDS_PATH_UPDATE,
UP_TO_DATE
};
QDebug &operator<<(QDebug &ds, STATE s);
enum class EVENT {
INIT_DONE,
M_AREA_NOT_READY,
M_AREA_READY,
M_AREA_PATH_CHANGED,
S_AREA_PATH_CHANGED,
CORRIDOR_PATH_CHANGED,
M_AREA_TILES_CHANGED,
M_AREA_PROGRESS_CHANGED,
J_AREA_UPDATED,
DEPOT_CHANGED,
SURVEY_DESTROYED,
MISSION_ITEMS_DESTROYED,
SURVEY_UPDATE_TRIGGERED,
SURVEY_UPDATED,
PATH_CHANGED,
PATH_UPDATED
};
QDebug &operator<<(QDebug &ds, EVENT s);
class WimaStateMachine : public QObject {
Q_OBJECT
public:
explicit WimaStateMachine(QObject *parent = nullptr);
STATE state();
void updateState(EVENT e);
bool upToDate();
bool surveyReady();
signals:
void stateChanged();
void upToDateChanged();
void surveyReadyChanged();
private:
void setState(STATE s);
bool surveyReady(STATE s);
bool upToDate(STATE s);
STATE _state;
};
} // namespace wima_planer_detail
#include "GeoArea.h" #include "GeoArea.h"
#include "snake.h"
#include "QGCLoggingCategory.h"
#include "QGCQGeoCoordinate.h"
#include <QDebug> #include <QDebug>
QGC_LOGGING_CATEGORY(GeoAreaLog, "GeoAreaLog")
const char *GeoArea::wimaAreaName = "GeoArea"; const char *GeoArea::wimaAreaName = "GeoArea";
const char *GeoArea::areaTypeName = "AreaType"; const char *GeoArea::areaTypeName = "AreaType";
const char *GeoArea::settingsGroup = "GeoArea"; const char *GeoArea::settingsGroup = "GeoArea";
...@@ -10,7 +17,7 @@ const char *GeoArea::settingsGroup = "GeoArea"; ...@@ -10,7 +17,7 @@ const char *GeoArea::settingsGroup = "GeoArea";
GeoArea::GeoArea(QObject *parent) : QGCMapPolygon(parent) { init(); } GeoArea::GeoArea(QObject *parent) : QGCMapPolygon(parent) { init(); }
GeoArea::GeoArea(const GeoArea &other, QObject *parent) GeoArea::GeoArea(const GeoArea &other, QObject *parent)
: QGCMapPolygon(other, parent) { : QGCMapPolygon(other, parent), _errorString(other._errorString) {
init(); init();
} }
...@@ -34,13 +41,40 @@ bool GeoArea::loadFromJson(const QJsonObject &json, QString &errorString) { ...@@ -34,13 +41,40 @@ bool GeoArea::loadFromJson(const QJsonObject &json, QString &errorString) {
return true; return true;
} }
bool GeoArea::isSimplePolygon() { bool GeoArea::isCorrect() {
qWarning() << "WimaArea::isSimplePolygon: impl. missing."; if (this->pathModel().count() >= 3) {
auto origin = this->pathModel().value<QGCQGeoCoordinate *>(0)->coordinate();
snake::FPolygon polygonENU;
snake::areaToEnu(origin, this->pathModel(), polygonENU);
std::string msg;
if (bg::is_valid(polygonENU, msg)) {
return true;
} else {
qCWarning(GeoAreaLog) << msg.c_str();
qCWarning(GeoAreaLog) << "origin: " << origin;
std::stringstream ss;
ss << bg::wkt(polygonENU);
qCWarning(GeoAreaLog) << "polygonENU: " << ss.str().c_str();
setErrorString(tr("Area invalid. Area must be a simple polygon."));
}
}
return false; return false;
} }
QString GeoArea::errorString() const { return this->_errorString; }
void GeoArea::init() { this->setObjectName(wimaAreaName); } void GeoArea::init() { this->setObjectName(wimaAreaName); }
void GeoArea::setErrorString(const QString &str) {
this->_errorString = str;
emit errorStringChanged();
}
void GeoArea::setErrorString(const string &str) {
this->_errorString = str.c_str();
emit errorStringChanged();
}
bool copyAreaList(const QmlObjectListModel &from, QmlObjectListModel &to, bool copyAreaList(const QmlObjectListModel &from, QmlObjectListModel &to,
QObject *parent) { QObject *parent) {
// Check if elements are valid. // Check if elements are valid.
......
...@@ -13,6 +13,7 @@ public: ...@@ -13,6 +13,7 @@ public:
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT)
Q_PROPERTY(QString editorQML READ editorQML CONSTANT) Q_PROPERTY(QString editorQML READ editorQML CONSTANT)
Q_PROPERTY(QString errorString READ errorString NOTIFY errorStringChanged)
virtual QString mapVisualQML(void) const = 0; virtual QString mapVisualQML(void) const = 0;
virtual QString editorQML(void) const = 0; virtual QString editorQML(void) const = 0;
...@@ -23,15 +24,25 @@ public: ...@@ -23,15 +24,25 @@ public:
virtual GeoArea *clone(QObject *parent = nullptr) const = 0; virtual GeoArea *clone(QObject *parent = nullptr) const = 0;
bool isSimplePolygon(); Q_INVOKABLE virtual bool isCorrect();
Q_INVOKABLE QString errorString() const;
// static Members // static Members
static const char *wimaAreaName; static const char *wimaAreaName;
static const char *areaTypeName; static const char *areaTypeName;
static const char *settingsGroup; static const char *settingsGroup;
signals:
void errorStringChanged();
protected:
void setErrorString(const QString &str);
void setErrorString(const std::string &str);
private: private:
void init(); void init();
QString _errorString;
}; };
// Example usage: // Example usage:
......
...@@ -91,7 +91,7 @@ MeasurementArea::MeasurementArea(QObject *parent) ...@@ -91,7 +91,7 @@ MeasurementArea::MeasurementArea(QObject *parent)
MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent) MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent)
: GeoArea(other, parent), : GeoArea(other, parent),
_metaDataMap(FactMetaData::createMapFromJsonFile( _metaDataMap(FactMetaData::createMapFromJsonFile(
QStringLiteral(":/json/WimaMeasurementArea.SettingsGroup.json"), QStringLiteral(":/json/MeasurementArea.SettingsGroup.json"),
this /* QObject parent */)), this /* QObject parent */)),
_tileHeight(SettingsFact(settingsGroup, _metaDataMap[tileHeightName], _tileHeight(SettingsFact(settingsGroup, _metaDataMap[tileHeightName],
this /* QObject parent */)), this /* QObject parent */)),
...@@ -103,6 +103,13 @@ MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent) ...@@ -103,6 +103,13 @@ MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent)
_showTiles(SettingsFact(settingsGroup, _metaDataMap[showTilesName], _showTiles(SettingsFact(settingsGroup, _metaDataMap[showTilesName],
this /* QObject parent */)), this /* QObject parent */)),
_state(STATE::IDLE) { _state(STATE::IDLE) {
_tileHeight = other._tileHeight;
_tileWidth = other._tileWidth;
_minTileAreaPercent = other._minTileAreaPercent;
_showTiles = other._showTiles;
_progress = other._progress;
_tileData = other._tileData;
init(); init();
} }
...@@ -115,6 +122,7 @@ MeasurementArea::~MeasurementArea() {} ...@@ -115,6 +122,7 @@ MeasurementArea::~MeasurementArea() {}
QString MeasurementArea::mapVisualQML() const { QString MeasurementArea::mapVisualQML() const {
return QStringLiteral("MeasurementAreaMapVisual.qml"); return QStringLiteral("MeasurementAreaMapVisual.qml");
// return QStringLiteral("");
} }
QString MeasurementArea::editorQML() const { QString MeasurementArea::editorQML() const {
...@@ -211,6 +219,18 @@ bool MeasurementArea::loadFromJson(const QJsonObject &json, ...@@ -211,6 +219,18 @@ bool MeasurementArea::loadFromJson(const QJsonObject &json,
} }
} }
bool MeasurementArea::isCorrect() {
if (GeoArea::isCorrect()) {
if (ready()) {
return true;
} else {
setErrorString(
tr("Measurement Area tile calculation in progess. Please wait."));
}
}
return false;
}
bool MeasurementArea::setProgress(const QVector<int> &p) { bool MeasurementArea::setProgress(const QVector<int> &p) {
if (ready()) { if (ready()) {
if (p.size() == this->tiles()->count() && this->_progress != p) { if (p.size() == this->tiles()->count() && this->_progress != p) {
...@@ -240,7 +260,7 @@ void MeasurementArea::doUpdate() { ...@@ -240,7 +260,7 @@ void MeasurementArea::doUpdate() {
const auto estNumTiles = totalArea / tileArea; const auto estNumTiles = totalArea / tileArea;
// Check some conditions. // Check some conditions.
if (long(std::ceil(estNumTiles.value())) <= SNAKE_MAX_TILES && if (long(std::ceil(estNumTiles.value())) <= SNAKE_MAX_TILES &&
this->count() >= 3 && this->isSimplePolygon()) { this->GeoArea::isCorrect()) {
setState(STATE::UPDATEING); setState(STATE::UPDATEING);
auto polygon = this->coordinateList(); auto polygon = this->coordinateList();
......
...@@ -50,6 +50,7 @@ public: ...@@ -50,6 +50,7 @@ public:
MeasurementArea *clone(QObject *parent = nullptr) const; MeasurementArea *clone(QObject *parent = nullptr) const;
void saveToJson(QJsonObject &json) override; void saveToJson(QJsonObject &json) override;
bool loadFromJson(const QJsonObject &json, QString &errorString) override; bool loadFromJson(const QJsonObject &json, QString &errorString) override;
Q_INVOKABLE virtual bool isCorrect();
// Property getters. // Property getters.
Fact *tileHeight(); Fact *tileHeight();
......
...@@ -25,7 +25,10 @@ SafeArea &SafeArea::operator=(const SafeArea &other) { ...@@ -25,7 +25,10 @@ SafeArea &SafeArea::operator=(const SafeArea &other) {
return *this; return *this;
} }
QString SafeArea::mapVisualQML() const { return "SafeAreaMapVisual.qml"; } QString SafeArea::mapVisualQML() const {
return "SafeAreaMapVisual.qml";
// return "";
}
QString SafeArea::editorQML() const { return "SafeAreaEditor.qml"; } QString SafeArea::editorQML() const { return "SafeAreaEditor.qml"; }
...@@ -37,11 +40,41 @@ const QGeoCoordinate &SafeArea::depot() const { return _depot; } ...@@ -37,11 +40,41 @@ const QGeoCoordinate &SafeArea::depot() const { return _depot; }
QGeoCoordinate SafeArea::depotQml() const { return _depot; } QGeoCoordinate SafeArea::depotQml() const { return _depot; }
bool SafeArea::setDepot(const QGeoCoordinate &coordinate) { void SafeArea::putDepotInside() {
if (_depot.latitude() != coordinate.latitude() || if (!this->containsCoordinate(this->_depot) &&
_depot.longitude() != coordinate.longitude()) { this->pathModel().count() > 0) {
if (this->containsCoordinate(coordinate)) { if (this->_depot.isValid()) {
_depot = coordinate; // Use nearest coordinate.
auto minDist = std::numeric_limits<double>::infinity();
int minIndex = 0;
for (int idx = 0; idx < this->pathModel().count(); ++idx) {
const QObject *obj = this->pathModel()[idx];
const auto *vertex = qobject_cast<const QGCQGeoCoordinate *>(obj);
if (vertex != nullptr) {
auto d = vertex->coordinate().distanceTo(this->_depot);
if (d < minDist) {
minDist = d;
minIndex = idx;
}
} else {
qCCritical(SafeAreaLog) << "init(): nullptr catched!";
}
}
this->setDepot(
this->pathModel().value<QGCQGeoCoordinate *>(minIndex)->coordinate());
} else {
// Use first coordinate.
this->setDepot(
this->pathModel().value<QGCQGeoCoordinate *>(0)->coordinate());
}
}
}
bool SafeArea::setDepot(const QGeoCoordinate &newDepot) {
if (_depot.latitude() != newDepot.latitude() ||
_depot.longitude() != newDepot.longitude()) {
if (this->containsCoordinate(newDepot)) {
_depot = newDepot;
_depot.setAltitude(0); _depot.setAltitude(0);
emit depotChanged(); emit depotChanged();
return true; return true;
...@@ -89,38 +122,22 @@ bool SafeArea::loadFromJson(const QJsonObject &json, QString &errorString) { ...@@ -89,38 +122,22 @@ bool SafeArea::loadFromJson(const QJsonObject &json, QString &errorString) {
return retVal; return retVal;
} }
void SafeArea::init() { bool SafeArea::isCorrect() {
this->setObjectName(safeAreaName); if (GeoArea::isCorrect()) {
connect(this, &GeoArea::pathChanged, [this] { if (this->_depot.isValid()) {
if (!this->_depot.isValid() || !this->containsCoordinate(this->_depot)) { if (this->containsCoordinate(this->_depot)) {
if (this->containsCoordinate(this->center())) { return true;
// Use center. } else {
this->setDepot(this->center()); setErrorString(tr("Depot outside Safe Area"));
} else if (this->_depot.isValid()) {
// Use nearest coordinate.
auto minDist = std::numeric_limits<double>::infinity();
int minIndex = 0;
for (int idx = 0; idx < this->pathModel().count(); ++idx) {
const QObject *obj = this->pathModel()[idx];
const auto *vertex = qobject_cast<const QGCQGeoCoordinate *>(obj);
if (vertex != nullptr) {
auto d = vertex->coordinate().distanceTo(this->_depot);
if (d < minDist) {
minDist = d;
minIndex = idx;
}
} else {
qCCritical(SafeAreaLog) << "init(): nullptr catched!";
}
}
this->setDepot(this->pathModel()
.value<QGCQGeoCoordinate *>(minIndex)
->coordinate());
} else if (this->pathModel().count() > 0) {
// Use first coordinate.
this->setDepot(
this->pathModel().value<QGCQGeoCoordinate *>(0)->coordinate());
} }
} else {
qCritical(SafeAreaLog) << "Depot invalid " << _depot;
} }
}); }
return false;
}
void SafeArea::init() {
this->setObjectName(safeAreaName);
connect(this, &GeoArea::pathChanged, this, &SafeArea::putDepotInside);
} }
...@@ -13,15 +13,17 @@ public: ...@@ -13,15 +13,17 @@ public:
Q_PROPERTY( Q_PROPERTY(
QGeoCoordinate depot READ depotQml WRITE setDepot NOTIFY depotChanged) QGeoCoordinate depot READ depotQml WRITE setDepot NOTIFY depotChanged)
// Overrides from WimaPolygon // Overrides from GeoArea
QString mapVisualQML(void) const override; QString mapVisualQML(void) const override;
QString editorQML(void) const override; QString editorQML(void) const override;
SafeArea *clone(QObject *parent = nullptr) const; SafeArea *clone(QObject *parent = nullptr) const;
void saveToJson(QJsonObject &json) override; void saveToJson(QJsonObject &json) override;
bool loadFromJson(const QJsonObject &json, QString &errorString) override; bool loadFromJson(const QJsonObject &json, QString &errorString) override;
Q_INVOKABLE virtual bool isCorrect();
// Property acessors // Property acessors
const QGeoCoordinate &depot(void) const; const QGeoCoordinate &depot(void) const;
bool setDepot(const QGeoCoordinate &newDepot);
QGeoCoordinate depotQml(void) const; QGeoCoordinate depotQml(void) const;
// static Members // static Members
...@@ -31,9 +33,8 @@ public: ...@@ -31,9 +33,8 @@ public:
static const char *depotAltitudeName; static const char *depotAltitudeName;
signals: signals:
void depotChanged(void); void depotChanged(void);
private slots:
public slots: void putDepotInside();
bool setDepot(const QGeoCoordinate &coordinate);
private: private:
// Member Methodes // Member Methodes
......
...@@ -5,46 +5,46 @@ ...@@ -5,46 +5,46 @@
[ [
{ {
"name": "TileHeight", "name": "TileHeight",
"shortDescription": "The height of a tile", "shrotDesc": "The height of a tile",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 2, "decimalPlaces": 2,
"defaultValue": 5 "default": 5
}, },
{ {
"name": "TileWidth", "name": "TileWidth",
"shortDescription": "The height of a tile", "shrotDesc": "The height of a tile",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 2, "decimalPlaces": 2,
"defaultValue": 5 "default": 5
}, },
{ {
"name": "MinTileAreaPercent", "name": "MinTileAreaPercent",
"shortDescription": "The minimal allowed area in percent (of width*height).", "shrotDesc": "The minimal allowed area in percent (of width*height).",
"type": "double", "type": "double",
"units": "%", "units": "%",
"min": 0, "min": 0,
"max": 100, "max": 100,
"decimalPlaces": 2, "decimalPlaces": 2,
"defaultValue": 20 "default": 20
}, },
{ {
"name": "ShowTiles", "name": "ShowTiles",
"shortDescription": "Show tiles", "shrotDesc": "Show tiles",
"type": "bool", "type": "bool",
"defaultValue": true "default": true
}, },
{ {
"name": "BorderPolygonOffset", "name": "BorderPolygonOffset",
"shortDescription": "The distance between the measurement area and it's enclosing polygon", "shrotDesc": "The distance between the measurement area and it's enclosing polygon",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0, "min": 0,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5 "default": 5
} }
] ]
} }
...@@ -20,6 +20,9 @@ namespace bu = boost::units; ...@@ -20,6 +20,9 @@ namespace bu = boost::units;
#include <GeographicLib/Geocentric.hpp> #include <GeographicLib/Geocentric.hpp>
#include <GeographicLib/LocalCartesian.hpp> #include <GeographicLib/LocalCartesian.hpp>
#include "QGCQGeoCoordinate.h"
#include "QmlObjectListModel.h"
using namespace std; using namespace std;
namespace snake { namespace snake {
...@@ -105,13 +108,11 @@ template <class GeoPoint1, class GeoPoint2> ...@@ -105,13 +108,11 @@ template <class GeoPoint1, class GeoPoint2>
void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, FPoint &out) { void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, FPoint &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f()); GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
origin.altitude(), earth); earth);
double x = 0, y = 0, z = 0; double x = 0, y = 0, z = 0;
auto alt = in.altitude(); proj.Forward(in.latitude(), in.longitude(), 0, x, y, z);
alt = std::isnan(alt) ? 0 : alt;
proj.Forward(in.latitude(), in.longitude(), alt, x, y, z);
out.set<0>(x); out.set<0>(x);
out.set<1>(y); out.set<1>(y);
(void)z; (void)z;
...@@ -121,13 +122,11 @@ template <class GeoPoint1, class GeoPoint2, class Point> ...@@ -121,13 +122,11 @@ template <class GeoPoint1, class GeoPoint2, class Point>
void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, Point &out) { void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, Point &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f()); GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
origin.altitude(), earth); earth);
double x = 0, y = 0, z = 0; double x = 0, y = 0, z = 0;
auto alt = in.altitude(); proj.Forward(in.latitude(), in.longitude(), 0, x, y, z);
alt = std::isnan(alt) ? 0 : alt;
proj.Forward(in.latitude(), in.longitude(), alt, x, y, z);
out.setX(x); out.setX(x);
out.setY(y); out.setY(y);
(void)z; (void)z;
...@@ -137,8 +136,8 @@ template <class GeoPoint> ...@@ -137,8 +136,8 @@ template <class GeoPoint>
void fromENU(const GeoPoint &origin, const FPoint &in, GeoPoint &out) { void fromENU(const GeoPoint &origin, const FPoint &in, GeoPoint &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(), static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f()); GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
origin.altitude(), earth); earth);
double lat = 0, lon = 0, alt = 0; double lat = 0, lon = 0, alt = 0;
proj.Reverse(in.get<0>(), in.get<1>(), 0.0, lat, lon, alt); proj.Reverse(in.get<0>(), in.get<1>(), 0.0, lat, lon, alt);
...@@ -166,9 +165,26 @@ void areaToEnu(const GeoPoint &origin, const Container &in, FPolygon &out) { ...@@ -166,9 +165,26 @@ void areaToEnu(const GeoPoint &origin, const Container &in, FPolygon &out) {
bg::correct(out); bg::correct(out);
} }
template <class GeoPoint>
void areaToEnu(const GeoPoint &origin, QmlObjectListModel &in, FPolygon &out) {
FPolygon buffer;
for (int i = 0; i < in.count(); ++i) {
auto vertex = in.value<const QGCQGeoCoordinate *>(i);
if (vertex != nullptr) {
FPoint p;
toENU(origin, vertex->coordinate(), p);
buffer.outer().push_back(p);
} else {
return;
}
}
bg::correct(buffer);
out = std::move(buffer);
}
template <class GeoPoint, class Container1, class Container2> template <class GeoPoint, class Container1, class Container2>
void areaFromEnu(const GeoPoint &origin, Container1 &in, void areaFromEnu(const GeoPoint &origin, const Container1 &in,
const Container2 &out) { Container2 &out) {
for (auto &vertex : in) { for (auto &vertex : in) {
typename Container2::value_type p; typename Container2::value_type p;
fromENU(origin, vertex, p); fromENU(origin, vertex, p);
...@@ -177,7 +193,7 @@ void areaFromEnu(const GeoPoint &origin, Container1 &in, ...@@ -177,7 +193,7 @@ void areaFromEnu(const GeoPoint &origin, Container1 &in,
} }
template <class GeoPoint, class Container> template <class GeoPoint, class Container>
void areaFromEnu(const GeoPoint &origin, FPolygon &in, const Container &out) { void areaFromEnu(const GeoPoint &origin, const FPolygon &in, Container &out) {
for (auto &vertex : in.outer()) { for (auto &vertex : in.outer()) {
typename Container::value_type p; typename Container::value_type p;
fromENU(origin, vertex, p); fromENU(origin, vertex, p);
......
...@@ -5,31 +5,31 @@ ...@@ -5,31 +5,31 @@
[ [
{ {
"name": "TransectDistance", "name": "TransectDistance",
"shortDescription": "The distance between transects.", "shortDesc": "The distance between transects.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "default": 5.0
}, },
{ {
"name": "DeltaAlpha", "name": "DeltaAlpha",
"shortDescription": "Angle discretisation.", "shortDesc": "Angle discretisation.",
"type": "double", "type": "double",
"units": "Deg", "units": "Deg",
"min": 0.3, "min": 0.3,
"max": 90, "max": 90,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "default": 5.0
}, },
{ {
"name": "MinLength", "name": "MinLength",
"shortDescription": "The minimal transect length.", "shortDesc": "The minimal transect length.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "default": 5.0
} }
] ]
} }
...@@ -5,31 +5,31 @@ ...@@ -5,31 +5,31 @@
[ [
{ {
"name": "TransectDistance", "name": "TransectDistance",
"shortDescription": "The distance between transects.", "shrotDesc": "The distan",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "default": 5.0
}, },
{ {
"name": "Alpha", "name": "Alpha",
"shortDescription": "Transect angle.", "shrotDesc": "Transect angle.",
"type": "double", "type": "double",
"units": "Deg", "units": "Deg",
"min": 0, "min": 0,
"max": 180, "max": 180,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 0.0 "default": 0.0
}, },
{ {
"name": "MinLength", "name": "MinLength",
"shortDescription": "The minimal transect length.", "shrotDesc": "The minimal transect length.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "default": 5.0
} }
] ]
} }
...@@ -5,18 +5,18 @@ ...@@ -5,18 +5,18 @@
[ [
{ {
"name": "Variant", "name": "Variant",
"shortDescription": "Route variant.", "shrotDesc": "Route variant.",
"type": "uint64", "type": "uint64",
"defaultValue": 0 "default": 0
}, },
{ {
"name": "Altitude", "name": "Altitude",
"shortDescription": "Altitude", "shrotDesc": "Altitude",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 1, "min": 1,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 10.0 "default": 10.0
} }
] ]
} }
import QtQuick 2.0
import QtQuick.Layouts 1.11
import QtQuick.Controls 1.4
import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.ScreenTools 1.0
GridLayout {
id:_root
property bool checked: true
property var missionItem: undefined
property int availableWidth: 300
property var _areaData: missionItem.areaData
property real _margin: ScreenTools.defaultFontPixelWidth / 2
width: availableWidth
columnSpacing: _margin
rowSpacing: _margin
columns: 2
Component.onCompleted: {
console.assert(missionItem !== undefined, "please set the missionItem property")
checkedChangedHandler()
}
onCheckedChanged: checkedChangedHandler()
ExclusiveGroup{id:areaGroup}
Repeater{
id: areaSelector
property int selectedIndex: -1
model: _missionItem.areaData.areaList
delegate: QGCRadioButton {
text: object.objectName
checkable: _root.checked
Layout.fillWidth: true
Layout.columnSpan: 2
onCheckedChanged: {
if (checked){
areaSelector.selectedIndex = index
}
}
Component.onCompleted: {
if (index === 0){
checked = true
}
object.interactive = Qt.binding(function(){return checked && _root.checked})
}
}
} // area Repeater
ColumnLayout {
id:editorParent
Layout.fillWidth: true
Layout.columnSpan: 2
}
Repeater{
id:areaEditorRepeater
model: _missionItem.areaData.areaList
delegate: Item{
id:editor
visible: index == areaSelector.selectedIndex
property var _visualItem: undefined
property var geoArea: object
Component.onCompleted: {
if (geoArea.editorQML && !_visualItem) {
var component = Qt.createComponent(geoArea.editorQML)
if (component.status === Component.Error) {
console.log("Error loading Qml: ", geoArea.editorQML, component.errorString())
} else {
_visualItem = component.createObject(editorParent, {
geoArea: editor.geoArea,
visible: Qt.binding(function(){return editor.visible}),
availableWidth: Qt.binding(function(){return editorParent.width})})
}
}
}
Component.onDestruction: {
if (_visualItem) {
_visualItem.destroy()
}
}
} // editor
} // areaEditorRepeater
QGCButton{
text: "Check Rules"
enabled: _root.checked
Layout.fillWidth: true
onClicked: {
_areaData.isCorrect()
}
}
QGCButton{
text: "Intersection"
enabled: _root.checked
Layout.fillWidth: true
onClicked: {
_areaData.intersection()
}
}
function checkedChangedHandler(){
if (_root.checked){
missionItem.startEditing()
} else {
missionItem.stopEditing()
}
}
}
...@@ -9,7 +9,7 @@ import QGroundControl.ScreenTools 1.0 ...@@ -9,7 +9,7 @@ import QGroundControl.ScreenTools 1.0
GridLayout { GridLayout {
id: grid id: grid
property var generator // CircularGenerator property var generator: undefined // CircularGenerator
property var availableWidth property var availableWidth
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
...@@ -18,6 +18,10 @@ GridLayout { ...@@ -18,6 +18,10 @@ GridLayout {
rowSpacing: _margin rowSpacing: _margin
columns: 2 columns: 2
Component.onCompleted: {
console.assert(generator !== undefined, "please set the generator property")
}
QGCLabel { text: qsTr("Distance") } QGCLabel { text: qsTr("Distance") }
FactTextField { FactTextField {
fact: generator.distance fact: generator.distance
......
...@@ -36,9 +36,10 @@ Item { ...@@ -36,9 +36,10 @@ Item {
var component = Qt.createComponent(_root.geoArea.mapVisualQML) var component = Qt.createComponent(_root.geoArea.mapVisualQML)
if (component.status === Component.Error) { if (component.status === Component.Error) {
console.log("Error loading Qml: ", _root.geoArea.mapVisualQML, component.errorString()) console.log("Error loading Qml: ", _root.geoArea.mapVisualQML, component.errorString())
} else {
_root._visualItem = component.createObject(_root.map, { map: _root.map, geoArea: _root.geoArea})
_root._visualItem.clicked.connect(_root.clicked)
} }
_root._visualItem = component.createObject(_root.map, { map: _root.map, geoArea: _root.geoArea})
_root._visualItem.clicked.connect(_root.clicked)
} }
} }
......
// Idea from:
// https://stackoverflow.com/questions/42992067/qtquick-dragging-mapquickitem-on-a-map
import QtQuick 2.3
import QtLocation 5.3
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
Rectangle {
id: root
property var anchor: undefined
property bool draggable: true
readonly property bool dragged: mouseArea.drag.active
signal dragStart
signal dragStop
signal clicked
property bool _mobile: ScreenTools.isMobile
property real _touchWidth: Math.max(anchor.width, ScreenTools.minTouchPixels)
property real _touchHeight: Math.max(anchor.height, ScreenTools.minTouchPixels)
property real _touchMarginHorizontal: _mobile ? (_touchWidth - anchor.width) / 2 : 0
property real _touchMarginVertical: _mobile ? (_touchHeight - anchor.height) / 2 : 0
x: anchor.x - _touchMarginHorizontal
y: anchor.y - _touchMarginVertical
width: anchor.width + (_touchMarginHorizontal * 2)
height: anchor.height + (_touchMarginVertical * 2)
color: "transparent"
z: QGroundControl.zOrderMapItems + 1
Component.onCompleted: {
console.assert(anchor !== undefined, "please set the anchor property")
}
onDraggedChanged: {
if (dragged) {
dragStart()
} else {
dragStop()
}
}
QGCMouseArea {
id: mouseArea
enabled: draggable
preventStealing: true
drag.target: root
drag.threshold: 0
anchors.fill: parent
cursorShape: draggable ?
(dragged ? Qt.ClosedHandCursor : Qt.OpenHandCursor)
: Qt.ArrowCursor
onClicked: {
focus = true
root.clicked()
}
}
Connections {
target: anchor
onXChanged: if (!dragged) x = anchor.x - _touchMarginHorizontal
onYChanged: if (!dragged) y = anchor.y - _touchMarginVertical
}
onXChanged: if (dragged) anchor.x = x + _touchMarginHorizontal
onYChanged: if (dragged) anchor.y = y + _touchMarginVertical
Drag.active: true
}
...@@ -8,8 +8,8 @@ import QGroundControl.ScreenTools 1.0 ...@@ -8,8 +8,8 @@ import QGroundControl.ScreenTools 1.0
GridLayout { GridLayout {
property var generator // CircularGenerator property var generator: undefined // LinearGenerator
property var availableWidth property var availableWidth: 300
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property real _margin: ScreenTools.defaultFontPixelWidth / 2
width: availableWidth width: availableWidth
...@@ -17,6 +17,10 @@ GridLayout { ...@@ -17,6 +17,10 @@ GridLayout {
rowSpacing: _margin rowSpacing: _margin
columns: 2 columns: 2
Component.onCompleted: {
console.assert(generator !== undefined, "please set the generator property")
}
QGCLabel { text: qsTr("Distance") } QGCLabel { text: qsTr("Distance") }
FactTextField { FactTextField {
fact: generator.distance fact: generator.distance
......
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2 import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
...@@ -13,140 +10,98 @@ import QGroundControl.FactControls 1.0 ...@@ -13,140 +10,98 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0 import QGroundControl.FlightMap 1.0
// Editor for Operating Area items GridLayout {
Rectangle { id: editorColumn
id: _root columns: 2
height: visible ? (editorColumn.height + (_margin * 2)) : 0 columnSpacing: _margin
rowSpacing: _margin
width: availableWidth width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property var geoArea: undefined
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 property int availableWidth
property bool polygonInteractive: areaItem.interactive
property var polygon: areaItem
property bool initNecesarry: true
onPolygonInteractiveChanged: { property real _margin: ScreenTools.defaultFontPixelWidth / 2
polygon.interactive = polygonInteractive;
}
QGCPalette { id: qgcPal; colorGroupEnabled: true } Component.onCompleted: {
console.assert(geoArea !== undefined, "please set the areaItem property")
}
Column { SectionHeader {
id: editorColumn id: tilesHeader
anchors.margins: _margin text: qsTr("Tiles")
anchors.top: parent.top Layout.columnSpan: 2
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right }
spacing: _margin
SectionHeader { GridLayout{
id: settingsHeader visible: tilesHeader.checked
text: qsTr("General") Layout.fillWidth: true
Layout.columnSpan: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel {
text: qsTr("Height")
Layout.fillWidth: true
} }
Column { FactTextField {
anchors.left: parent.left fact: geoArea.tileHeight
anchors.right: parent.right Layout.fillWidth: true
spacing: _margin
visible: settingsHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Offset") }
FactTextField {
fact: areaItem.borderPolygonOffset
Layout.fillWidth: true
}
}
FactCheckBox {
text: qsTr("Border Polygon")
fact: areaItem.showBorderPolygon
//enabled: !missionItem.followTerrain
}
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: 1
}
} // Column - Settings
SectionHeader {
id: tilesHeader
text: qsTr("Tiles")
} }
Column { QGCLabel {
anchors.left: parent.left text: qsTr("Width")
anchors.right: parent.right Layout.fillWidth: true
spacing: _margin }
visible: tilesHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Height") }
FactTextField {
fact: areaItem.tileHeight
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Width") }
FactTextField { FactTextField {
fact: areaItem.tileWidth fact: geoArea.tileWidth
Layout.fillWidth: true Layout.fillWidth: true
} }
QGCLabel { text: qsTr("Min. Area") } QGCLabel {
text: qsTr("Min. Area")
Layout.fillWidth: true
}
FactTextField { FactTextField {
fact: areaItem.minTileArea fact: geoArea.minTileArea
Layout.fillWidth: true Layout.fillWidth: true
} }
FactCheckBox { FactCheckBox {
text: qsTr("Show Tiles") text: qsTr("Show Tiles")
fact: areaItem.showTiles fact: geoArea.showTiles
} }
} // Tile GridLayout }
} // Tile Column
SectionHeader { SectionHeader {
id: statsHeader id: statsHeader
text: qsTr("Statistics") text: qsTr("Statistics")
} Layout.fillWidth: true
Layout.columnSpan: 2
}
Grid { GridLayout{
columns: 2 visible: statsHeader.checked
columnSpacing: ScreenTools.defaultFontPixelWidth Layout.fillWidth: true
visible: statsHeader.checked Layout.columnSpan: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Area") } QGCLabel { text: qsTr("Area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(areaItem.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString } // QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(geoArea.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
QGCLabel { text: qsTr("Tiles") }
QGCLabel { text: areaItem.tiles.count }
QGCLabel { text: qsTr("Max. Tiles") } QGCLabel { text: qsTr("Tiles") }
QGCLabel { text: areaItem.maxTiles } QGCLabel { text: geoArea.tiles.count }
} QGCLabel { text: qsTr("Max. Tiles") }
} // Column QGCLabel { text: geoArea.maxTiles }
} // Rectangle }
} // Column
...@@ -44,6 +44,7 @@ Item { ...@@ -44,6 +44,7 @@ Item {
borderColor: "green" borderColor: "green"
interiorColor: "green" interiorColor: "green"
altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision
z: QGroundControl.zOrderMapItems-1
interiorOpacity: _root.opacity interiorOpacity: _root.opacity
} }
......
ParameterEditor 1.0 ParameterEditor.qml
AreaDataEditor 1.0 AreaDataEditor.qml
LinearGenerator 1.0 LinearGenerator.qml
CircularGenerator 1.0 CircularGenerator.qml
SafeAreaEditor 1.0 SafeAreaEditor.qml
MeasurementAreaEditor 1.0 MeasurementAreaEditor.qml
...@@ -37,21 +37,28 @@ Item { ...@@ -37,21 +37,28 @@ Item {
signal clicked(int sequenceNumber) signal clicked(int sequenceNumber)
on_EditingChanged: { // on_EditingChanged: {
_destroyEntryCoordinate() // if (_editing){
_destroyExitCoordinate() // _destroyEntryCoordinate()
_destroyTransectsComponent() // _destroyExitCoordinate()
_destroyGeneratorVisuals() // _destroyTransectsComponent()
} // _destroyGeneratorVisuals()
// } else {
// _addEntryCoordinate()
// _addExitCoordinate()
// _addTransectsComponent()
// _addGeneratorVisuals()
// }
// }
Component.onCompleted: { Component.onCompleted: {
console.assert(map != undefined, "please set the map property")
_addEntryCoordinate() _addEntryCoordinate()
_addExitCoordinate() _addExitCoordinate()
_addTransectsComponent() _addTransectsComponent()
_addGeneratorVisuals() _addGeneratorVisuals()
var bbox = boundingBox() var bbox = boundingBox()
_missionItem.areaData.initialize(bbox[0], bbox[1]) _missionItem.areaData.initialize(bbox[0], bbox[1])
console.assert(map != undefined, "please set the map property")
} }
Component.onDestruction: { Component.onDestruction: {
...@@ -71,10 +78,11 @@ Item { ...@@ -71,10 +78,11 @@ Item {
id: visualTransectsComponent id: visualTransectsComponent
MapPolyline { MapPolyline {
property var route: _missionItem.route
line.color: "white" line.color: "white"
line.width: 2 line.width: 2
path: route.length > 0 ? route : [] path: _missionItem.route
onPathChanged: console.log("path:" + path)
} }
} }
......
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
ColumnLayout {
id:root
property int availableWidth: 300
property var missionItem: undefined ///< Mission Item for editor
property bool checked: true
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property var _generator: missionItem.generator
property var _generatorEditor: undefined
width: availableWidth
Component.onCompleted: {
console.assert(missionItem !== undefined, "please set the missionItem property")
_addGeneratorEditor()
}
Component.onDestruction: {
_destroyGeneratorEditor()
}
on_GeneratorChanged: {
_destroyGeneratorEditor()
_addGeneratorEditor()
}
SectionHeader {
id: generalHeader
Layout.fillWidth: true
text: qsTr("General")
}
GridLayout {
id: generalGrid
Layout.fillWidth: true
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: generalHeader.checked
QGCLabel { text: qsTr("Altitude!!!") }
QGCLabel { text: qsTr("Relative Altitude!!!") }
QGCLabel {
text: qsTr("Variant")
Layout.columnSpan: 2
visible: variantRepeater.len > 0
}
GridLayout{
Layout.columnSpan: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 6
Repeater{
id: variantRepeater
property var fact: missionItem.variant
property int variant: fact.value
property var names: missionItem.variantNames
property int len: missionItem.variantNames.length
model: len
delegate: QGCRadioButton {
checked: index === variantRepeater.variant
text: variantRepeater.names[index] ? variantRepeater.names[index]: ""
onCheckedChanged: {
if (checked){
missionItem.variant.value = index
}
checked = Qt.binding(function(){ return index === variantRepeater.variant})
}
}
} // variant repeater
} // variant grid
} // general grid
// Generator Editor
SectionHeader {
id: generatorHeader
Layout.fillWidth: true
text: qsTr("Generator")
}
GridLayout{
Layout.fillWidth: true
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: generatorHeader.checked
QGCComboBox {
property var names: missionItem.generatorNameList
property int length: names.length
enabled: root.checked
anchors.margins: ScreenTools.defaultFontPixelWidth
currentIndex: missionItem.generatorIndex
Layout.columnSpan: 2
model: missionItem.generatorNameList
onActivated: {
if (index != -1){
missionItem.switchToGenerator(index)
}
}
}
}
ColumnLayout{
id:generatorEditorParent
Layout.fillWidth: true
visible: generatorHeader.checked
}
// bussy indicator
ColumnLayout{
Layout.fillWidth: true
spacing: _margin
BusyIndicator{
id: indicator
property bool calculating: missionItem.calculating
running: calculating
visible: calculating || timer.running
onCalculatingChanged: {
if(!calculating){
// defer hiding
timer.restart()
}
}
Timer{
id: timer
interval: 1000
repeat: false
running: false
}
}
} // indicator column
function _addGeneratorEditor(){
if (_generator.editorQml && !_generatorEditor) {
var component = Qt.createComponent(_generator.editorQml)
if (component.status === Component.Error) {
console.log("Error loading Qml: ",
_generator.editorQml, component.errorString())
} else {
_generatorEditor =
component.createObject(
generatorEditorParent, {
"generator": root._generator,
"availableWidth": generatorEditorParent.width,
})
}
}
}
function _destroyGeneratorEditor(){
if (_generatorEditor){
_generatorEditor.destroy()
_generatorEditor = undefined
}
}
}
import QtQml 2.2
import QtQuick 2.0
import QtLocation 5.3
MapQuickItem {
id: root
width: 15
height: 15
anchorPoint.x: width/2
anchorPoint.y: height/2
property color primaryColor: "orange"
property color secondaryColor: "lightblue"
property real centerWidth: width / 2
property real centerHeight: height / 2
property real radius: Math.min(canvas.width, canvas.height) / 2
property real minimumValue: 0
property real maximumValue: 100
property real currentValue: 33
// this is the angle that splits the circle in two arcs
// first arc is drawn from 0 radians to angle radians
// second arc is angle radians to 2*PI radians
property real angle: (currentValue - minimumValue) / (maximumValue - minimumValue) * 2 * Math.PI
// we want both circle to start / end at 12 o'clock
// without this offset we would start / end at 9 o'clock
property real angleOffset: -Math.PI / 2
property string text: ""
signal clicked()
onPrimaryColorChanged: canvas.requestPaint()
onSecondaryColorChanged: canvas.requestPaint()
onMinimumValueChanged: canvas.requestPaint()
onMaximumValueChanged: canvas.requestPaint()
onCurrentValueChanged: canvas.requestPaint()
// draws two arcs (portion of a circle)
// fills the circle with a lighter secondary color
// when pressed
sourceItem: Canvas {
id: canvas
width: root.width
height: root.height
antialiasing: true
onPaint: {
var ctx = getContext("2d");
ctx.save();
ctx.clearRect(0, 0, canvas.width, canvas.height);
// fills the mouse area when pressed
// the fill color is a lighter version of the
// secondary color
if (mouseArea.pressed) {
ctx.beginPath();
ctx.lineWidth = 1;
ctx.fillStyle = Qt.lighter(root.secondaryColor, 1.25);
ctx.arc(root.centerWidth,
root.centerHeight,
root.radius,
0,
2*Math.PI);
ctx.fill();
}
// First, thinner arc
// From angle to 2*PI
ctx.beginPath();
ctx.lineWidth = 1;
ctx.strokeStyle = primaryColor;
ctx.arc(root.centerWidth,
root.centerHeight,
root.radius,
angleOffset + root.angle,
angleOffset + 2*Math.PI);
ctx.stroke();
// Second, thicker arc
// From 0 to angle
ctx.beginPath();
ctx.lineWidth = 1;
ctx.strokeStyle = root.secondaryColor;
ctx.arc(root.centerWidth,
root.centerHeight,
root.radius,
root.angleOffset,
root.angleOffset + root.angle);
ctx.stroke();
ctx.restore();
}
Text {
anchors.centerIn: parent
text: root.text
color: root.primaryColor
}
MouseArea {
id: mouseArea
anchors.fill: parent
onClicked: root.clicked()
onPressedChanged: canvas.requestPaint()
}
}
}
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.4
import QtQuick.Dialogs 1.2
import QtQuick.Extras 1.4
import QtQuick.Layouts 1.2 import QtQuick.Layouts 1.2
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0 import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Operating Area items GridLayout {
Rectangle { id: editorColumn
id: _root columns: 2
height: visible ? (editorColumn.height + (_margin * 2)) : 0 columnSpacing: _margin
rowSpacing: _margin
width: availableWidth width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
property real _margin: ScreenTools.defaultFontPixelWidth / 2 property var geoArea: undefined
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5 property int availableWidth
property bool polygonInteractive: areaItem.interactive
property var polygon: areaItem property real _margin: ScreenTools.defaultFontPixelWidth / 2
property bool initNecesarry: true
Component.onCompleted: {
QGCPalette { id: qgcPal; colorGroupEnabled: true } console.assert(geoArea !== undefined, "please set the areaItem property")
}
Column {
id: editorColumn SectionHeader {
anchors.margins: _margin id: statsHeader
anchors.top: parent.top text: qsTr("Statistics")
anchors.left: parent.left Layout.fillWidth: true
anchors.right: parent.right Layout.columnSpan: 2
spacing: _margin }
SectionHeader { GridLayout {
id: scanHeader columns: 2
text: qsTr("Settings") columnSpacing: _margin
} rowSpacing: _margin
visible: statsHeader.checked
Column { Layout.fillWidth: true
anchors.left: parent.left Layout.columnSpan: 2
anchors.right: parent.right
spacing: _margin QGCLabel { text: qsTr("Area") }
visible: scanHeader.checked //QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(geoArea.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
}
GridLayout { }
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Offset") }
FactTextField {
fact: areaItem.borderPolygonOffset
Layout.fillWidth: true
}
}
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: 1
}
}
FactCheckBox {
text: qsTr("Border Polygon")
fact: areaItem.showBorderPolygon
//enabled: !missionItem.followTerrain
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(areaItem.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
}
} // Column
} // Rectangle
...@@ -24,36 +24,13 @@ Item { ...@@ -24,36 +24,13 @@ Item {
property var map: undefined ///< Map control to place item in property var map: undefined ///< Map control to place item in
property var geoArea: undefined ///< GeoArea derived class. property var geoArea: undefined ///< GeoArea derived class.
property var _depotVisual: undefined
property var _depotDrag: undefined
property bool _showDepot: geoArea.interactive
opacity: 0.3
signal clicked(int sequenceNumber) signal clicked(int sequenceNumber)
on_ShowDepotChanged: {
if (_showDepot){
_addDepotVisual()
_addDepotDrag()
} else {
_destroyDepotVisual()
_destroyDepotDrag()
}
}
Component.onCompleted: { Component.onCompleted: {
if (_showDepot){
_addDepotVisual()
_addDepotDrag()
}
console.assert(map !== undefined, "please set the map property") console.assert(map !== undefined, "please set the map property")
console.assert(geoArea !== undefined, "please set the geoArea property") console.assert(geoArea !== undefined, "please set the geoArea property")
} }
Component.onDestruction: {
_destroyDepotVisual()
}
// Area polygon // Area polygon
QGCMapPolygonVisuals { QGCMapPolygonVisuals {
...@@ -65,78 +42,61 @@ Item { ...@@ -65,78 +42,61 @@ Item {
borderColor: "blue" borderColor: "blue"
interiorColor: "blue" interiorColor: "blue"
altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision
interiorOpacity: _root.opacity z: QGroundControl.zOrderMapItems-1
interiorOpacity: 0.3
}
Loader {
id:depotLoader
sourceComponent: depotComponent
} }
// Depot Point. // Depot Point.
Component { Component {
id: depotPointComponent id: depotComponent
MapQuickItem { Item {
coordinate: _root.geoArea.depot id: depotMapItem
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY MapQuickItem {
visible: true id: mapItem
sourceItem:
MissionItemIndexLabel { coordinate: _root.geoArea.depot
checked: geoArea.interactive anchorPoint.x: sourceItem.anchorPointX
label: qsTr("Launch") anchorPoint.y: sourceItem.anchorPointY
highlightSelected: true visible: true
onClicked: _root.clicked(0) z: QGroundControl.zOrderMapItems
visible: true
Component.onCompleted: {
coordinate = Qt.binding(function(){return _root.geoArea.depot})
} }
}
}
Component { sourceItem:
id: depotDragComponent MissionItemIndexLabel {
checked: true
MissionItemIndicatorDrag { label: qsTr("Depot")
mapControl: _root.map highlightSelected: true
itemIndicator: _depot onClicked: _root.clicked(0)
itemCoordinate: geoArea.depot visible: mapItem.visible
visible: geoArea.interactive z: mapItem.z
property var depot: geoArea.depot
onItemCoordinateChanged: {
if (itemCoordinate.latitude !== depot.latitude ||
itemCoordinate.longitude !== depot.longitude){
if (_root.areaItem.containsCoordinate(itemCoordinate)){
_root.areaItem.depot = itemCoordinate
}
} }
itemCoordinate = Qt.binding(function(){return _root.geoArea.depot})
} }
}
}
function _addDepotVisual() {
if (!_depotVisual){
_depotVisual = depotPointComponent.createObject(_root)
map.addMapItem(_depotVisual)
}
}
function _destroyDepotVisual() { ItemDragger {
if (_depotVisual){ anchor: mapItem
map.removeMapItem(_depotVisual) z: QGroundControl.zOrderMapItems+1
_depotVisual.destroy() draggable: _root.geoArea.interactive
_depotVisual = undefined
}
}
function _addDepotDrag() { onDragStop:{
if (!_depotDrag){ _root.geoArea.depot = mapItem.coordinate
_depotDrag = depotDragComponent.createObject(_root) mapItem.coordinate = Qt.binding(function(){return _root.geoArea.depot})
} }
} }
function _destroyDepotDrag() { Component.onCompleted: {
if (_depotDrag){ _root.map.addMapItem(mapItem)
_depotDrag.destroy() }
_depotDrag = undefined
} }
} }
} }
This diff is collapsed.
This diff is collapsed.
...@@ -113,6 +113,4 @@ MAVLinkChart 1.0 MAVLinkChart.qml ...@@ -113,6 +113,4 @@ MAVLinkChart 1.0 MAVLinkChart.qml
MeasurementItemMapVisual 1.0 MeasurementItemMapVisual.qml MeasurementItemMapVisual 1.0 MeasurementItemMapVisual.qml
CircularGeneratorMapVisual 1.0 CircularGeneratorMapVisual.qml CircularGeneratorMapVisual 1.0 CircularGeneratorMapVisual.qml
GeoAreaVisualLoader 1.0 GeoAreaVisualLoader.qml GeoAreaVisualLoader 1.0 GeoAreaVisualLoader.qml
DragCoordinate 1.0 DragCoordinate.qml ItemDragger 1.0 ItemDragger.qml
CoordinateIndicator 1.0 CoordinateIndicator.qml
CoordinateIndicatorDrag 1.0 CoordinateIndicatorDrag.qml
...@@ -7,87 +7,91 @@ ...@@ -7,87 +7,91 @@
* *
****************************************************************************/ ****************************************************************************/
#ifndef QmlObjectListModel_H #ifndef QmlObjectListModel_H
#define QmlObjectListModel_H #define QmlObjectListModel_H
#include <QAbstractListModel> #include <QAbstractListModel>
class QmlObjectListModel : public QAbstractListModel class QmlObjectListModel : public QAbstractListModel {
{ Q_OBJECT
Q_OBJECT
public: public:
QmlObjectListModel(QObject* parent = nullptr); QmlObjectListModel(QObject *parent = nullptr);
~QmlObjectListModel() override; ~QmlObjectListModel() override;
Q_PROPERTY(int count READ count NOTIFY countChanged) Q_PROPERTY(int count READ count NOTIFY countChanged)
/// Returns true if any of the items in the list are dirty. Requires each object to have /// Returns true if any of the items in the list are dirty. Requires each
/// a dirty property and dirtyChanged signal. /// object to have a dirty property and dirtyChanged signal.
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_INVOKABLE QObject* get(int index); Q_INVOKABLE QObject *get(int index);
// Property accessors // Property accessors
int count () const; int count() const;
bool dirty () const { return _dirty; } bool dirty() const { return _dirty; }
void setDirty (bool dirty); void setDirty(bool dirty);
void append (QObject* object); void append(QObject *object);
void append (QList<QObject*> objects); void append(QList<QObject *> objects);
QObjectList swapObjectList (const QObjectList& newlist); QObjectList swapObjectList(const QObjectList &newlist);
void clear (); void clear();
QObject* removeAt (int i); QObject *removeAt(int i);
QObject* removeOne (QObject* object) { return removeAt(indexOf(object)); } QObject *removeOne(QObject *object) { return removeAt(indexOf(object)); }
void insert (int i, QObject* object); void insert(int i, QObject *object);
void insert (int i, QList<QObject*> objects); void insert(int i, QList<QObject *> objects);
bool contains (QObject* object) { return _objectList.indexOf(object) != -1; } bool contains(QObject *object) { return _objectList.indexOf(object) != -1; }
int indexOf (QObject* object) { return _objectList.indexOf(object); } int indexOf(QObject *object) { return _objectList.indexOf(object); }
/// Moves an item to a new position /// Moves an item to a new position
void move(int from, int to); void move(int from, int to);
QObject* operator[] (int i); QObject *operator[](int i);
const QObject* operator[] (int i) const; const QObject *operator[](int i) const;
template<class T> T value (int index) { return qobject_cast<T>(_objectList[index]); } template <class T> T value(int index) {
QList<QObject*>* objectList () { return &_objectList; } return qobject_cast<T>(_objectList[index]);
}
/// Calls deleteLater on all items and this itself. QList<QObject *> *objectList() { return &_objectList; }
void deleteListAndContents ();
/// Calls deleteLater on all items and this itself.
/// Clears the list and calls deleteLater on each entry void deleteListAndContents();
void clearAndDeleteContents ();
/// Clears the list and calls deleteLater on each entry
void beginReset (); void clearAndDeleteContents();
void endReset ();
void beginReset();
void endReset();
signals: signals:
void countChanged (int count); void countChanged(int count);
void dirtyChanged (bool dirtyChanged); void dirtyChanged(bool dirtyChanged);
private slots: private slots:
void _childDirtyChanged (bool dirty); void _childDirtyChanged(bool dirty);
private: private:
// Overrides from QAbstractListModel // Overrides from QAbstractListModel
int rowCount (const QModelIndex & parent = QModelIndex()) const override; int rowCount(const QModelIndex &parent = QModelIndex()) const override;
QVariant data (const QModelIndex & index, int role = Qt::DisplayRole) const override; QVariant data(const QModelIndex &index,
bool insertRows (int position, int rows, const QModelIndex &index = QModelIndex()) override; int role = Qt::DisplayRole) const override;
bool removeRows (int position, int rows, const QModelIndex &index = QModelIndex()) override; bool insertRows(int position, int rows,
bool setData (const QModelIndex &index, const QVariant &value, int role = Qt::EditRole) override; const QModelIndex &index = QModelIndex()) override;
QHash<int, QByteArray> roleNames(void) const override; bool removeRows(int position, int rows,
const QModelIndex &index = QModelIndex()) override;
bool setData(const QModelIndex &index, const QVariant &value,
int role = Qt::EditRole) override;
QHash<int, QByteArray> roleNames(void) const override;
private: private:
QList<QObject*> _objectList; QList<QObject *> _objectList;
bool _dirty; bool _dirty;
bool _skipDirtyFirstItem; bool _skipDirtyFirstItem;
bool _externalBeginResetModel; bool _externalBeginResetModel;
static const int ObjectRole; static const int ObjectRole;
static const int TextRole; static const int TextRole;
}; };
#endif #endif
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