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

measurement works mostly, some smaller issues left

parent 5a5b161e
......@@ -261,19 +261,18 @@
<file alias="QmlTest.qml">src/QmlControls/QmlTest.qml</file>
<file alias="RadioComponent.qml">src/AutoPilotPlugins/Common/RadioComponent.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="MeasurementItemEditor.qml">src/MeasurementComplexItem/qml/MeasurementItemEditor.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/CoordinateIndicatorDrag.qml">src/MeasurementComplexItem/qml/CoordinateIndicatorDrag.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="ProgressIndicator.qml">src/MeasurementComplexItem/qml/ProgressIndicator.qml</file>
<file alias="MeasurementComplexItem/LinearGeneratorEditor.qml">src/MeasurementComplexItem/qml/LinearGeneratorEditor.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="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="SetupParameterEditor.qml">src/VehicleSetup/SetupParameterEditor.qml</file>
<file alias="SetupView.qml">src/VehicleSetup/SetupView.qml</file>
......@@ -290,6 +289,10 @@
<file alias="VirtualJoystick.qml">src/FlightDisplay/VirtualJoystick.qml</file>
<file alias="VTOLLandingPatternEditor.qml">src/PlanView/VTOLLandingPatternEditor.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 prefix="/FirstRunPromptDialogs">
<file alias="UnitsFirstRunPrompt.qml">src/FirstRunPromptDialogs/UnitsFirstRunPrompt.qml</file>
......
......@@ -2,7 +2,9 @@
#include "geometry/MeasurementArea.h"
#include "geometry/SafeArea.h"
#include "geometry/snake.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCQGeoCoordinate.h"
......@@ -12,20 +14,24 @@ AreaData::AreaData(QObject *parent) : QObject(parent) {}
AreaData::~AreaData() {}
AreaData::AreaData(const AreaData &other, QObject *parent) : QObject(parent) {
if (!copyAreaList(other._areaList, _areaList, this)) {
qCWarning(AreaDataLog) << "AreaData(): not able to copy other._areaList";
} else {
_origin = other._origin;
}
AreaData::AreaData(const AreaData &other, QObject *parent)
: QObject(parent), _initialized(false), _showErrorMessages(true) {
*this = other;
}
AreaData &AreaData::operator=(const AreaData &other) {
if (!copyAreaList(other._areaList, _areaList, this)) {
qCWarning(AreaDataLog) << "operator=(): not able to copy other._areaList";
} else {
_origin = other._origin;
this->clear();
// Clone elements.
for (int i = 0; i < other._areaList.count(); ++i) {
auto obj = other._areaList[i];
auto area = qobject_cast<const GeoArea *>(obj);
this->insert(area->clone(this));
}
_origin = other._origin;
_initialized = other._initialized;
return *this;
}
......@@ -34,6 +40,13 @@ bool AreaData::insert(GeoArea *areaData) {
if (Q_LIKELY(!this->_areaList.contains(areaData))) {
_areaList.append(areaData);
emit areaList();
auto *measurementArea = qobject_cast<MeasurementArea *>(areaData);
if (measurementArea != nullptr) {
connect(measurementArea, &MeasurementArea::centerChanged, this,
&AreaData::_updateOrigin);
_setOrigin(measurementArea->center());
}
return true;
}
}
......@@ -46,9 +59,14 @@ void AreaData::remove(GeoArea *areaData) {
if (index >= 0) {
QObject *obj = _areaList.removeAt(index);
_setOrigin(_newOrigin());
auto *measurementArea = qobject_cast<MeasurementArea *>(areaData);
if (measurementArea != nullptr) {
disconnect(measurementArea, &MeasurementArea::centerChanged, this,
&AreaData::_updateOrigin);
_setOrigin(QGeoCoordinate());
}
if (obj->parent() == nullptr) {
if (obj->parent() == nullptr || obj->parent() == this) {
obj->deleteLater();
}
......@@ -58,11 +76,12 @@ void AreaData::remove(GeoArea *areaData) {
void AreaData::clear() {
if (_areaList.count() > 0) {
for (int i = 0; i < _areaList.count(); ++i) {
remove(_areaList.value<GeoArea *>(i));
while (_areaList.count() > 0) {
remove(_areaList.value<GeoArea *>(0));
}
emit areaListChanged();
}
_errorString.clear();
}
QmlObjectListModel *AreaData::areaList() { return &_areaList; }
......@@ -71,17 +90,44 @@ const QmlObjectListModel *AreaData::areaList() const { return &_areaList; }
const QGeoCoordinate &AreaData::origin() const { return _origin; }
bool AreaData::isValid() const {
qWarning("AreaData::isValid(): impl. incomplete.");
auto *measurementArea = getGeoArea<const MeasurementArea *>(_areaList);
auto *safeArea = getGeoArea<const SafeArea *>(_areaList);
return measurementArea != nullptr && safeArea != nullptr &&
measurementArea->count() >= 3 && safeArea->count() >= 3 &&
_origin.isValid();
}
bool AreaData::isCorrect() {
if (!initialized()) {
qCWarning(AreaDataLog) << "isCorrect(): not initialized";
return false;
}
bool AreaData::tryMakeValid() {
qWarning("AreaData::tryMakeValid(): impl. missing.");
// Check if areas are correct
if (!_areasCorrect()) {
return false;
}
// Check if areas where added.
MeasurementArea *measurementArea = nullptr;
SafeArea *safeArea = nullptr;
if (!_getAreas(&measurementArea, &safeArea)) {
return false;
}
// Check if measurement area is covered by safe area.
if (!_origin.isValid()) {
qCWarning(AreaDataLog) << "isCorrect(): origin invalid";
return false;
}
const auto &origin = this->origin();
snake::FPolygon safeAreaENU;
snake::areaToEnu(origin, safeArea->pathModel(), safeAreaENU);
snake::FPolygon measurementAreaENU;
snake::areaToEnu(origin, measurementArea->pathModel(), measurementAreaENU);
// qDebug() << "origin" << origin;
// std::stringstream ss;
// ss << "measurementAreaENU: " << bg::wkt(measurementAreaENU) << std::endl;
// ss << "safeAreaENU: " << bg::wkt(safeAreaENU) << std::endl;
// qDebug() << ss.str().c_str();
if (!bg::covered_by(measurementAreaENU, safeAreaENU)) {
_processError(tr("Measurement Area not inside Safe Area. Please adjust "
"the Measurement Area."));
return false;
}
return true;
}
......@@ -135,6 +181,15 @@ bool AreaData::initialize(const QGeoCoordinate &bottomLeft,
measurementArea->appendVertex(QGeoCoordinate(
0.8 * bottomLeft.latitude() + 0.2 * topRight.latitude(),
0.2 * bottomLeft.longitude() + 0.8 * topRight.longitude()));
// Set depot
safeArea->setDepot(QGeoCoordinate(
safeArea->vertexCoordinate(0).latitude() * 0.5 +
measurementArea->vertexCoordinate(0).latitude() * 0.5,
safeArea->vertexCoordinate(0).longitude() * 0.5 +
measurementArea->vertexCoordinate(0).longitude() * 0.5));
_initialized = true;
return true;
} else {
qCWarning(AreaDataLog)
......@@ -144,11 +199,59 @@ bool AreaData::initialize(const QGeoCoordinate &bottomLeft,
}
}
bool AreaData::initialized() {
auto *measurementArea = getGeoArea<MeasurementArea *>(_areaList);
auto *safeArea = getGeoArea<SafeArea *>(_areaList);
return measurementArea != nullptr && safeArea != nullptr &&
measurementArea->count() >= 3 && safeArea->count() >= 3;
bool AreaData::initialized() { return _initialized; }
void AreaData::intersection() {
if (initialized() && _areasCorrect()) {
MeasurementArea *measurementArea = nullptr;
SafeArea *safeArea = nullptr;
if (_getAreas(&measurementArea, &safeArea)) {
// convert to ENU
const auto origin = this->origin();
snake::FPolygon safeAreaENU;
snake::areaToEnu(origin, safeArea->pathModel(), safeAreaENU);
snake::FPolygon measurementAreaENU;
snake::areaToEnu(origin, measurementArea->pathModel(),
measurementAreaENU);
// do intersection
std::deque<snake::FPolygon> outputENU;
boost::geometry::intersection(measurementAreaENU, safeAreaENU, outputENU);
if (outputENU.size() < 1 || outputENU[0].outer().size() < 4) {
_processError(
"Intersection did't deliver any result. Measurement Area and "
"Safe Area must touch each other.");
return;
}
if (outputENU[0].inners().size() > 0 || outputENU.size() > 1) {
_processError(
"Hint: Only simple polygons can be displayed. If Intersection"
"produces polygons with holes or multi polygons, only "
"partial information can be displayed.");
}
// Shrink the result if safeAreaENU doesn't cover it.
auto large = std::move(outputENU[0]);
snake::FPolygon small;
while (!bg::covered_by(large, safeAreaENU)) {
snake::offsetPolygon(large, small, -0.1);
large = std::move(small);
qDebug() << "intersection(): shrink";
}
// Convert.
measurementArea->clear();
for (auto it = large.outer().begin(); it != large.outer().end() - 1;
++it) {
QGeoCoordinate c;
snake::fromENU(origin, *it, c);
measurementArea->appendVertex(c);
}
}
}
}
bool AreaData::operator==(const AreaData &other) const {
......@@ -174,24 +277,59 @@ void AreaData::_setOrigin(const QGeoCoordinate &origin) {
}
}
QGeoCoordinate AreaData::_newOrigin() {
auto *measurementArea = getGeoArea<MeasurementArea *>(_areaList);
auto *safeArea = getGeoArea<SafeArea *>(_areaList);
if (measurementArea != nullptr && measurementArea->pathModel().count() > 0) {
QGCQGeoCoordinate *ori =
measurementArea->pathModel().value<QGCQGeoCoordinate *>(0);
if (ori != nullptr && ori->coordinate().isValid()) {
return ori->coordinate();
void AreaData::_processError(const QString &str) {
this->_errorString = str;
emit error();
if (_showErrorMessages) {
qgcApp()->informationMessageBoxOnMainThread(tr("Area Editor"),
this->errorString());
}
}
bool AreaData::_areasCorrect() {
// Check if areas are correct.
for (int i = 0; i < _areaList.count(); ++i) {
auto *area = _areaList.value<GeoArea *>(0);
if (!area->isCorrect()) {
_processError(area->errorString());
return false;
}
}
return true;
}
if (safeArea != nullptr && safeArea->pathModel().count() > 0) {
QGCQGeoCoordinate *ori =
measurementArea->pathModel().value<QGCQGeoCoordinate *>(0);
if (ori != nullptr && ori->coordinate().isValid()) {
return ori->coordinate();
bool AreaData::_getAreas(MeasurementArea **measurementArea,
SafeArea **safeArea) {
*measurementArea = getGeoArea<MeasurementArea *>(_areaList);
if (*measurementArea == nullptr) {
_processError(
tr("Measurement Area missing. Please define a measurement area."));
return false;
}
*safeArea = getGeoArea<SafeArea *>(_areaList);
if (*safeArea == nullptr) {
_processError(tr("Safe Area missing. Please define a safe area."));
return false;
}
return true;
}
void AreaData::setShowErrorMessages(bool showErrorMessages) {
if (showErrorMessages != _showErrorMessages) {
_showErrorMessages = showErrorMessages;
emit showErrorMessagesChanged();
}
}
return QGeoCoordinate();
void AreaData::_updateOrigin() {
auto *measurementArea = getGeoArea<MeasurementArea *>(_areaList);
if (measurementArea != nullptr) {
_setOrigin(measurementArea->center());
}
}
bool AreaData::showErrorMessages() const { return _showErrorMessages; }
QString AreaData::errorString() const { return _errorString; }
......@@ -18,6 +18,8 @@ public:
AreaData &operator=(const AreaData &other);
Q_PROPERTY(QmlObjectListModel *areaList READ areaList NOTIFY areaListChanged)
Q_PROPERTY(bool showErrorMessages READ showErrorMessages WRITE
setShowErrorMessages NOTIFY showErrorMessagesChanged)
// Member Methodes
//!
......@@ -27,7 +29,8 @@ public:
//!
//! \brief remove
//! \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 clear();
//!
......@@ -46,8 +49,7 @@ public:
//! \note Origin might change if the list of areas changes.
const QGeoCoordinate &origin() const;
Q_INVOKABLE bool isValid() const;
Q_INVOKABLE bool tryMakeValid();
Q_INVOKABLE bool isCorrect();
//!
//! \brief initialize Initializes the areas in a valid way, such that they
//! area inside the bounding box. \param bottomLeft bottom left corner of the
......@@ -65,18 +67,33 @@ public:
//! either.
//!
Q_INVOKABLE bool initialized();
Q_INVOKABLE void intersection();
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:
void areaListChanged();
void originChanged();
void error(); // Emitted if errorString() contains a new message.
void showErrorMessagesChanged();
private slots:
void _updateOrigin();
private:
void _setOrigin(const QGeoCoordinate &origin);
QGeoCoordinate _newOrigin();
void _processError(const QString &str);
bool _areasCorrect();
bool _getAreas(MeasurementArea **measurementArea, SafeArea **safeArea);
QGeoCoordinate _origin;
QmlObjectListModel _areaList;
bool _initialized;
QString _errorString;
bool _showErrorMessages;
};
......@@ -62,7 +62,7 @@ QString CircularGenerator::abbreviation() { return QStringLiteral("C. Gen."); }
bool CircularGenerator::get(Generator &generator) {
if (this->_d) {
if (this->_d->isValid()) {
if (this->_d->isCorrect()) {
// Prepare data.
auto origin = this->_d->origin();
origin.setAltitude(0);
......@@ -200,7 +200,7 @@ void CircularGenerator::resetReference() {
}
void CircularGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) {
if (this->_d != nullptr && !this->_connectionsEstablished) {
auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......@@ -233,7 +233,7 @@ void CircularGenerator::establishConnections() {
}
void CircularGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) {
if (this->_d != nullptr && this->_connectionsEstablished) {
auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......
......@@ -8,16 +8,26 @@ GeneratorBase::GeneratorBase(QObject *parent)
GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent)
: QObject(parent), _d(d) {
establishConnections();
connect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
}
GeneratorBase::~GeneratorBase() {}
GeneratorBase::Data GeneratorBase::data() const { return _d; }
void GeneratorBase::setData(const Data &d) {
void GeneratorBase::setData(Data d) {
if (d != nullptr) {
if (_d != nullptr) {
disconnect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
}
deleteConnections();
_d = d;
establishConnections();
connect(_d, &AreaData::areaListChanged, this,
&GeneratorBase::_areaListChangedHandler);
}
}
void GeneratorBase::establishConnections() {}
......@@ -27,6 +37,7 @@ void GeneratorBase::deleteConnections() {}
void GeneratorBase::_areaListChangedHandler() {
deleteConnections();
establishConnections();
emit generatorChanged();
}
} // namespace routing
......@@ -33,7 +33,7 @@ public:
virtual bool get(Generator &generator) = 0;
Data data() const;
void setData(const Data &d);
void setData(Data d);
signals:
void generatorChanged();
......
......@@ -48,7 +48,7 @@ QString LinearGenerator::abbreviation() { return QStringLiteral("L. Gen."); }
bool LinearGenerator::get(Generator &generator) {
if (_d) {
if (this->_d->isValid()) {
if (this->_d->isCorrect()) {
// Prepare data.
auto origin = this->_d->origin();
origin.setAltitude(0);
......@@ -148,7 +148,7 @@ Fact *LinearGenerator::alpha() { return &_alpha; }
Fact *LinearGenerator::minLength() { return &_minLength; }
void LinearGenerator::establishConnections() {
if (this->_d && !this->_connectionsEstablished) {
if (this->_d != nullptr && !this->_connectionsEstablished) {
auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......@@ -178,7 +178,7 @@ void LinearGenerator::establishConnections() {
}
void LinearGenerator::deleteConnections() {
if (this->_d && this->_connectionsEstablished) {
if (this->_d != nullptr && this->_connectionsEstablished) {
auto measurementArea =
getGeoArea<const MeasurementArea *>(*this->_d->areaList());
auto serviceArea = getGeoArea<const SafeArea *>(*this->_d->areaList());
......
......@@ -376,14 +376,15 @@ void MeasurementComplexItem::_setAreaData(
}
}
bool MeasurementComplexItem::_updateRoute() {
void MeasurementComplexItem::_updateRoute() {
if (!editing()) {
// Reset data.
this->_route.clear();
this->_variantVector.clear();
this->_variantNames.clear();
emit variantNamesChanged();
if (this->_pAreaData->isValid()) {
if (this->_pAreaData->isCorrect()) {
// Prepare data.
auto origin = this->_pAreaData->origin();
......@@ -391,7 +392,7 @@ bool MeasurementComplexItem::_updateRoute() {
if (!origin.isValid()) {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): origin invalid." << origin;
return false;
return;
}
// Convert safe area.
......@@ -401,7 +402,7 @@ bool MeasurementComplexItem::_updateRoute() {
if (!(geoSafeArea.size() >= 3)) {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea;
return false;
return;
}
for (auto &v : geoSafeArea) {
if (v.isValid()) {
......@@ -410,7 +411,7 @@ bool MeasurementComplexItem::_updateRoute() {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): safe area contains invalid coordinate."
<< geoSafeArea;
return false;
return;
}
}
......@@ -426,22 +427,25 @@ bool MeasurementComplexItem::_updateRoute() {
if (this->_pGenerator->get(g)) {
// Start/Restart routing worker.
this->_pWorker->route(par, g);
return true;
_setState(STATE::ROUTING);
return;
} else {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): generator creation failed.";
return false;
return;
}
} else {
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): pGenerator == nullptr, number of registered "
"generators: "
<< this->_generatorList.size();
return false;
return;
}
} else {
qCDebug(MeasurementComplexItemLog) << "_updateWorker(): plan data invalid.";
return false;
qCDebug(MeasurementComplexItemLog)
<< "_updateWorker(): plan data invalid.";
return;
}
}
}
......@@ -471,7 +475,7 @@ void MeasurementComplexItem::_changeVariant() {
}
auto &newVariantCoordinates = this->_variantVector[variant];
this->_route.swap(newVariantCoordinates);
emit routeChanged();
} else { // error
qCDebug(MeasurementComplexItemLog)
<< "Variant out of bounds (variant =" << variant << ").";
......@@ -497,6 +501,7 @@ void MeasurementComplexItem::_reverseRoute() {
auto &t = this->_route;
std::reverse(t.begin(), t.end());
}
emit routeChanged();
}
}
......@@ -661,27 +666,35 @@ int MeasurementComplexItem::generatorIndex() {
return this->_generatorList.indexOf(this->_pGenerator);
}
void MeasurementComplexItem::editingStart() {
if (!_editing(this->_state)) {
void MeasurementComplexItem::startEditing() {
if (!editing()) {
*_pEditorData = *_pAreaData;
_setAreaData(_pEditorData);
_setState(STATE::EDITING);
}
}
void MeasurementComplexItem::editingStop() {
if (_editing(this->_state)) {
if (_pEditorData->isValid()) {
void MeasurementComplexItem::stopEditing() {
if (editing()) {
bool correct = _pEditorData->isCorrect();
if (correct) {
*_pAreaData = *_pEditorData;
}
_setAreaData(_pAreaData);
_setState(STATE::IDLE);
if (_pEditorData->isValid() && *_pEditorData != *_pAreaData) {
if (correct && *_pEditorData != *_pAreaData) {
_updateRoute();
}
}
}
void MeasurementComplexItem::abortEditing() {
if (editing()) {
_setAreaData(_pAreaData);
_setState(STATE::IDLE);
}
}
void MeasurementComplexItem::_storeRoutingData(
MeasurementComplexItem::PtrRoutingData pRoute) {
if (this->_state == STATE::ROUTING) {
......@@ -781,10 +794,11 @@ void MeasurementComplexItem::_storeRoutingData(
this->_variant.setCookedValue(QVariant(0));
connect(&this->_variant, &Fact::rawValueChanged, this,
&MeasurementComplexItem::_changeVariant);
this->_changeVariant();
this->_setState(STATE::IDLE);
this->_route.swap(this->_variantVector.first());
emit routeChanged();
this->_setState(STATE::IDLE);
} else {
qCDebug(MeasurementComplexItemLog)
<< "_setTransects(): failed, variantVector empty.";
......
......@@ -105,19 +105,26 @@ public:
// 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
//! 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
//! 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
const AreaData *areaData() const;
......@@ -156,7 +163,7 @@ private slots:
// Worker functions.
void _storeRoutingData(PtrRoutingData pRoute);
bool _updateRoute();
void _updateRoute();
void _changeVariant();
void _reverseRoute();
......
#include "WimaPlaner.h"
#include "MissionController.h"
#include "MissionSettingsItem.h"
#include "PlanMasterController.h"
#include "QGCApplication.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
#include "SimpleMissionItem.h"
#include "Geometry/GeoUtilities.h"
#include "Geometry/PlanimetryCalculus.h"
#include "OptimisationTools.h"
#include "CircularSurvey.h"
#include "Geometry/WimaArea.h"
#include "Geometry/WimaAreaData.h"
#include "WimaBridge.h"
#include "WimaStateMachine.h"
using namespace wima_planer_detail;
#include <functional>
QGC_LOGGING_CATEGORY(WimaPlanerLog, "WimaPlanerLog")
class CommandRAII {
std::function<void(void)> f;
public:
CommandRAII(const std::function<void(void)> &fun) : f(fun) {}
~CommandRAII() { f(); }
};
const char *WimaPlaner::wimaFileExtension = "wima";
const char *WimaPlaner::areaItemsName = "AreaItems";
const char *WimaPlaner::missionItemsName = "MissionItems";
WimaPlaner::WimaPlaner(QObject *parent)
: QObject(parent), _masterController(nullptr), _missionController(nullptr),
_currentAreaIndex(-1), _joinedArea(this), _survey(nullptr),
_nemoInterface(this), _stateMachine(new WimaStateMachine),
_areasMonitored(false), _missionControllerMonitored(false),
_progressLocked(false), _synchronized(false) {
connect(this, &WimaPlaner::currentPolygonIndexChanged, this,
&WimaPlaner::updatePolygonInteractivity);
// Monitoring.
enableAreaMonitoring();
// Mission controller not set at this point. Not enabling monitoring.
#ifndef NDEBUG
// for debugging and testing purpose, remove if not needed anymore
connect(&_autoLoadTimer, &QTimer::timeout, this,
&WimaPlaner::autoLoadMission);
_autoLoadTimer.setSingleShot(true);
_autoLoadTimer.start(300);
#endif
// NemoInterface
connect(&this->_nemoInterface, &NemoInterface::progressChanged, this,
&WimaPlaner::nemoInterfaceProgressChangedHandler);
// StateMachine
connect(this->_stateMachine.get(), &WimaStateMachine::upToDateChanged, this,
&WimaPlaner::needsUpdateChanged);
connect(this->_stateMachine.get(), &WimaStateMachine::surveyReadyChanged, this,
&WimaPlaner::readyForSynchronizationChanged);
connect(this->_stateMachine.get(), &WimaStateMachine::surveyReadyChanged, this,
&WimaPlaner::surveyReadyChanged);
}
WimaPlaner::~WimaPlaner() {}
PlanMasterController *WimaPlaner::masterController() {
return _masterController;
}
MissionController *WimaPlaner::missionController() {
return _missionController;
}
QmlObjectListModel *WimaPlaner::visualItems() { return &_visualItems; }
int WimaPlaner::currentPolygonIndex() const { return _currentAreaIndex; }
QString WimaPlaner::currentFile() const { return _currentFile; }
QStringList WimaPlaner::loadNameFilters() const {
QStringList filters;
filters << tr("Supported types (*.%1 *.%2)")
.arg(wimaFileExtension)
.arg(AppSettings::planFileExtension)
<< tr("All Files (*.*)");
return filters;
}
QStringList WimaPlaner::saveNameFilters() const {
QStringList filters;
filters << tr("Supported types (*.%1 *.%2)")
.arg(wimaFileExtension)
.arg(AppSettings::planFileExtension);
return filters;
}
QString WimaPlaner::fileExtension() const { return wimaFileExtension; }
QGeoCoordinate WimaPlaner::joinedAreaCenter() const {
return _joinedArea.center();
}
NemoInterface *WimaPlaner::nemoInterface() { return &_nemoInterface; }
void WimaPlaner::setMasterController(PlanMasterController *masterC) {
if (_masterController != masterC) {
_masterController = masterC;
emit masterControllerChanged();
}
}
void WimaPlaner::setMissionController(MissionController *missionC) {
if (_missionController != missionC) {
disableMissionControllerMonitoring();
_missionController = missionC;
enableMissionControllerMonitoring();
emit missionControllerChanged();
}
}
void WimaPlaner::setCurrentPolygonIndex(int index) {
if (index >= 0 && index < _visualItems.count() &&
index != _currentAreaIndex) {
_currentAreaIndex = index;
emit currentPolygonIndexChanged(index);
}
}
void WimaPlaner::setProgressLocked(bool l) {
if (this->_progressLocked != l) {
this->_progressLocked = l;
emit progressLockedChanged();
if (!this->_progressLocked) {
if (this->_measurementArea.setProgress(this->_nemoInterface.progress()))
this->_update();
}
}
}
bool WimaPlaner::synchronized() { return _synchronized; }
bool WimaPlaner::needsUpdate() { return !this->_stateMachine->upToDate(); }
bool WimaPlaner::readyForSynchronization() {
return this->_stateMachine->surveyReady();
}
bool WimaPlaner::surveyReady() { return this->_stateMachine->surveyReady(); }
bool WimaPlaner::progressLocked() { return this->_progressLocked; }
void WimaPlaner::removeArea(int index) {
if (index >= 0 && index < _visualItems.count()) {
WimaArea *area = qobject_cast<WimaArea *>(_visualItems.removeAt(index));
if (area == nullptr) {
qCWarning(WimaPlanerLog)
<< "removeArea(): nullptr catched, internal error.";
return;
}
area->clear();
area->borderPolygon()->clear();
emit visualItemsChanged();
if (_visualItems.count() == 0) {
// this branch is reached if all items are removed
// to guarentee proper behavior, _currentAreaIndex must be set to a
// invalid value, as on constructor init.
resetAllInteractive();
_currentAreaIndex = -1;
return;
}
if (_currentAreaIndex >= _visualItems.count()) {
setCurrentPolygonIndex(_visualItems.count() - 1);
} else {
updatePolygonInteractivity(_currentAreaIndex);
}
} else {
qCWarning(WimaPlanerLog) << "removeArea(): Index out of bounds!";
}
}
bool WimaPlaner::addMeasurementArea() {
if (!_visualItems.contains(&_measurementArea)) {
_visualItems.append(&_measurementArea);
int newIndex = _visualItems.count() - 1;
setCurrentPolygonIndex(newIndex);
emit visualItemsChanged();
return true;
} else {
return false;
}
}
bool WimaPlaner::addServiceArea() {
if (!_visualItems.contains(&_serviceArea)) {
_visualItems.append(&_serviceArea);
int newIndex = _visualItems.count() - 1;
setCurrentPolygonIndex(newIndex);
emit visualItemsChanged();
return true;
} else {
return false;
}
}
bool WimaPlaner::addCorridor() {
if (!_visualItems.contains(&_corridor)) {
_visualItems.append(&_corridor);
int newIndex = _visualItems.count() - 1;
setCurrentPolygonIndex(newIndex);
emit visualItemsChanged();
return true;
} else {
return false;
}
}
void WimaPlaner::removeAll() {
bool changesApplied = false;
// Delete Pointers.
while (_visualItems.count() > 0) {
removeArea(0);
changesApplied = true;
}
_measurementArea = WimaMeasurementArea();
_joinedArea = WimaJoinedArea();
_serviceArea = WimaServiceArea();
_corridor = WimaCorridor();
// Remove missions items.
_missionController->removeAll();
_currentFile = "";
_survey = nullptr;
emit currentFileChanged();
if (changesApplied)
emit visualItemsChanged();
}
void WimaPlaner::update() { this->_update(); }
void WimaPlaner::_update() {
setSynchronized(false);
switch (this->_stateMachine->state()) {
case STATE::NEEDS_INIT: {
if (this->_measurementArea.ready()) {
this->_stateMachine->updateState(EVENT::INIT_DONE);
this->_update();
} else {
this->_stateMachine->updateState(EVENT::M_AREA_NOT_READY);
}
} break;
case STATE::WAITING_FOR_TILE_UPDATE: {
} break;
case STATE::NEEDS_J_AREA_UPDATE: {
// check if at least service area and measurement area are available
if (_visualItems.indexOf(&_serviceArea) == -1 ||
_visualItems.indexOf(&_measurementArea) == -1)
return;
// Check if polygons have at least three vertices
if (_serviceArea.count() < 3) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"), tr("Service area has less than three vertices."));
return;
}
if (_measurementArea.count() < 3) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"),
tr("Measurement area has less than three vertices."));
return;
}
// Check for simple polygons
if (!_serviceArea.isSimplePolygon()) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"), tr("Service area is not a simple polygon. Only "
"simple polygons allowed."));
return;
}
if (!_corridor.isSimplePolygon() && _corridor.count() > 0) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"), tr("Corridor is not a simple polygon. Only simple "
"polygons allowed."));
return;
}
if (!_measurementArea.isSimplePolygon()) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"), tr("Measurement area is not a simple polygon. Only "
"simple polygons allowed."));
return;
}
if (!_serviceArea.containsCoordinate(_serviceArea.depot())) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"), tr("Depot not inside service area."));
return;
}
// Join areas.
_joinedArea.setPath(_serviceArea.path());
if (_corridor.count() >= 3) {
_joinedArea.join(_corridor);
}
if (!_joinedArea.join(_measurementArea)) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Area Error"),
tr("Not able to join areas. Service and measurement area"
" must be overlapping, or connected through a "
"corridor."));
return;
}
this->_stateMachine->updateState(EVENT::J_AREA_UPDATED);
this->_update();
} break; // STATE::NEEDS_J_AREA_UPDATE
case STATE::NEEDS_SURVEY_UPDATE: {
// Need to insert Survey?
QmlObjectListModel *missionItems = _missionController->visualItems();
int surveyIndex = missionItems->indexOf(_survey);
// Create survey item if not yet present.
if (surveyIndex < 0) {
_missionController->insertComplexMissionItem(
CircularSurvey::name,
_measurementArea.center(), missionItems->count());
_survey = qobject_cast<CircularSurvey *>(
missionItems->get(missionItems->count() - 1));
if (_survey == nullptr) {
qCWarning(WimaPlanerLog) << "_survey == nullptr";
return;
}
// establish connections
connect(_survey, &CircularSurvey::visualTransectPointsChanged, this,
&WimaPlaner::CSVisualTransectPointsChangedHandler);
connect(_survey, &CircularSurvey::destroyed, this,
&WimaPlaner::CSDestroyedHandler);
}
(void)toPlanData(this->_survey->planData());
} break; // STATE::NEEDS_SURVEY_UPDATE
case STATE::WAITING_FOR_SURVEY_UPDATE: {
} break;
case STATE::NEEDS_PATH_UPDATE: {
// Check if survey is present.
QmlObjectListModel *missionItems = _missionController->visualItems();
int surveyIndex = missionItems->indexOf(_survey);
if (surveyIndex < 0) {
this->_stateMachine->updateState(EVENT::SURVEY_DESTROYED);
this->_update();
} else {
// Remove old arrival and return path.
int size = missionItems->count();
for (int i = surveyIndex + 1; i < size; i++)
_missionController->removeVisualItem(surveyIndex + 1);
for (int i = surveyIndex - 1; i > 1; i--)
_missionController->removeVisualItem(i);
// set home position to serArea center
MissionSettingsItem *settingsItem =
qobject_cast<MissionSettingsItem *>(missionItems->get(0));
if (settingsItem == nullptr) {
qCWarning(WimaPlanerLog) << "update(): settingsItem == nullptr";
return;
}
// set altitudes
auto depot = _serviceArea.depot();
depot.setAltitude(0);
settingsItem->setCoordinate(depot);
// set takeoff position
_missionController->insertTakeoffItem(depot, 1, false);
if (_survey->visualTransectPoints().size() == 0) {
qCWarning(WimaPlanerLog) << "update(): survey no points";
return;
}
// calculate path from take off to survey
QGeoCoordinate start = depot;
QGeoCoordinate end = _survey->coordinate();
QVector<QGeoCoordinate> path;
if (!shortestPath(start, end, path)) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Path Error"), tr("Not able to calculate path from "
"depot position to measurement area. Please "
"double check area and route parameters."));
return;
}
for (int i = 1; i < path.count() - 1; i++) {
(void)_missionController->insertSimpleMissionItem(
path[i], missionItems->count() - 1);
}
// calculate return path
start = _survey->exitCoordinate();
end = depot;
path.clear();
if (!shortestPath(start, end, path)) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Path Error"), tr("Not able to calculate path from "
"measurement area to depot position. Please "
"double check area and route parameters."));
return;
}
for (int i = 1; i < path.count() - 1; i++) {
(void)_missionController->insertSimpleMissionItem(
path[i], missionItems->count());
}
// Add waypoint (rover ignores land command).
(void)_missionController->insertSimpleMissionItem(depot,
missionItems->count());
// create land position item
(void)_missionController->insertLandItem(depot, missionItems->count(),
true);
auto surveyIndex = _missionController->visualItems()->indexOf(_survey);
_missionController->setCurrentPlanViewSeqNum(surveyIndex, true);
this->_stateMachine->updateState(EVENT::PATH_UPDATED);
}
} break; // STATE::NEEDS_PATH_UPDATE
case STATE::UP_TO_DATE: {
} break; // STATE::UP_TO_DATE
} // switch
}
void WimaPlaner::CSDestroyedHandler() {
this->_stateMachine->updateState(EVENT::SURVEY_DESTROYED);
}
void WimaPlaner::CSVisualTransectPointsChangedHandler() {
if (this->_survey && this->_survey->calculating()){
this->_stateMachine->updateState(EVENT::SURVEY_UPDATE_TRIGGERED);
} else {
this->_stateMachine->updateState(EVENT::SURVEY_UPDATED);
this->_update();
}
}
void WimaPlaner::mAreaPathChangedHandler() {
this->_stateMachine->updateState(EVENT::M_AREA_PATH_CHANGED);
}
void WimaPlaner::mAreaTilesChangedHandler() {
this->_nemoInterface.setTileData(this->_measurementArea.tileData());
this->_stateMachine->updateState(EVENT::M_AREA_TILES_CHANGED);
}
void WimaPlaner::mAreaProgressChangedHandler() {
this->_stateMachine->updateState(EVENT::M_AREA_PROGRESS_CHANGED);
}
void WimaPlaner::mAreaProgressAcceptedHandler() { this->_update(); }
void WimaPlaner::mAreaReadyChangedHandler() {
if (this->_measurementArea.ready()) {
this->_stateMachine->updateState(EVENT::M_AREA_READY);
} else {
this->_stateMachine->updateState(EVENT::M_AREA_NOT_READY);
}
}
void WimaPlaner::sAreaPathChangedHandler() {
this->_stateMachine->updateState(EVENT::S_AREA_PATH_CHANGED);
}
void WimaPlaner::corridorPathChangedHandler() {
this->_stateMachine->updateState(EVENT::CORRIDOR_PATH_CHANGED);
}
void WimaPlaner::depotChangedHandler() {
this->_stateMachine->updateState(EVENT::DEPOT_CHANGED);
}
void WimaPlaner::missionControllerVisualItemsChangedHandler() {
// Search for survey.
auto surveyIndex = _missionController->visualItems()->indexOf(_survey);
if (surveyIndex < 0) {
// survey not found.
this->_stateMachine->updateState(EVENT::SURVEY_DESTROYED);
} else {
this->_stateMachine->updateState(EVENT::PATH_CHANGED);
}
}
void WimaPlaner::missionControllerWaypointPathChangedHandler() {
missionControllerVisualItemsChangedHandler();
}
void WimaPlaner::missionControllerNewItemsFromVehicleHandler() {
this->_stateMachine->updateState(EVENT::MISSION_ITEMS_DESTROYED);
}
void WimaPlaner::missionControllerMissionItemCountChangedHandler() {
missionControllerVisualItemsChangedHandler();
}
void WimaPlaner::nemoInterfaceProgressChangedHandler() {
auto p = this->_nemoInterface.progress();
WimaBridge::instance()->setProgress(p);
if (!progressLocked()) {
this->_measurementArea.setProgress(p);
this->_update();
}
}
void WimaPlaner::saveToCurrent() { saveToFile(_currentFile); }
void WimaPlaner::saveToFile(const QString &filename) {
if (filename.isEmpty()) {
return;
}
QString planFilename = filename;
if (!QFileInfo(filename).fileName().contains(".")) {
planFilename += QString(".%1").arg(wimaFileExtension);
}
QFile file(planFilename);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Save Error"),
tr("Plan save error %1 : %2").arg(filename).arg(file.errorString()));
_currentFile.clear();
emit currentFileChanged();
} else {
FileType fileType = FileType::WimaFile;
if (planFilename.contains(QString(".%1").arg(wimaFileExtension))) {
fileType = FileType::WimaFile;
} else if (planFilename.contains(
QString(".%1").arg(AppSettings::planFileExtension))) {
fileType = FileType::PlanFile;
} else {
if (planFilename.contains(".")) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Save Error"), tr("File format not supported"));
} else {
qgcApp()->warningMessageBoxOnMainThread(
tr("Save Error"), tr("File without file extension not accepted."));
return;
}
}
QJsonDocument saveDoc = saveToJson(fileType);
file.write(saveDoc.toJson());
if (_currentFile != planFilename) {
_currentFile = planFilename;
emit currentFileChanged();
}
}
}
bool WimaPlaner::loadFromCurrent() { return loadFromFile(_currentFile); }
bool WimaPlaner::loadFromFile(const QString &filename) {
// Remove obsolete connections.
disableAreaMonitoring();
disableMissionControllerMonitoring();
CommandRAII onExit([this] {
this->enableAreaMonitoring();
this->enableMissionControllerMonitoring();
});
// disconnect old survey
if (_survey != nullptr) {
disconnect(_survey, &CircularSurvey::visualTransectPointsChanged, this,
&WimaPlaner::CSVisualTransectPointsChangedHandler);
disconnect(_survey, &CircularSurvey::destroyed, this,
&WimaPlaner::CSDestroyedHandler);
}
setSynchronized(false);
// Precondition.
QString errorString;
QString errorMessage =
tr("Error loading Plan file (%1). %2").arg(filename).arg("%1");
if (filename.isEmpty()) {
return false;
}
QFileInfo fileInfo(filename);
QFile file(filename);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
errorString = file.errorString() + QStringLiteral(" ") + filename;
qgcApp()->warningMessageBoxOnMainThread(tr("Load Error"),
errorMessage.arg(errorString));
return false;
}
if (fileInfo.suffix() == wimaFileExtension) {
QJsonDocument jsonDoc;
QByteArray bytes = file.readAll();
if (!JsonHelper::isJsonFile(bytes, jsonDoc, errorString)) {
qgcApp()->warningMessageBoxOnMainThread(tr("Load Error"),
errorMessage.arg(errorString));
return false;
}
QJsonObject json = jsonDoc.object();
// AreaItems
QJsonArray areaArray = json[areaItemsName].toArray();
_visualItems.clear();
int validAreaCounter = 0;
for (int i = 0; i < areaArray.size() && validAreaCounter < 3; i++) {
QJsonObject jsonArea = areaArray[i].toObject();
if (jsonArea.contains(WimaArea::areaTypeName) &&
jsonArea[WimaArea::areaTypeName].isString()) {
if (jsonArea[WimaArea::areaTypeName] ==
WimaMeasurementArea::WimaMeasurementAreaName) {
bool success = _measurementArea.loadFromJson(jsonArea, errorString);
if (!success) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Load Error"), errorMessage.arg(errorString));
return false;
}
validAreaCounter++;
_visualItems.append(&_measurementArea);
emit visualItemsChanged();
} else if (jsonArea[WimaArea::areaTypeName] ==
WimaServiceArea::wimaServiceAreaName) {
bool success = _serviceArea.loadFromJson(jsonArea, errorString);
if (!success) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Load Error"), errorMessage.arg(errorString));
return false;
}
validAreaCounter++;
_visualItems.append(&_serviceArea);
emit visualItemsChanged();
} else if (jsonArea[WimaArea::areaTypeName] ==
WimaCorridor::WimaCorridorName) {
bool success = _corridor.loadFromJson(jsonArea, errorString);
if (!success) {
qgcApp()->warningMessageBoxOnMainThread(
tr("Load Error"), errorMessage.arg(errorString));
return false;
}
validAreaCounter++;
_visualItems.append(&_corridor);
emit visualItemsChanged();
} else {
errorString +=
QString(tr("%s not supported.\n").arg(WimaArea::areaTypeName));
qgcApp()->warningMessageBoxOnMainThread(
tr("Load Error"), errorMessage.arg(errorString));
return false;
}
} else {
errorString += QString(tr("Invalid or non existing entry for %s.\n")
.arg(WimaArea::areaTypeName));
return false;
}
}
_currentFile.sprintf("%s/%s.%s", fileInfo.path().toLocal8Bit().data(),
fileInfo.completeBaseName().toLocal8Bit().data(),
wimaFileExtension);
emit currentFileChanged();
QJsonObject missionObject = json[missionItemsName].toObject();
QJsonDocument missionJsonDoc = QJsonDocument(missionObject);
// create temporary file with missionItems
QFile temporaryFile;
QString cropedFileName = filename.section("/", 0, -2);
QString temporaryFileName;
for (int i = 0;; i++) {
temporaryFileName =
cropedFileName +
QString("/temp%1.%2").arg(i).arg(AppSettings::planFileExtension);
if (!QFile::exists(temporaryFileName)) {
temporaryFile.setFileName(temporaryFileName);
if (temporaryFile.open(QIODevice::WriteOnly | QIODevice::Text)) {
break;
}
}
if (i > 1000) {
qCWarning(WimaPlanerLog)
<< "loadFromFile(): not able to create temporary file.";
return false;
}
}
temporaryFile.write(missionJsonDoc.toJson());
temporaryFile.close();
// load from temporary file
_masterController->loadFromFile(temporaryFileName);
QmlObjectListModel *missionItems = _missionController->visualItems();
_survey = nullptr;
for (int i = 0; i < missionItems->count(); i++) {
_survey = missionItems->value<CircularSurvey *>(i);
if (_survey != nullptr) {
connect(_survey, &CircularSurvey::visualTransectPointsChanged, this,
&WimaPlaner::CSVisualTransectPointsChangedHandler);
connect(_survey, &CircularSurvey::destroyed, this,
&WimaPlaner::CSDestroyedHandler);
break;
}
}
// remove temporary file
if (!temporaryFile.remove()) {
qCWarning(WimaPlanerLog)
<< "WimaPlaner::loadFromFile(): not able to remove "
"temporary file.";
}
return true;
} else {
errorString += QString(tr("File extension not supported.\n"));
qgcApp()->warningMessageBoxOnMainThread(tr("Load Error"),
errorMessage.arg(errorString));
return false;
}
}
void WimaPlaner::updatePolygonInteractivity(int index) {
if (index >= 0 && index < _visualItems.count()) {
resetAllInteractive();
WimaArea *interactivePoly =
qobject_cast<WimaArea *>(_visualItems.get(index));
if (interactivePoly != nullptr)
interactivePoly->setWimaAreaInteractive(true);
}
}
void WimaPlaner::synchronize() {
if (readyForSynchronization()) {
AreaData planData;
if (toPlanData(planData)) {
WimaBridge::instance()->setPlanData(planData);
setSynchronized(true);
} else {
qCWarning(WimaPlanerLog) << "error creating plan data.";
}
}
}
bool WimaPlaner::shortestPath(const QGeoCoordinate &start,
const QGeoCoordinate &destination,
QVector<QGeoCoordinate> &path) {
using namespace GeoUtilities;
using namespace PolygonCalculus;
QPolygonF polygon2D;
toCartesianList(_joinedArea.coordinateList(), /*origin*/ start, polygon2D);
QPointF start2D(0, 0);
QPointF end2D;
QVector<QPointF> path2D;
toCartesian(destination, start, end2D);
bool retVal =
PolygonCalculus::shortestPath(polygon2D, start2D, end2D, path2D);
toGeoList(path2D, /*origin*/ start, path);
return retVal;
}
void WimaPlaner::setSynchronized(bool s) {
if (this->_synchronized != s) {
this->_synchronized = s;
emit this->synchronizedChanged();
}
}
void WimaPlaner::enableAreaMonitoring() {
if (!areasMonitored()) {
connect(&this->_measurementArea, &WimaArea::pathChanged, this,
&WimaPlaner::mAreaPathChangedHandler);
connect(&this->_measurementArea, &WimaMeasurementArea::tilesChanged, this,
&WimaPlaner::mAreaTilesChangedHandler);
connect(&this->_measurementArea, &WimaMeasurementArea::progressChanged,
this, &WimaPlaner::mAreaProgressChangedHandler);
connect(&this->_measurementArea, &WimaMeasurementArea::progressAccepted,
this, &WimaPlaner::mAreaProgressAcceptedHandler);
connect(&this->_measurementArea, &WimaMeasurementArea::readyChanged, this,
&WimaPlaner::mAreaReadyChangedHandler);
connect(&this->_serviceArea, &WimaArea::pathChanged, this,
&WimaPlaner::sAreaPathChangedHandler);
connect(&this->_serviceArea, &WimaServiceArea::depotChanged, this,
&WimaPlaner::depotChangedHandler);
connect(&this->_corridor, &WimaArea::pathChanged, this,
&WimaPlaner::corridorPathChangedHandler);
this->_areasMonitored = true;
}
}
void WimaPlaner::disableAreaMonitoring() {
if (areasMonitored()) {
disconnect(&this->_measurementArea, &WimaArea::pathChanged, this,
&WimaPlaner::mAreaPathChangedHandler);
disconnect(&this->_measurementArea, &WimaMeasurementArea::tilesChanged,
this, &WimaPlaner::mAreaTilesChangedHandler);
disconnect(&this->_measurementArea, &WimaMeasurementArea::progressChanged,
this, &WimaPlaner::mAreaProgressChangedHandler);
disconnect(&this->_measurementArea, &WimaMeasurementArea::progressAccepted,
this, &WimaPlaner::mAreaProgressAcceptedHandler);
disconnect(&this->_measurementArea, &WimaMeasurementArea::readyChanged,
this, &WimaPlaner::mAreaReadyChangedHandler);
disconnect(&this->_serviceArea, &WimaArea::pathChanged, this,
&WimaPlaner::sAreaPathChangedHandler);
disconnect(&this->_serviceArea, &WimaServiceArea::depotChanged, this,
&WimaPlaner::depotChangedHandler);
disconnect(&this->_corridor, &WimaArea::pathChanged, this,
&WimaPlaner::corridorPathChangedHandler);
this->_areasMonitored = false;
}
}
void WimaPlaner::enableMissionControllerMonitoring() {
if (!missionControllerMonitored() && this->missionController() != nullptr) {
connect(this->missionController(), &MissionController::visualItemsChanged,
this, &WimaPlaner::missionControllerVisualItemsChangedHandler);
connect(this->missionController(), &MissionController::waypointPathChanged,
this, &WimaPlaner::missionControllerWaypointPathChangedHandler);
connect(this->missionController(), &MissionController::newItemsFromVehicle,
this, &WimaPlaner::missionControllerNewItemsFromVehicleHandler);
connect(this->missionController(),
&MissionController::missionItemCountChanged, this,
&WimaPlaner::missionControllerMissionItemCountChangedHandler);
this->_missionControllerMonitored = true;
}
}
void WimaPlaner::disableMissionControllerMonitoring() {
if (missionControllerMonitored() && this->missionController() != nullptr) {
disconnect(this->missionController(),
&MissionController::visualItemsChanged, this,
&WimaPlaner::missionControllerVisualItemsChangedHandler);
disconnect(this->missionController(),
&MissionController::waypointPathChanged, this,
&WimaPlaner::missionControllerWaypointPathChangedHandler);
disconnect(this->missionController(),
&MissionController::newItemsFromVehicle, this,
&WimaPlaner::missionControllerNewItemsFromVehicleHandler);
disconnect(this->missionController(),
&MissionController::missionItemCountChanged, this,
&WimaPlaner::missionControllerMissionItemCountChangedHandler);
this->_missionControllerMonitored = false;
}
}
bool WimaPlaner::areasMonitored() { return this->_areasMonitored; }
bool WimaPlaner::missionControllerMonitored() {
return this->_missionControllerMonitored;
}
void WimaPlaner::resetAllInteractive() {
// Marks all areas as inactive (area.interactive == false)
int itemCount = _visualItems.count();
if (itemCount > 0) {
for (int i = 0; i < itemCount; i++) {
WimaArea *iteratorPoly = qobject_cast<WimaArea *>(_visualItems.get(i));
iteratorPoly->setWimaAreaInteractive(false);
}
}
}
void WimaPlaner::setInteractive() {
updatePolygonInteractivity(_currentAreaIndex);
}
/*!
* \fn WimaPlanData WimaPlaner::toPlanData()
*
* Returns a \c WimaPlanData object containing information about the current
* mission. The \c WimaPlanData object holds only the data which is relevant
* for the \c WimaController class. Should only be called if update() was
* successful.
*
* \sa WimaController, WimaPlanData
*/
bool WimaPlaner::toPlanData(AreaData &planData) {
planData.append(_measurementArea);
planData.append(_serviceArea);
planData.append(_corridor);
planData.append(_joinedArea);
return planData.isValid();
}
#ifndef NDEBUG
void WimaPlaner::autoLoadMission() {
loadFromFile("/home/valentin/Desktop/drones/qgroundcontrol/Paths/"
"KlingenbachTest.wima");
synchronize();
}
#endif
QJsonDocument WimaPlaner::saveToJson(FileType fileType) {
/// This function save all areas (of WimaPlaner) and all mission items (of
/// MissionController) to a QJsonDocument
/// @param fileType is either WimaFile or PlanFile (enum), if fileType ==
/// PlanFile only mission items are stored
QJsonObject json;
if (fileType == FileType::WimaFile) {
QJsonArray jsonArray;
for (int i = 0; i < _visualItems.count(); i++) {
QJsonObject json;
WimaArea *area = qobject_cast<WimaArea *>(_visualItems.get(i));
if (area == nullptr) {
qCWarning(WimaPlanerLog) << "saveing, area == nullptr!";
return QJsonDocument();
}
// check the type of area, create and append the JsonObject to the
// JsonArray once determined
WimaMeasurementArea *opArea = qobject_cast<WimaMeasurementArea *>(area);
if (opArea != nullptr) {
opArea->saveToJson(json);
jsonArray.append(json);
continue;
}
WimaServiceArea *serArea = qobject_cast<WimaServiceArea *>(area);
if (serArea != nullptr) {
serArea->saveToJson(json);
jsonArray.append(json);
continue;
}
WimaCorridor *corridor = qobject_cast<WimaCorridor *>(area);
if (corridor != nullptr) {
corridor->saveToJson(json);
jsonArray.append(json);
continue;
}
// if non of the obove branches was trigger, type must be WimaArea
area->saveToJson(json);
jsonArray.append(json);
}
json[areaItemsName] = jsonArray;
json[missionItemsName] = _masterController->saveToJson().object();
return QJsonDocument(json);
} else if (fileType == FileType::PlanFile) {
return _masterController->saveToJson();
}
return QJsonDocument(json);
}
#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
};
#include "WimaStateMachine.h"
#include "QGCLoggingCategory.h"
#include <QDebug>
const QLoggingCategory &WimaPlanerLog();
namespace wima_planer_detail {
template <typename T>
constexpr typename std::underlying_type<T>::type integral(T value) {
return static_cast<typename std::underlying_type<T>::type>(value);
}
WimaStateMachine::WimaStateMachine(QObject *parent)
: QObject(parent), _state(STATE::NEEDS_INIT) {}
STATE WimaStateMachine::state() { return this->_state; }
void WimaStateMachine::updateState(EVENT e) {
qCDebug(WimaPlanerLog) << "StateMachine::updateState(): event:" << e;
switch (this->_state) {
case STATE::NEEDS_INIT:
switch (e) {
case EVENT::INIT_DONE:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_NOT_READY:
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
case EVENT::SURVEY_UPDATE_TRIGGERED:
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::NEEDS_INIT
case STATE::WAITING_FOR_TILE_UPDATE:
switch (e) {
case EVENT::INIT_DONE:
case EVENT::M_AREA_NOT_READY:
break;
case EVENT::M_AREA_READY:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
case EVENT::SURVEY_UPDATE_TRIGGERED:
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::NEEDS_INIT
case STATE::NEEDS_J_AREA_UPDATE:
switch (e) {
case EVENT::INIT_DONE:
break;
case EVENT::M_AREA_NOT_READY:
setState(STATE::WAITING_FOR_TILE_UPDATE);
break;
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
break;
case EVENT::J_AREA_UPDATED:
setState(STATE::NEEDS_SURVEY_UPDATE);
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
case EVENT::SURVEY_UPDATE_TRIGGERED:
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::NEEDS_J_AREA_UPDATE
case STATE::NEEDS_SURVEY_UPDATE:
switch (e) {
case EVENT::INIT_DONE:
case EVENT::M_AREA_NOT_READY:
setState(STATE::WAITING_FOR_TILE_UPDATE);
break;
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
break;
case EVENT::SURVEY_UPDATE_TRIGGERED:
setState(STATE::WAITING_FOR_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::NEEDS_SURVEY_UPDATE
case STATE::WAITING_FOR_SURVEY_UPDATE:
switch (e) {
case EVENT::INIT_DONE:
case EVENT::M_AREA_NOT_READY:
setState(STATE::WAITING_FOR_TILE_UPDATE);
break;
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
setState(STATE::NEEDS_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATE_TRIGGERED:
break;
case EVENT::SURVEY_UPDATED:
setState(STATE::NEEDS_PATH_UPDATE);
case EVENT::PATH_CHANGED:
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::WAYTING_FOR_SURVEY_UPDATE
case STATE::NEEDS_PATH_UPDATE:
switch (e) {
case EVENT::INIT_DONE:
case EVENT::M_AREA_NOT_READY:
setState(STATE::WAITING_FOR_TILE_UPDATE);
break;
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
setState(STATE::NEEDS_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATE_TRIGGERED:
setState(STATE::WAITING_FOR_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
break;
case EVENT::PATH_UPDATED:
setState(STATE::UP_TO_DATE);
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::NEEDS_PATH_UPDATE
case STATE::UP_TO_DATE:
switch (e) {
case EVENT::INIT_DONE:
case EVENT::M_AREA_NOT_READY:
setState(STATE::WAITING_FOR_TILE_UPDATE);
break;
case EVENT::M_AREA_READY:
case EVENT::M_AREA_PATH_CHANGED:
case EVENT::S_AREA_PATH_CHANGED:
case EVENT::CORRIDOR_PATH_CHANGED:
setState(STATE::NEEDS_J_AREA_UPDATE);
break;
case EVENT::M_AREA_TILES_CHANGED:
case EVENT::M_AREA_PROGRESS_CHANGED:
case EVENT::J_AREA_UPDATED:
case EVENT::DEPOT_CHANGED:
case EVENT::SURVEY_DESTROYED:
case EVENT::MISSION_ITEMS_DESTROYED:
setState(STATE::NEEDS_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATE_TRIGGERED:
setState(STATE::WAITING_FOR_SURVEY_UPDATE);
break;
case EVENT::SURVEY_UPDATED:
case EVENT::PATH_CHANGED:
setState(STATE::NEEDS_PATH_UPDATE);
break;
case EVENT::PATH_UPDATED:
break;
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown event: " << e;
Q_ASSERT(false);
}
break; // STATE::UP_TO_DATE
qCCritical(WimaPlanerLog)
<< "StateMachine::updateState: Unknown state: " << this->_state;
Q_ASSERT(false);
}
}
bool WimaStateMachine::upToDate() { return upToDate(this->_state); }
bool WimaStateMachine::surveyReady() { return surveyReady(this->_state); }
void WimaStateMachine::setState(STATE s) {
if (this->_state != s) {
auto oldState = this->_state;
this->_state = s;
emit stateChanged();
if (upToDate(oldState) != upToDate(s)) {
emit upToDateChanged();
}
if (surveyReady(oldState) != surveyReady(s)) {
emit surveyReadyChanged();
}
qCDebug(WimaPlanerLog) << "StateMachine::setState():" << oldState << "->"
<< s;
}
}
bool WimaStateMachine::surveyReady(STATE s) {
// Using a switch to enable compiler checking of used states.
bool value = false;
switch (s) {
case STATE::NEEDS_INIT:
case STATE::WAITING_FOR_TILE_UPDATE:
case STATE::NEEDS_J_AREA_UPDATE:
case STATE::NEEDS_SURVEY_UPDATE:
case STATE::WAITING_FOR_SURVEY_UPDATE:
break;
case STATE::NEEDS_PATH_UPDATE:
case STATE::UP_TO_DATE:
value = true;
break;
}
return value;
}
bool WimaStateMachine::upToDate(STATE s) {
// Using a switch to enable compiler checking of used states.
bool value = false;
switch (s) {
case STATE::NEEDS_INIT:
case STATE::WAITING_FOR_TILE_UPDATE:
case STATE::NEEDS_J_AREA_UPDATE:
case STATE::NEEDS_SURVEY_UPDATE:
case STATE::WAITING_FOR_SURVEY_UPDATE:
case STATE::NEEDS_PATH_UPDATE:
break;
case STATE::UP_TO_DATE:
value = true;
break;
}
return value;
}
QDebug &operator<<(QDebug &ds, STATE s) {
switch (s) {
case STATE::NEEDS_INIT:
ds << "NEEDS_INIT";
break;
case STATE::WAITING_FOR_TILE_UPDATE:
ds << "WAITING_FOR_TILE_UPDATE";
break;
case STATE::NEEDS_J_AREA_UPDATE:
ds << "NEEDS_J_AREA_UPDATE";
break;
case STATE::NEEDS_SURVEY_UPDATE:
ds << "NEEDS_SURVEY_UPDATE";
break;
case STATE::WAITING_FOR_SURVEY_UPDATE:
ds << "WAITING_FOR_SURVEY_UPDATE";
break;
case STATE::NEEDS_PATH_UPDATE:
ds << "NEEDS_PATH_UPDATE";
break;
case STATE::UP_TO_DATE:
ds << "UP_TO_DATE";
break;
}
return ds;
}
QDebug &operator<<(QDebug &ds, EVENT s) {
switch (s) {
case EVENT::INIT_DONE:
ds << "INIT_DONE";
break;
case EVENT::M_AREA_NOT_READY:
ds << "M_AREA_NOT_READY";
break;
case EVENT::M_AREA_READY:
ds << "M_AREA_READY";
break;
case EVENT::M_AREA_PATH_CHANGED:
ds << "M_AREA_PATH_CHANGED";
break;
case EVENT::S_AREA_PATH_CHANGED:
ds << "S_AREA_PATH_CHANGED";
break;
case EVENT::CORRIDOR_PATH_CHANGED:
ds << "CORRIDOR_PATH_CHANGED";
break;
case EVENT::M_AREA_TILES_CHANGED:
ds << "M_AREA_TILES_CHANGED";
break;
case EVENT::M_AREA_PROGRESS_CHANGED:
ds << "M_AREA_PROGRESS_CHANGED";
break;
case EVENT::J_AREA_UPDATED:
ds << "J_AREA_UPDATED";
break;
case EVENT::DEPOT_CHANGED:
ds << "DEPOT_CHANGED";
break;
case EVENT::SURVEY_DESTROYED:
ds << "SURVEY_DESTROYED";
break;
case EVENT::MISSION_ITEMS_DESTROYED:
ds << "MISSION_ITEMS_DESTROYED";
break;
case EVENT::SURVEY_UPDATE_TRIGGERED:
ds << "SURVEY_UPDATE_TRIGGERED";
break;
case EVENT::SURVEY_UPDATED:
ds << "SURVEY_UPDATED";
break;
case EVENT::PATH_CHANGED:
ds << "PATH_CHANGED";
break;
case EVENT::PATH_UPDATED:
ds << "PATH_UPDATED";
break;
}
return ds;
}
} // namespace wima_planer_detail
#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 "snake.h"
#include "QGCLoggingCategory.h"
#include "QGCQGeoCoordinate.h"
#include <QDebug>
QGC_LOGGING_CATEGORY(GeoAreaLog, "GeoAreaLog")
const char *GeoArea::wimaAreaName = "GeoArea";
const char *GeoArea::areaTypeName = "AreaType";
const char *GeoArea::settingsGroup = "GeoArea";
......@@ -10,7 +17,7 @@ const char *GeoArea::settingsGroup = "GeoArea";
GeoArea::GeoArea(QObject *parent) : QGCMapPolygon(parent) { init(); }
GeoArea::GeoArea(const GeoArea &other, QObject *parent)
: QGCMapPolygon(other, parent) {
: QGCMapPolygon(other, parent), _errorString(other._errorString) {
init();
}
......@@ -34,13 +41,40 @@ bool GeoArea::loadFromJson(const QJsonObject &json, QString &errorString) {
return true;
}
bool GeoArea::isSimplePolygon() {
qWarning() << "WimaArea::isSimplePolygon: impl. missing.";
bool GeoArea::isCorrect() {
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;
}
QString GeoArea::errorString() const { return this->_errorString; }
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,
QObject *parent) {
// Check if elements are valid.
......
......@@ -13,6 +13,7 @@ public:
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT)
Q_PROPERTY(QString editorQML READ editorQML CONSTANT)
Q_PROPERTY(QString errorString READ errorString NOTIFY errorStringChanged)
virtual QString mapVisualQML(void) const = 0;
virtual QString editorQML(void) const = 0;
......@@ -23,15 +24,25 @@ public:
virtual GeoArea *clone(QObject *parent = nullptr) const = 0;
bool isSimplePolygon();
Q_INVOKABLE virtual bool isCorrect();
Q_INVOKABLE QString errorString() const;
// static Members
static const char *wimaAreaName;
static const char *areaTypeName;
static const char *settingsGroup;
signals:
void errorStringChanged();
protected:
void setErrorString(const QString &str);
void setErrorString(const std::string &str);
private:
void init();
QString _errorString;
};
// Example usage:
......
......@@ -91,7 +91,7 @@ MeasurementArea::MeasurementArea(QObject *parent)
MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent)
: GeoArea(other, parent),
_metaDataMap(FactMetaData::createMapFromJsonFile(
QStringLiteral(":/json/WimaMeasurementArea.SettingsGroup.json"),
QStringLiteral(":/json/MeasurementArea.SettingsGroup.json"),
this /* QObject parent */)),
_tileHeight(SettingsFact(settingsGroup, _metaDataMap[tileHeightName],
this /* QObject parent */)),
......@@ -103,6 +103,13 @@ MeasurementArea::MeasurementArea(const MeasurementArea &other, QObject *parent)
_showTiles(SettingsFact(settingsGroup, _metaDataMap[showTilesName],
this /* QObject parent */)),
_state(STATE::IDLE) {
_tileHeight = other._tileHeight;
_tileWidth = other._tileWidth;
_minTileAreaPercent = other._minTileAreaPercent;
_showTiles = other._showTiles;
_progress = other._progress;
_tileData = other._tileData;
init();
}
......@@ -115,6 +122,7 @@ MeasurementArea::~MeasurementArea() {}
QString MeasurementArea::mapVisualQML() const {
return QStringLiteral("MeasurementAreaMapVisual.qml");
// return QStringLiteral("");
}
QString MeasurementArea::editorQML() const {
......@@ -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) {
if (ready()) {
if (p.size() == this->tiles()->count() && this->_progress != p) {
......@@ -240,7 +260,7 @@ void MeasurementArea::doUpdate() {
const auto estNumTiles = totalArea / tileArea;
// Check some conditions.
if (long(std::ceil(estNumTiles.value())) <= SNAKE_MAX_TILES &&
this->count() >= 3 && this->isSimplePolygon()) {
this->GeoArea::isCorrect()) {
setState(STATE::UPDATEING);
auto polygon = this->coordinateList();
......
......@@ -50,6 +50,7 @@ public:
MeasurementArea *clone(QObject *parent = nullptr) const;
void saveToJson(QJsonObject &json) override;
bool loadFromJson(const QJsonObject &json, QString &errorString) override;
Q_INVOKABLE virtual bool isCorrect();
// Property getters.
Fact *tileHeight();
......
......@@ -25,7 +25,10 @@ SafeArea &SafeArea::operator=(const SafeArea &other) {
return *this;
}
QString SafeArea::mapVisualQML() const { return "SafeAreaMapVisual.qml"; }
QString SafeArea::mapVisualQML() const {
return "SafeAreaMapVisual.qml";
// return "";
}
QString SafeArea::editorQML() const { return "SafeAreaEditor.qml"; }
......@@ -37,11 +40,41 @@ const QGeoCoordinate &SafeArea::depot() const { return _depot; }
QGeoCoordinate SafeArea::depotQml() const { return _depot; }
bool SafeArea::setDepot(const QGeoCoordinate &coordinate) {
if (_depot.latitude() != coordinate.latitude() ||
_depot.longitude() != coordinate.longitude()) {
if (this->containsCoordinate(coordinate)) {
_depot = coordinate;
void SafeArea::putDepotInside() {
if (!this->containsCoordinate(this->_depot) &&
this->pathModel().count() > 0) {
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 {
// 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);
emit depotChanged();
return true;
......@@ -89,38 +122,22 @@ bool SafeArea::loadFromJson(const QJsonObject &json, QString &errorString) {
return retVal;
}
void SafeArea::init() {
this->setObjectName(safeAreaName);
connect(this, &GeoArea::pathChanged, [this] {
if (!this->_depot.isValid() || !this->containsCoordinate(this->_depot)) {
if (this->containsCoordinate(this->center())) {
// Use center.
this->setDepot(this->center());
} 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;
}
bool SafeArea::isCorrect() {
if (GeoArea::isCorrect()) {
if (this->_depot.isValid()) {
if (this->containsCoordinate(this->_depot)) {
return true;
} else {
qCCritical(SafeAreaLog) << "init(): nullptr catched!";
}
setErrorString(tr("Depot outside Safe Area"));
}
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:
Q_PROPERTY(
QGeoCoordinate depot READ depotQml WRITE setDepot NOTIFY depotChanged)
// Overrides from WimaPolygon
// Overrides from GeoArea
QString mapVisualQML(void) const override;
QString editorQML(void) const override;
SafeArea *clone(QObject *parent = nullptr) const;
void saveToJson(QJsonObject &json) override;
bool loadFromJson(const QJsonObject &json, QString &errorString) override;
Q_INVOKABLE virtual bool isCorrect();
// Property acessors
const QGeoCoordinate &depot(void) const;
bool setDepot(const QGeoCoordinate &newDepot);
QGeoCoordinate depotQml(void) const;
// static Members
......@@ -31,9 +33,8 @@ public:
static const char *depotAltitudeName;
signals:
void depotChanged(void);
public slots:
bool setDepot(const QGeoCoordinate &coordinate);
private slots:
void putDepotInside();
private:
// Member Methodes
......
......@@ -5,46 +5,46 @@
[
{
"name": "TileHeight",
"shortDescription": "The height of a tile",
"shrotDesc": "The height of a tile",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 2,
"defaultValue": 5
"default": 5
},
{
"name": "TileWidth",
"shortDescription": "The height of a tile",
"shrotDesc": "The height of a tile",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 2,
"defaultValue": 5
"default": 5
},
{
"name": "MinTileAreaPercent",
"shortDescription": "The minimal allowed area in percent (of width*height).",
"shrotDesc": "The minimal allowed area in percent (of width*height).",
"type": "double",
"units": "%",
"min": 0,
"max": 100,
"decimalPlaces": 2,
"defaultValue": 20
"default": 20
},
{
"name": "ShowTiles",
"shortDescription": "Show tiles",
"shrotDesc": "Show tiles",
"type": "bool",
"defaultValue": true
"default": true
},
{
"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",
"units": "m",
"min": 0,
"decimalPlaces": 1,
"defaultValue": 5
"default": 5
}
]
}
......@@ -20,6 +20,9 @@ namespace bu = boost::units;
#include <GeographicLib/Geocentric.hpp>
#include <GeographicLib/LocalCartesian.hpp>
#include "QGCQGeoCoordinate.h"
#include "QmlObjectListModel.h"
using namespace std;
namespace snake {
......@@ -105,13 +108,11 @@ template <class GeoPoint1, class GeoPoint2>
void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, FPoint &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(),
origin.altitude(), earth);
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
earth);
double x = 0, y = 0, z = 0;
auto alt = in.altitude();
alt = std::isnan(alt) ? 0 : alt;
proj.Forward(in.latitude(), in.longitude(), alt, x, y, z);
proj.Forward(in.latitude(), in.longitude(), 0, x, y, z);
out.set<0>(x);
out.set<1>(y);
(void)z;
......@@ -121,13 +122,11 @@ template <class GeoPoint1, class GeoPoint2, class Point>
void toENU(const GeoPoint1 &origin, const GeoPoint2 &in, Point &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(),
origin.altitude(), earth);
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
earth);
double x = 0, y = 0, z = 0;
auto alt = in.altitude();
alt = std::isnan(alt) ? 0 : alt;
proj.Forward(in.latitude(), in.longitude(), alt, x, y, z);
proj.Forward(in.latitude(), in.longitude(), 0, x, y, z);
out.setX(x);
out.setY(y);
(void)z;
......@@ -137,8 +136,8 @@ template <class GeoPoint>
void fromENU(const GeoPoint &origin, const FPoint &in, GeoPoint &out) {
static GeographicLib::Geocentric earth(GeographicLib::Constants::WGS84_a(),
GeographicLib::Constants::WGS84_f());
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(),
origin.altitude(), earth);
GeographicLib::LocalCartesian proj(origin.latitude(), origin.longitude(), 0,
earth);
double lat = 0, lon = 0, alt = 0;
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) {
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>
void areaFromEnu(const GeoPoint &origin, Container1 &in,
const Container2 &out) {
void areaFromEnu(const GeoPoint &origin, const Container1 &in,
Container2 &out) {
for (auto &vertex : in) {
typename Container2::value_type p;
fromENU(origin, vertex, p);
......@@ -177,7 +193,7 @@ void areaFromEnu(const GeoPoint &origin, Container1 &in,
}
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()) {
typename Container::value_type p;
fromENU(origin, vertex, p);
......
......@@ -5,31 +5,31 @@
[
{
"name": "TransectDistance",
"shortDescription": "The distance between transects.",
"shortDesc": "The distance between transects.",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 1,
"defaultValue": 5.0
"default": 5.0
},
{
"name": "DeltaAlpha",
"shortDescription": "Angle discretisation.",
"shortDesc": "Angle discretisation.",
"type": "double",
"units": "Deg",
"min": 0.3,
"max": 90,
"decimalPlaces": 1,
"defaultValue": 5.0
"default": 5.0
},
{
"name": "MinLength",
"shortDescription": "The minimal transect length.",
"shortDesc": "The minimal transect length.",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 1,
"defaultValue": 5.0
"default": 5.0
}
]
}
......@@ -5,31 +5,31 @@
[
{
"name": "TransectDistance",
"shortDescription": "The distance between transects.",
"shrotDesc": "The distan",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 1,
"defaultValue": 5.0
"default": 5.0
},
{
"name": "Alpha",
"shortDescription": "Transect angle.",
"shrotDesc": "Transect angle.",
"type": "double",
"units": "Deg",
"min": 0,
"max": 180,
"decimalPlaces": 1,
"defaultValue": 0.0
"default": 0.0
},
{
"name": "MinLength",
"shortDescription": "The minimal transect length.",
"shrotDesc": "The minimal transect length.",
"type": "double",
"units": "m",
"min": 0.3,
"decimalPlaces": 1,
"defaultValue": 5.0
"default": 5.0
}
]
}
......@@ -5,18 +5,18 @@
[
{
"name": "Variant",
"shortDescription": "Route variant.",
"shrotDesc": "Route variant.",
"type": "uint64",
"defaultValue": 0
"default": 0
},
{
"name": "Altitude",
"shortDescription": "Altitude",
"shrotDesc": "Altitude",
"type": "double",
"units": "m",
"min": 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
GridLayout {
id: grid
property var generator // CircularGenerator
property var generator: undefined // CircularGenerator
property var availableWidth
property real _margin: ScreenTools.defaultFontPixelWidth / 2
......@@ -18,6 +18,10 @@ GridLayout {
rowSpacing: _margin
columns: 2
Component.onCompleted: {
console.assert(generator !== undefined, "please set the generator property")
}
QGCLabel { text: qsTr("Distance") }
FactTextField {
fact: generator.distance
......
......@@ -36,11 +36,12 @@ Item {
var component = Qt.createComponent(_root.geoArea.mapVisualQML)
if (component.status === Component.Error) {
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)
}
}
}
Component.onDestruction: {
if (_visualItem) {
......
// 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
GridLayout {
property var generator // CircularGenerator
property var availableWidth
property var generator: undefined // LinearGenerator
property var availableWidth: 300
property real _margin: ScreenTools.defaultFontPixelWidth / 2
width: availableWidth
......@@ -17,6 +17,10 @@ GridLayout {
rowSpacing: _margin
columns: 2
Component.onCompleted: {
console.assert(generator !== undefined, "please set the generator property")
}
QGCLabel { text: qsTr("Distance") }
FactTextField {
fact: generator.distance
......
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
......@@ -13,140 +10,98 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Operating Area items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property bool polygonInteractive: areaItem.interactive
property var polygon: areaItem
property bool initNecesarry: true
onPolygonInteractiveChanged: {
polygon.interactive = polygonInteractive;
}
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Column {
GridLayout {
id: editorColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
SectionHeader {
id: settingsHeader
text: qsTr("General")
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: settingsHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columns: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Offset") }
width: availableWidth
FactTextField {
fact: areaItem.borderPolygonOffset
Layout.fillWidth: true
}
}
property var geoArea: undefined
property int availableWidth
FactCheckBox {
text: qsTr("Border Polygon")
fact: areaItem.showBorderPolygon
//enabled: !missionItem.followTerrain
}
property real _margin: ScreenTools.defaultFontPixelWidth / 2
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: 1
Component.onCompleted: {
console.assert(geoArea !== undefined, "please set the areaItem property")
}
} // Column - Settings
SectionHeader {
id: tilesHeader
text: qsTr("Tiles")
Layout.columnSpan: 2
Layout.fillWidth: true
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
GridLayout{
visible: tilesHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
Layout.fillWidth: true
Layout.columnSpan: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Height") }
QGCLabel {
text: qsTr("Height")
Layout.fillWidth: true
}
FactTextField {
fact: areaItem.tileHeight
fact: geoArea.tileHeight
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Width") }
QGCLabel {
text: qsTr("Width")
Layout.fillWidth: true
}
FactTextField {
fact: areaItem.tileWidth
fact: geoArea.tileWidth
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Min. Area") }
QGCLabel {
text: qsTr("Min. Area")
Layout.fillWidth: true
}
FactTextField {
fact: areaItem.minTileArea
fact: geoArea.minTileArea
Layout.fillWidth: true
}
FactCheckBox {
text: qsTr("Show Tiles")
fact: areaItem.showTiles
fact: geoArea.showTiles
}
}
} // Tile GridLayout
} // Tile Column
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
Layout.fillWidth: true
Layout.columnSpan: 2
}
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
GridLayout{
visible: statsHeader.checked
Layout.fillWidth: true
Layout.columnSpan: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
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: geoArea.tiles.count }
QGCLabel { text: qsTr("Max. Tiles") }
QGCLabel { text: areaItem.maxTiles }
QGCLabel { text: geoArea.maxTiles }
}
} // Column
} // Rectangle
} // Column
......@@ -44,6 +44,7 @@ Item {
borderColor: "green"
interiorColor: "green"
altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision
z: QGroundControl.zOrderMapItems-1
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
......@@ -13,10 +13,11 @@ import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
import MeasurementComplexItem 1.0 as MCI
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
height: visible ? (mainColumn.height + (_margin * 2)) : 0
width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
......@@ -31,273 +32,107 @@ Rectangle {
QGroundControl.multiVehicleManager.activeVehicle :
QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _missionItem: missionItem
property var _generator: missionItem.generator
property var _generatorEditor: undefined
property var _areaData: missionItem.areaData
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Component.onCompleted: {
_addGeneratorEditor()
}
Component.onDestruction: {
_destroyGeneratorEditor()
}
on_GeneratorChanged: {
_destroyGeneratorEditor()
_addGeneratorEditor()
}
Column { // main column
id: editorColumn
ColumnLayout { // main Column
id: mainColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
// ColumnLayout {
// id: wizardColumn
// anchors.left: parent.left
// anchors.right: parent.right
// spacing: _margin
// visible: !_missionItem.surveyAreaPolygon.isValid || _missionItem.wizardMode
// ColumnLayout {
// Layout.fillWidth: true
// spacing: _margin
// visible: !_polygonDone
// QGCLabel {
// Layout.fillWidth: true
// wrapMode: Text.WordWrap
// horizontalAlignment: Text.AlignHCenter
// text: qsTr("Use the Polygon Tools to create the polygon which outlines your survey area.")
// }
// }
// }
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
//visible: !wizardColumn.visible
// QGCTabBar {
// id: tabBar
// anchors.left: parent.left
// anchors.right: parent.right
// Component.onCompleted: currentIndex = QGroundControl.settingsManager.planViewSettings.displayPresetsTabFirst.rawValue ? 2 : 0
// QGCTabButton { icon.source: "/qmlimages/PatternGrid.png"; icon.height: ScreenTools.defaultFontPixelHeight }
// QGCTabButton { icon.source: "/qmlimages/PatternCamera.png"; icon.height: ScreenTools.defaultFontPixelHeight }
// QGCTabButton { icon.source: "/qmlimages/PatternTerrain.png"; icon.height: ScreenTools.defaultFontPixelHeight }
// QGCTabButton { icon.source: "/qmlimages/PatternPresets.png"; icon.height: ScreenTools.defaultFontPixelHeight }
// }
// Grid tab
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
// visible: tabBar.currentIndex === 0
SectionHeader {
id: generalHeader
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("General")
}
GridLayout {
id: generalGrid
anchors.left: parent.left
anchors.right: parent.right
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
id: tipLabel
Layout.fillWidth: true
wrapMode: Text.WordWrap
horizontalAlignment: Text.AlignHCenter
text: qsTr("Use the Area Editor to modify areas.")
visible: areaDataEditor.visible
}
GridLayout{
Layout.columnSpan: 2
GridLayout {
id: editorSelector
Layout.fillWidth: true
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
ExclusiveGroup{id:areaGroup}
Repeater{
id: areaReapeater
model: _missionItem.areaData.areaList
delegate: QGCRadioButton {
text: object.objectName
QGCButton{
text: "Open Area Editor"
visible: parameterEditor.visible
Layout.fillWidth: true
Layout.columnSpan: 2
onCheckedChanged: {
updateInteractive()
}
Component.onCompleted: {
if (index === 0){
checked = true
onClicked:{
areaDataEditor.checked = true
}
}
function updateInteractive(){
if (checked){
object.interactive = true
} else {
object.interactive = false
}
QGCButton{
text: "Done"
Layout.fillWidth: true
visible: areaDataEditor.visible
onClicked: {
if (_areaData.isCorrect()){
parameterEditor.checked = true
}
}
} // area Repeater
} // general grid
// Generator Editor
SectionHeader {
id: generatorHeader
anchors.left: parent.left
anchors.right: parent.right
text: qsTr("Generator")
}
GridLayout{
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: generatorHeader.checked
QGCComboBox {
property var names: missionItem.generatorNameList
property int length: names.length
anchors.margins: ScreenTools.defaultFontPixelWidth
currentIndex: missionItem.generatorIndex
Layout.columnSpan: 2
model: missionItem.generatorNameList
onActivated: {
if (index != -1){
missionItem.switchToGenerator(index)
}
}
QGCButton{
text: "Abort"
visible: areaDataEditor.visible
Layout.fillWidth: true
onClicked:{
missionItem.abortEditing()
parameterEditor.checked = true
}
}
ColumnLayout{
id:generatorEditorParent
anchors.left: parent.left
anchors.right: parent.right
visible: generatorHeader.checked
}
} // editorSelector
// bussy indicator
ColumnLayout{
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
ExclusiveGroup { id:editorGroup}
BusyIndicator{
id: indicator
MCI.ParameterEditor{
id:parameterEditor
property bool calculating: missionItem.calculating
missionItem: _root._missionItem
availableWidth: mainColumn.width
visible: checked
running: calculating
visible: calculating || timer.running
property ExclusiveGroup group: editorGroup
onCalculatingChanged: {
if(!calculating){
// defer hiding
timer.restart()
onGroupChanged: {
if (group){
group.bindCheckable(parameterEditor)
}
}
Timer{
id: timer
interval: 1000
repeat: false
running: false
Component.onCompleted: {
checked = false
}
}
} // indicator column
} // Grid Column
} // Main editing column
} // Top level Column
KMLOrSHPFileDialog {
id: kmlOrSHPLoadDialog
title: qsTr("Select Polygon File")
selectExisting: true
MCI.AreaDataEditor{
id:areaDataEditor
onAcceptedForLoad: {
_missionItem.surveyAreaPolygon.loadKMLOrSHPFile(file)
_missionItem.resetState = false
//editorMap.mapFitFunctions.fitMapViewportTo_missionItems()
close()
}
}
missionItem: _root._missionItem
availableWidth: mainColumn.width
visible: checked
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,
})
}
property ExclusiveGroup group: editorGroup
onGroupChanged: {
if (group){
group.bindCheckable(areaDataEditor)
}
}
function _destroyGeneratorEditor(){
if (_generatorEditor){
_generatorEditor.destroy()
_generatorEditor = undefined
Component.onCompleted: {
checked = true
}
}
} // main Column
} // Rectangle
......@@ -37,21 +37,28 @@ Item {
signal clicked(int sequenceNumber)
on_EditingChanged: {
_destroyEntryCoordinate()
_destroyExitCoordinate()
_destroyTransectsComponent()
_destroyGeneratorVisuals()
}
// on_EditingChanged: {
// if (_editing){
// _destroyEntryCoordinate()
// _destroyExitCoordinate()
// _destroyTransectsComponent()
// _destroyGeneratorVisuals()
// } else {
// _addEntryCoordinate()
// _addExitCoordinate()
// _addTransectsComponent()
// _addGeneratorVisuals()
// }
// }
Component.onCompleted: {
console.assert(map != undefined, "please set the map property")
_addEntryCoordinate()
_addExitCoordinate()
_addTransectsComponent()
_addGeneratorVisuals()
var bbox = boundingBox()
_missionItem.areaData.initialize(bbox[0], bbox[1])
console.assert(map != undefined, "please set the map property")
}
Component.onDestruction: {
......@@ -71,10 +78,11 @@ Item {
id: visualTransectsComponent
MapPolyline {
property var route: _missionItem.route
line.color: "white"
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.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.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Operating Area items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
width: availableWidth
color: qgcPal.windowShadeDark
radius: _radius
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property bool polygonInteractive: areaItem.interactive
property var polygon: areaItem
property bool initNecesarry: true
QGCPalette { id: qgcPal; colorGroupEnabled: true }
Column {
GridLayout {
id: editorColumn
anchors.margins: _margin
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
SectionHeader {
id: scanHeader
text: qsTr("Settings")
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: scanHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columns: 2
columnSpacing: _margin
rowSpacing: _margin
columns: 2
QGCLabel { text: qsTr("Offset") }
width: availableWidth
FactTextField {
fact: areaItem.borderPolygonOffset
Layout.fillWidth: true
}
}
property var geoArea: undefined
property int availableWidth
Item {
height: ScreenTools.defaultFontPixelHeight / 2
width: 1
}
}
property real _margin: ScreenTools.defaultFontPixelWidth / 2
FactCheckBox {
text: qsTr("Border Polygon")
fact: areaItem.showBorderPolygon
//enabled: !missionItem.followTerrain
Component.onCompleted: {
console.assert(geoArea !== undefined, "please set the areaItem property")
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
Layout.fillWidth: true
Layout.columnSpan: 2
}
Grid {
GridLayout {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
columnSpacing: _margin
rowSpacing: _margin
visible: statsHeader.checked
Layout.fillWidth: true
Layout.columnSpan: 2
QGCLabel { text: qsTr("Area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(areaItem.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
//QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(geoArea.area).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
}
} // Column
} // Rectangle
}
......@@ -24,36 +24,13 @@ Item {
property var map: undefined ///< Map control to place item in
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)
on_ShowDepotChanged: {
if (_showDepot){
_addDepotVisual()
_addDepotDrag()
} else {
_destroyDepotVisual()
_destroyDepotDrag()
}
}
Component.onCompleted: {
if (_showDepot){
_addDepotVisual()
_addDepotDrag()
}
console.assert(map !== undefined, "please set the map property")
console.assert(geoArea !== undefined, "please set the geoArea property")
}
Component.onDestruction: {
_destroyDepotVisual()
}
// Area polygon
QGCMapPolygonVisuals {
......@@ -65,78 +42,61 @@ Item {
borderColor: "blue"
interiorColor: "blue"
altColor: QGroundControl.globalPalette.surveyPolygonTerrainCollision
interiorOpacity: _root.opacity
z: QGroundControl.zOrderMapItems-1
interiorOpacity: 0.3
}
Loader {
id:depotLoader
sourceComponent: depotComponent
}
// Depot Point.
Component {
id: depotPointComponent
id: depotComponent
Item {
id: depotMapItem
MapQuickItem {
id: mapItem
coordinate: _root.geoArea.depot
anchorPoint.x: sourceItem.anchorPointX
anchorPoint.y: sourceItem.anchorPointY
visible: true
z: QGroundControl.zOrderMapItems
Component.onCompleted: {
coordinate = Qt.binding(function(){return _root.geoArea.depot})
}
sourceItem:
MissionItemIndexLabel {
checked: geoArea.interactive
label: qsTr("Launch")
checked: true
label: qsTr("Depot")
highlightSelected: true
onClicked: _root.clicked(0)
visible: true
}
}
}
Component {
id: depotDragComponent
MissionItemIndicatorDrag {
mapControl: _root.map
itemIndicator: _depot
itemCoordinate: geoArea.depot
visible: geoArea.interactive
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})
}
visible: mapItem.visible
z: mapItem.z
}
}
function _addDepotVisual() {
if (!_depotVisual){
_depotVisual = depotPointComponent.createObject(_root)
map.addMapItem(_depotVisual)
}
}
ItemDragger {
anchor: mapItem
z: QGroundControl.zOrderMapItems+1
draggable: _root.geoArea.interactive
function _destroyDepotVisual() {
if (_depotVisual){
map.removeMapItem(_depotVisual)
_depotVisual.destroy()
_depotVisual = undefined
onDragStop:{
_root.geoArea.depot = mapItem.coordinate
mapItem.coordinate = Qt.binding(function(){return _root.geoArea.depot})
}
}
function _addDepotDrag() {
if (!_depotDrag){
_depotDrag = depotDragComponent.createObject(_root)
}
Component.onCompleted: {
_root.map.addMapItem(mapItem)
}
function _destroyDepotDrag() {
if (_depotDrag){
_depotDrag.destroy()
_depotDrag = undefined
}
}
}
......@@ -10,64 +10,71 @@
#ifndef QGCMapPolygon_H
#define QGCMapPolygon_H
#include <QObject>
#include <QGeoCoordinate>
#include <QVariantList>
#include <QObject>
#include <QPolygon>
#include <QVariantList>
#include "QmlObjectListModel.h"
#include "KMLDomDocument.h"
#include "QmlObjectListModel.h"
/// The QGCMapPolygon class provides a polygon which can be displayed on a map using a map visuals control.
/// It maintains a representation of the polygon on QVariantList and QmlObjectListModel format.
class QGCMapPolygon : public QObject
{
/// The QGCMapPolygon class provides a polygon which can be displayed on a map
/// using a map visuals control. It maintains a representation of the polygon on
/// QVariantList and QmlObjectListModel format.
class QGCMapPolygon : public QObject {
Q_OBJECT
public:
QGCMapPolygon(QObject* parent = nullptr);
QGCMapPolygon(const QGCMapPolygon& other, QObject* parent = nullptr);
QGCMapPolygon(QObject *parent = nullptr);
QGCMapPolygon(const QGCMapPolygon &other, QObject *parent = nullptr);
const QGCMapPolygon& operator=(const QGCMapPolygon& other);
const QGCMapPolygon &operator=(const QGCMapPolygon &other);
Q_PROPERTY(int count READ count NOTIFY countChanged)
Q_PROPERTY(QVariantList path READ path NOTIFY pathChanged)
Q_PROPERTY(double area READ area NOTIFY pathChanged)
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(QmlObjectListModel *pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
Q_PROPERTY(
QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY
centerDragChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY
interactiveChanged)
Q_PROPERTY(bool isValid READ isValid NOTIFY isValidChanged)
Q_PROPERTY(bool empty READ empty NOTIFY isEmptyChanged)
Q_PROPERTY(bool traceMode READ traceMode WRITE setTraceMode NOTIFY traceModeChanged)
Q_PROPERTY(bool showAltColor READ showAltColor WRITE setShowAltColor NOTIFY showAltColorChanged)
Q_PROPERTY(int selectedVertex READ selectedVertex WRITE selectVertex NOTIFY selectedVertexChanged)
Q_PROPERTY(
bool traceMode READ traceMode WRITE setTraceMode NOTIFY traceModeChanged)
Q_PROPERTY(bool showAltColor READ showAltColor WRITE setShowAltColor NOTIFY
showAltColorChanged)
Q_PROPERTY(int selectedVertex READ selectedVertex WRITE selectVertex NOTIFY
selectedVertexChanged)
Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
Q_INVOKABLE void appendVertex(const QGeoCoordinate &coordinate);
Q_INVOKABLE void removeVertex(int vertexIndex);
Q_INVOKABLE void appendVertices(const QVariantList& varCoords);
Q_INVOKABLE void appendVertices(const QVariantList &varCoords);
void appendVertices(const QList<QGeoCoordinate>& coordinates);
void appendVertices(const QList<QGeoCoordinate> &coordinates);
/// Adjust the value for the specified coordinate
/// @param vertexIndex Polygon point index to modify (0-based)
/// @param coordinate New coordinate for point
Q_INVOKABLE void adjustVertex(int vertexIndex, const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustVertex(int vertexIndex,
const QGeoCoordinate coordinate);
/// Splits the segment comprised of vertextIndex -> vertexIndex + 1
Q_INVOKABLE void splitPolygonSegment(int vertexIndex);
/// Returns true if the specified coordinate is within the polygon
Q_INVOKABLE bool containsCoordinate(const QGeoCoordinate& coordinate) const;
Q_INVOKABLE bool containsCoordinate(const QGeoCoordinate &coordinate) const;
/// Offsets the current polygon edges by the specified distance in meters
Q_INVOKABLE void offset(double distance);
/// Loads a polygon from a KML/SH{ file
/// @return true: success
Q_INVOKABLE bool loadKMLOrSHPFile(const QString& file);
Q_INVOKABLE bool loadKMLOrSHPFile(const QString &file);
/// Returns the path in a list of QGeoCoordinate's format
QList<QGeoCoordinate> coordinateList(void) const;
......@@ -78,19 +85,20 @@ public:
/// Adjust polygon winding order to be clockwise (if needed)
Q_INVOKABLE void verifyClockwiseWinding(void);
Q_INVOKABLE void beginReset (void);
Q_INVOKABLE void endReset (void);
Q_INVOKABLE void beginReset(void);
Q_INVOKABLE void endReset(void);
/// Saves the polygon to the json object.
/// @param json Json object to save to
void saveToJson(QJsonObject& json);
void saveToJson(QJsonObject &json);
/// Load a polygon from json
/// @param json Json object to load from
/// @param required true: no polygon in object will generate error
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
bool loadFromJson(const QJsonObject &json, bool required,
QString &errorString);
/// Convert polygon to NED and return (D is ignored)
QList<QPointF> nedPolygon(void) const;
......@@ -98,48 +106,48 @@ public:
/// Returns the area of the polygon in meters squared
double area(void) const;
QDomElement kmlPolygonElement(KMLDomDocument& domDocument);
QDomElement kmlPolygonElement(KMLDomDocument &domDocument);
// Property methods
int count (void) const { return _polygonPath.count(); }
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
QGeoCoordinate center (void) const { return _center; }
bool centerDrag (void) const { return _centerDrag; }
bool interactive (void) const { return _interactive; }
bool isValid (void) const { return _polygonModel.count() >= 3; }
bool empty (void) const { return _polygonModel.count() == 0; }
bool traceMode (void) const { return _traceMode; }
int count(void) const { return _polygonPath.count(); }
bool dirty(void) const { return _dirty; }
void setDirty(bool dirty);
QGeoCoordinate center(void) const { return _center; }
bool centerDrag(void) const { return _centerDrag; }
bool interactive(void) const { return _interactive; }
bool isValid(void) const { return _polygonModel.count() >= 3; }
bool empty(void) const { return _polygonModel.count() == 0; }
bool traceMode(void) const { return _traceMode; }
bool showAltColor(void) const { return _showAltColor; }
int selectedVertex() const { return _selectedVertexIndex; }
QVariantList path (void) const { return _polygonPath; }
QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; }
QmlObjectListModel& pathModel (void) { return _polygonModel; }
QVariantList path(void) const { return _polygonPath; }
QmlObjectListModel *qmlPathModel(void) { return &_polygonModel; }
QmlObjectListModel &pathModel(void) { return _polygonModel; }
void setPath (const QList<QGeoCoordinate>& path);
void setPath (const QVariantList& path);
void setCenter (QGeoCoordinate newCenter);
void setCenterDrag (bool centerDrag);
void setInteractive (bool interactive);
void setTraceMode (bool traceMode);
void setPath(const QList<QGeoCoordinate> &path);
void setPath(const QVariantList &path);
void setCenter(QGeoCoordinate newCenter);
void setCenterDrag(bool centerDrag);
void setInteractive(bool interactive);
void setTraceMode(bool traceMode);
void setShowAltColor(bool showAltColor);
void selectVertex (int index);
void selectVertex(int index);
static const char* jsonPolygonKey;
static const char *jsonPolygonKey;
signals:
void countChanged (int count);
void pathChanged (void);
void dirtyChanged (bool dirty);
void cleared (void);
void centerChanged (QGeoCoordinate center);
void centerDragChanged (bool centerDrag);
void interactiveChanged (bool interactive);
bool isValidChanged (void);
bool isEmptyChanged (void);
void traceModeChanged (bool traceMode);
void countChanged(int count);
void pathChanged(void);
void dirtyChanged(bool dirty);
void cleared(void);
void centerChanged(QGeoCoordinate center);
void centerDragChanged(bool centerDrag);
void interactiveChanged(bool interactive);
bool isValidChanged(void);
bool isEmptyChanged(void);
void traceModeChanged(bool traceMode);
void showAltColorChanged(bool showAltColor);
void selectedVertexChanged(int index);
......@@ -149,12 +157,12 @@ private slots:
void _updateCenter(void);
private:
void _init (void);
QPolygonF _toPolygonF (void) const;
QGeoCoordinate _coordFromPointF (const QPointF& point) const;
QPointF _pointFFromCoord (const QGeoCoordinate& coordinate) const;
void _beginResetIfNotActive (void);
void _endResetIfNotActive (void);
void _init(void);
QPolygonF _toPolygonF(void) const;
QGeoCoordinate _coordFromPointF(const QPointF &point) const;
QPointF _pointFFromCoord(const QGeoCoordinate &coordinate) const;
void _beginResetIfNotActive(void);
void _endResetIfNotActive(void);
QVariantList _polygonPath;
QmlObjectListModel _polygonModel;
......
......@@ -34,6 +34,10 @@ Item {
property int borderWidth: 0
property color borderColor: "black"
readonly property bool editing: _editing
property bool _editing: false
property bool _circleMode: false
property real _circleRadius
property bool _circleRadiusDrag: false
......@@ -50,6 +54,7 @@ Item {
readonly property string _polygonToolsText: qsTr("Polygon Tools")
readonly property string _traceText: qsTr("Click in the map to add vertices. Click 'Done Tracing' when finished.")
function addCommonVisuals() {
if (_objMgrCommonVisuals.empty) {
_objMgrCommonVisuals.createObject(polygonComponent, mapControl, true)
......@@ -301,7 +306,13 @@ Item {
sourceItem: SplitIndicator {
z: _zorderSplitHandle
onClicked: if(_root.interactive) mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
onClicked: {
if(_root.interactive){
mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
_root.split()
}
}
}
}
}
......@@ -351,7 +362,6 @@ Item {
mapControl: _root.mapControl
z: _zorderDragHandle
visible: !_circleMode
onDragStop: mapPolygon.verifyClockwiseWinding()
property int polygonVertex
......@@ -366,6 +376,15 @@ Item {
}
}
onDragStart:{
_root._editing = true
}
onDragStop:{
mapPolygon.verifyClockwiseWinding()
_root._editing = false
}
onClicked: if(_root.interactive) menu.popupVertex(polygonVertex)
}
}
......@@ -487,9 +506,17 @@ Item {
MissionItemIndicatorDrag {
mapControl: _root.mapControl
z: _zorderCenterHandle
onItemCoordinateChanged: mapPolygon.center = itemCoordinate
onDragStart: mapPolygon.centerDrag = true
onDragStop: mapPolygon.centerDrag = false
onDragStart: {
mapPolygon.centerDrag = true
_root._editing = true
}
onDragStop:{
mapPolygon.centerDrag = false
_root._editing = false
}
}
}
......@@ -620,6 +647,14 @@ Item {
_lastRadius = radius
}
}
onDragStart: {
_root._editing = true
}
onDragStop: {
_root._editing = false
}
}
}
......
......@@ -113,6 +113,4 @@ MAVLinkChart 1.0 MAVLinkChart.qml
MeasurementItemMapVisual 1.0 MeasurementItemMapVisual.qml
CircularGeneratorMapVisual 1.0 CircularGeneratorMapVisual.qml
GeoAreaVisualLoader 1.0 GeoAreaVisualLoader.qml
DragCoordinate 1.0 DragCoordinate.qml
CoordinateIndicator 1.0 CoordinateIndicator.qml
CoordinateIndicatorDrag 1.0 CoordinateIndicatorDrag.qml
ItemDragger 1.0 ItemDragger.qml
......@@ -7,80 +7,84 @@
*
****************************************************************************/
#ifndef QmlObjectListModel_H
#define QmlObjectListModel_H
#include <QAbstractListModel>
class QmlObjectListModel : public QAbstractListModel
{
class QmlObjectListModel : public QAbstractListModel {
Q_OBJECT
public:
QmlObjectListModel(QObject* parent = nullptr);
QmlObjectListModel(QObject *parent = nullptr);
~QmlObjectListModel() override;
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
/// a dirty property and dirtyChanged signal.
/// Returns true if any of the items in the list are dirty. Requires each
/// object to have a dirty property and dirtyChanged signal.
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_INVOKABLE QObject* get(int index);
Q_INVOKABLE QObject *get(int index);
// Property accessors
int count () const;
bool dirty () const { return _dirty; }
void setDirty (bool dirty);
void append (QObject* object);
void append (QList<QObject*> objects);
QObjectList swapObjectList (const QObjectList& newlist);
void clear ();
QObject* removeAt (int i);
QObject* removeOne (QObject* object) { return removeAt(indexOf(object)); }
void insert (int i, QObject* object);
void insert (int i, QList<QObject*> objects);
bool contains (QObject* object) { return _objectList.indexOf(object) != -1; }
int indexOf (QObject* object) { return _objectList.indexOf(object); }
int count() const;
bool dirty() const { return _dirty; }
void setDirty(bool dirty);
void append(QObject *object);
void append(QList<QObject *> objects);
QObjectList swapObjectList(const QObjectList &newlist);
void clear();
QObject *removeAt(int i);
QObject *removeOne(QObject *object) { return removeAt(indexOf(object)); }
void insert(int i, QObject *object);
void insert(int i, QList<QObject *> objects);
bool contains(QObject *object) { return _objectList.indexOf(object) != -1; }
int indexOf(QObject *object) { return _objectList.indexOf(object); }
/// Moves an item to a new position
void move(int from, int to);
QObject* operator[] (int i);
const QObject* operator[] (int i) const;
template<class T> T value (int index) { return qobject_cast<T>(_objectList[index]); }
QList<QObject*>* objectList () { return &_objectList; }
QObject *operator[](int i);
const QObject *operator[](int i) const;
template <class T> T value(int index) {
return qobject_cast<T>(_objectList[index]);
}
QList<QObject *> *objectList() { return &_objectList; }
/// Calls deleteLater on all items and this itself.
void deleteListAndContents ();
void deleteListAndContents();
/// Clears the list and calls deleteLater on each entry
void clearAndDeleteContents ();
void clearAndDeleteContents();
void beginReset ();
void endReset ();
void beginReset();
void endReset();
signals:
void countChanged (int count);
void dirtyChanged (bool dirtyChanged);
void countChanged(int count);
void dirtyChanged(bool dirtyChanged);
private slots:
void _childDirtyChanged (bool dirty);
void _childDirtyChanged(bool dirty);
private:
// Overrides from QAbstractListModel
int rowCount (const QModelIndex & parent = QModelIndex()) const override;
QVariant data (const QModelIndex & index, int role = Qt::DisplayRole) const override;
bool insertRows (int position, int rows, const QModelIndex &index = QModelIndex()) 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;
int rowCount(const QModelIndex &parent = QModelIndex()) const override;
QVariant data(const QModelIndex &index,
int role = Qt::DisplayRole) const override;
bool insertRows(int position, int rows,
const QModelIndex &index = QModelIndex()) 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:
QList<QObject*> _objectList;
QList<QObject *> _objectList;
bool _dirty;
bool _skipDirtyFirstItem;
......
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