Commit 6fd60bb5 authored by Valentin Platzgummer's avatar Valentin Platzgummer

CircularSurvey concurr. update improved

parent 81a0bb81
// Generated by the protocol buffer compiler. DO NOT EDIT! // Generated by the protocol buffer compiler. DO NOT EDIT!
this->_calculating = false;
emit calculatingChanged();
// source: ortools/constraint_solver/search_limit.proto // source: ortools/constraint_solver/search_limit.proto
#ifndef GOOGLE_PROTOBUF_INCLUDED_ortools_2fconstraint_5fsolver_2fsearch_5flimit_2eproto #ifndef GOOGLE_PROTOBUF_INCLUDED_ortools_2fconstraint_5fsolver_2fsearch_5flimit_2eproto
......
...@@ -413,6 +413,7 @@ FORMS += \ ...@@ -413,6 +413,7 @@ FORMS += \
# #
HEADERS += \ HEADERS += \
src/Wima/CSWorker.h \
src/Wima/CircularSurvey.h \ src/Wima/CircularSurvey.h \
src/Wima/Geometry/GenericCircle.h \ src/Wima/Geometry/GenericCircle.h \
src/Wima/Snake/clipper/clipper.hpp \ src/Wima/Snake/clipper/clipper.hpp \
...@@ -502,6 +503,7 @@ HEADERS += \ ...@@ -502,6 +503,7 @@ HEADERS += \
src/comm/ros_bridge/include/topic_subscriber.h \ src/comm/ros_bridge/include/topic_subscriber.h \
src/comm/utilities.h src/comm/utilities.h
SOURCES += \ SOURCES += \
src/Wima/CSWorker.cpp \
src/Wima/CircularSurvey.cc \ src/Wima/CircularSurvey.cc \
src/Wima/Snake/clipper/clipper.cpp \ src/Wima/Snake/clipper/clipper.cpp \
src/Wima/Snake/snake.cpp \ src/Wima/Snake/snake.cpp \
......
...@@ -92,9 +92,6 @@ Rectangle { ...@@ -92,9 +92,6 @@ Rectangle {
columns: 2 columns: 2
visible: transectsHeader.checked visible: transectsHeader.checked
QGCLabel { text: qsTr("Delta R") } QGCLabel { text: qsTr("Delta R") }
FactTextField { FactTextField {
fact: missionItem.deltaR fact: missionItem.deltaR
...@@ -131,12 +128,26 @@ Rectangle { ...@@ -131,12 +128,26 @@ Rectangle {
} }
} }
Column { GridLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: transectsHeader.checked visible: transectsHeader.checked
QGCButton {
text: qsTr("Reverse")
onClicked: missionItem.reverse();
Layout.fillWidth: true
}
QGCButton {
text: qsTr("Reset Ref.")
onClicked: missionItem.resetReference();
Layout.fillWidth: true
}
QGCCheckBox { QGCCheckBox {
id: relAlt id: relAlt
text: qsTr("Relative altitude") text: qsTr("Relative altitude")
...@@ -144,6 +155,8 @@ Rectangle { ...@@ -144,6 +155,8 @@ Rectangle {
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain) visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
Layout.fillWidth: true
Layout.columnSpan: 2
Connections { Connections {
target: missionItem.cameraCalc target: missionItem.cameraCalc
...@@ -151,96 +164,38 @@ Rectangle { ...@@ -151,96 +164,38 @@ Rectangle {
} }
} }
FactCheckBox {
text: qsTr("Reverse Path")
fact: missionItem.reverse
} }
QGCButton { Column{
text: qsTr("Reset Reference")
onClicked: missionItem.resetReference();
Layout.fillWidth: true
}
}
SectionHeader {
id: miscellaneousHeader
text: qsTr("Miscellaneous")
}
ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: miscellaneousHeader.checked
GridLayout { BusyIndicator{
Layout.fillWidth: true id: indicator
columnSpacing: _margin anchors.horizontalCenter: parent.horizontalCenter
rowSpacing: _margin running: missionItem.calculating
columns: 2
QGCLabel { text: qsTr("Max Waypoints") } onRunningChanged: {
FactTextField { if(running){
fact: missionItem.maxWaypoints visible = true
Layout.fillWidth: true } else {
timer.restart()
} }
} // GridLayout
} // ColumnLayout
/*
// The following code causes seg. faults from time to time
SectionHeader {
id: terrainHeader
text: qsTr("Terrain")
checked: missionItem.followTerrain
} }
ColumnLayout { Timer{
anchors.left: parent.left id: timer
anchors.right: parent.right interval: 2000
spacing: _margin repeat: false
visible: terrainHeader.checked
QGCCheckBox { onTriggered: {
id: followsTerrainCheckBox if (indicator.running == false){
text: qsTr("Vehicle follows terrain") indicator.visible = false
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
} }
GridLayout {
Layout.fillWidth: true
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
} }
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
} }
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
} }
} }
}*/
/*SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}*/
//TransectStyleComplexItemStats { }
} // Column } // Column
} // Rectangle } // Rectangle
This diff is collapsed.
#pragma once
#include <QGeoCoordinate>
#include <QList>
#include <QSharedPointer>
#include <QThread>
#include "snake.h"
#include <atomic>
#include <condition_variable>
#include <mutex>
//!
//! \brief The CSWorker class
//! \note Don't call QThread::start, QThread::quit, etc. onyl use Worker
//! members!
class CSWorker : public QThread {
Q_OBJECT
using Lock = std::unique_lock<std::mutex>;
public:
using Route = QList<QGeoCoordinate>;
using PtrRoute = QSharedPointer<Route>;
CSWorker(QObject *parent = nullptr);
~CSWorker() override;
bool calculating();
public slots:
void update(const QList<QGeoCoordinate> &polygon,
const QGeoCoordinate &origin, snake::Length deltaR,
snake::Length minLength, snake::Angle deltaAlpha);
signals:
void ready(PtrRoute pTransects);
void calculatingChanged();
protected:
void run() override;
private:
mutable std::mutex _mutex;
mutable std::condition_variable _cv;
// Internal data
QList<QGeoCoordinate> _polygon;
QGeoCoordinate _origin;
snake::Length _deltaR;
snake::Angle _deltaAlpha;
snake::Length _minLength;
std::size_t _maxWaypoints;
// State
std::atomic_bool _calculating;
std::atomic_bool _stop;
std::atomic_bool _restart;
};
This diff is collapsed.
...@@ -6,9 +6,14 @@ ...@@ -6,9 +6,14 @@
#include "SettingsFact.h" #include "SettingsFact.h"
#include "TransectStyleComplexItem.h" #include "TransectStyleComplexItem.h"
class CSWorker;
class CircularSurvey : public TransectStyleComplexItem { class CircularSurvey : public TransectStyleComplexItem {
Q_OBJECT Q_OBJECT
public: public:
using Route = QList<QGeoCoordinate>;
using PtrRoute = QSharedPointer<Route>;
/// @param vehicle Vehicle which this is being contructed for /// @param vehicle Vehicle which this is being contructed for
/// @param flyView true: Created for use in the Fly View, false: Created for /// @param flyView true: Created for use in the Fly View, false: Created for
/// use in the Plan View /// use in the Plan View
...@@ -16,19 +21,19 @@ public: ...@@ -16,19 +21,19 @@ public:
/// polygon /// polygon
CircularSurvey(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile, CircularSurvey(Vehicle *vehicle, bool flyView, const QString &kmlOrShpFile,
QObject *parent); QObject *parent);
~CircularSurvey();
Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY
refPointChanged) refPointChanged)
Q_PROPERTY(Fact *deltaR READ deltaR CONSTANT) Q_PROPERTY(Fact *deltaR READ deltaR CONSTANT)
Q_PROPERTY(Fact *deltaAlpha READ deltaAlpha CONSTANT) Q_PROPERTY(Fact *deltaAlpha READ deltaAlpha CONSTANT)
Q_PROPERTY(Fact *transectMinLength READ transectMinLength CONSTANT) Q_PROPERTY(Fact *transectMinLength READ transectMinLength CONSTANT)
Q_PROPERTY(Fact *reverse READ reverse CONSTANT)
Q_PROPERTY(Fact *maxWaypoints READ maxWaypoints CONSTANT)
Q_PROPERTY(bool isInitialized READ isInitialized WRITE setIsInitialized NOTIFY Q_PROPERTY(bool isInitialized READ isInitialized WRITE setIsInitialized NOTIFY
isInitializedChanged) isInitializedChanged)
Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged) Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged)
Q_INVOKABLE void resetReference(void); Q_INVOKABLE void resetReference(void);
Q_INVOKABLE void reverse(void);
// Property setters // Property setters
void setRefPoint(const QGeoCoordinate &refPt); void setRefPoint(const QGeoCoordinate &refPt);
...@@ -41,8 +46,6 @@ public: ...@@ -41,8 +46,6 @@ public:
Fact *deltaR(); Fact *deltaR();
Fact *deltaAlpha(); Fact *deltaAlpha();
Fact *transectMinLength(); Fact *transectMinLength();
Fact *reverse();
Fact *maxWaypoints();
bool calculating(); bool calculating();
// Is true if survey was automatically generated, prevents initialisation from // Is true if survey was automatically generated, prevents initialisation from
// gui. // gui.
...@@ -72,8 +75,6 @@ public: ...@@ -72,8 +75,6 @@ public:
static const char *deltaRName; static const char *deltaRName;
static const char *deltaAlphaName; static const char *deltaAlphaName;
static const char *transectMinLengthName; static const char *transectMinLengthName;
static const char *reverseName;
static const char *maxWaypointsName;
static const char *CircularSurveyName; static const char *CircularSurveyName;
static const char *refPointLongitudeName; static const char *refPointLongitudeName;
static const char *refPointLatitudeName; static const char *refPointLatitudeName;
...@@ -89,7 +90,7 @@ private slots: ...@@ -89,7 +90,7 @@ private slots:
void _rebuildTransectsPhase1(void) final; void _rebuildTransectsPhase1(void) final;
void _recalcComplexDistance(void) final; void _recalcComplexDistance(void) final;
void _recalcCameraShots(void) final; void _recalcCameraShots(void) final;
void _deferUpdate(); void _setTransects(PtrRoute pRoute);
private: private:
void _appendLoadedMissionItems(QList<MissionItem *> &items, void _appendLoadedMissionItems(QList<MissionItem *> &items,
...@@ -108,21 +109,14 @@ private: ...@@ -108,21 +109,14 @@ private:
// minimal transect lenght, transects are rejected if they are shorter than // minimal transect lenght, transects are rejected if they are shorter than
// this value // this value
SettingsFact _minLength; SettingsFact _minLength;
// reverses the _transects path
SettingsFact _reverse;
// the maximum number of waypoints _transects (TransectStyleComplexItem) can
// contain (to avoid performance hits)
SettingsFact _maxWaypoints;
// Timer to defer recalc
QTimer _timer;
// indicates if the polygon and refpoint etc. are initialized, prevents // indicates if the polygon and refpoint etc. are initialized, prevents
// reinitialisation from gui and execution of _rebuildTransectsPhase1 during // reinitialisation from gui and execution of _rebuildTransectsPhase1 during
// init from gui // init from gui
bool _isInitialized; bool _isInitialized;
using PtrTransects = std::shared_ptr<Transects>; using PtrWorker = std::shared_ptr<CSWorker>;
using Watcher = QFutureWatcher<PtrTransects>; PtrWorker _pWorker;
Watcher _watcher; PtrRoute _pRoute;
bool _calculating; bool _needsStoring;
bool _cancle; bool _needsReversal;
}; };
...@@ -781,8 +781,8 @@ void generateRoutingModel(const BoostLineString &vertices, ...@@ -781,8 +781,8 @@ void generateRoutingModel(const BoostLineString &vertices,
} }
bool route(const BoostPolygon &area, const Transects &transects, bool route(const BoostPolygon &area, const Transects &transects,
std::vector<TransectInfo> &transectInfo, Route &route, std::vector<TransectInfo> &transectInfo, Route &r,
string &errorString) { std::function<bool()> stop, string &errorString) {
//======================================= //=======================================
// Route Transects using Google or-tools. // Route Transects using Google or-tools.
//======================================= //=======================================
...@@ -819,9 +819,17 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -819,9 +819,17 @@ bool route(const BoostPolygon &area, const Transects &transects,
vertices.push_back(vertex); vertices.push_back(vertex);
} }
size_t n1 = vertices.size(); size_t n1 = vertices.size();
if (stop()) {
errorString = "User termination.";
return false;
}
// Generate routing model. // Generate routing model.
RoutingDataModel dataModel; RoutingDataModel dataModel;
Matrix<double> connectionGraph(n1, n1); Matrix<double> connectionGraph(n1, n1);
if (stop()) {
errorString = "User termination.";
return false;
}
// Offset joined area. // Offset joined area.
BoostPolygon areaOffset; BoostPolygon areaOffset;
offsetPolygon(area, areaOffset, detail::offsetConstant); offsetPolygon(area, areaOffset, detail::offsetConstant);
...@@ -835,6 +843,10 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -835,6 +843,10 @@ bool route(const BoostPolygon &area, const Transects &transects,
cout << "Execution time _generateRoutingModel(): " << delta.count() << " ms" cout << "Execution time _generateRoutingModel(): " << delta.count() << " ms"
<< endl; << endl;
#endif #endif
if (stop()) {
errorString = "User termination.";
return false;
}
// Create Routing Index Manager. // Create Routing Index Manager.
RoutingIndexManager manager(dataModel.distanceMatrix.getN(), RoutingIndexManager manager(dataModel.distanceMatrix.getN(),
...@@ -883,16 +895,13 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -883,16 +895,13 @@ bool route(const BoostPolygon &area, const Transects &transects,
index += 1; index += 1;
} }
} }
// Set first solution heuristic.
// Setting first solution heuristic. auto searchParameters = DefaultRoutingSearchParameters();
RoutingSearchParameters searchParameters = DefaultRoutingSearchParameters();
searchParameters.set_first_solution_strategy( searchParameters.set_first_solution_strategy(
FirstSolutionStrategy::PATH_CHEAPEST_ARC); FirstSolutionStrategy::PATH_CHEAPEST_ARC);
google::protobuf::Duration *tMax = // Set costume limit.
new google::protobuf::Duration(); // seconds auto *limit = solver->MakeCustomLimit(stop);
tMax->set_seconds(10); routing.AddSearchMonitor(limit);
searchParameters.set_allocated_time_limit(tMax);
// Solve the problem. // Solve the problem.
#ifdef SNAKE_SHOW_TIME #ifdef SNAKE_SHOW_TIME
start = std::chrono::high_resolution_clock::now(); start = std::chrono::high_resolution_clock::now();
...@@ -908,6 +917,9 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -908,6 +917,9 @@ bool route(const BoostPolygon &area, const Transects &transects,
if (!solution || solution->Size() <= 1) { if (!solution || solution->Size() <= 1) {
errorString = "Not able to solve the routing problem."; errorString = "Not able to solve the routing problem.";
return false; return false;
} else if (stop()) {
errorString = "User terminated.";
return false;
} }
// Extract index list from solution. // Extract index list from solution.
...@@ -944,12 +956,12 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -944,12 +956,12 @@ bool route(const BoostPolygon &area, const Transects &transects,
} }
for (auto it = reversedTransect.begin(); for (auto it = reversedTransect.begin();
it < reversedTransect.end() - 1; ++it) { it < reversedTransect.end() - 1; ++it) {
route.push_back(*it); r.push_back(*it);
} }
} else { } else {
const auto &t = transects[info1.index]; const auto &t = transects[info1.index];
for (auto it = t.begin(); it < t.end() - 1; ++it) { for (auto it = t.begin(); it < t.end() - 1; ++it) {
route.push_back(*it); r.push_back(*it);
} }
} }
} else { } else {
...@@ -958,12 +970,19 @@ bool route(const BoostPolygon &area, const Transects &transects, ...@@ -958,12 +970,19 @@ bool route(const BoostPolygon &area, const Transects &transects,
if (i != route_idx.size() - 2) { if (i != route_idx.size() - 2) {
idxList.pop_back(); idxList.pop_back();
} }
idx2Vertex(idxList, route); idx2Vertex(idxList, r);
} }
} }
return true; return true;
} }
bool route(const BoostPolygon &area, const Transects &transects,
std::vector<TransectInfo> &transectInfo, Route &r,
string &errorString) {
auto stop = [] { return false; };
return route(area, transects, transectInfo, r, stop, errorString);
}
} // namespace snake } // namespace snake
bool boost::geometry::model::operator==(snake::BoostPoint p1, bool boost::geometry::model::operator==(snake::BoostPoint p1,
......
#pragma once #pragma once
#include <array> #include <array>
#include <atomic>
#include <functional>
#include <memory> #include <memory>
#include <string> #include <string>
#include <vector> #include <vector>
...@@ -185,8 +187,11 @@ struct TransectInfo { ...@@ -185,8 +187,11 @@ struct TransectInfo {
bool reversed; bool reversed;
}; };
bool route(const BoostPolygon &area, const Transects &transects, bool route(const BoostPolygon &area, const Transects &transects,
std::vector<TransectInfo> &transectInfo, Route &route, std::vector<TransectInfo> &transectInfo, Route &r,
string &errorString); string &errorString);
bool route(const BoostPolygon &area, const Transects &transects,
std::vector<TransectInfo> &transectInfo, Route &r,
std::function<bool(void)> stop, string &errorString);
namespace detail { namespace detail {
const double offsetConstant = const double offsetConstant =
......
...@@ -21,12 +21,13 @@ const char *WimaPlaner::areaItemsName = "AreaItems"; ...@@ -21,12 +21,13 @@ const char *WimaPlaner::areaItemsName = "AreaItems";
const char *WimaPlaner::missionItemsName = "MissionItems"; const char *WimaPlaner::missionItemsName = "MissionItems";
WimaPlaner::WimaPlaner(QObject *parent) WimaPlaner::WimaPlaner(QObject *parent)
: QObject(parent), _currentAreaIndex(-1), _wimaBridge(nullptr), : QObject(parent), _masterController(nullptr), _missionController(nullptr),
_joinedArea(this), _joinedAreaValid(false), _measurementArea(this), _currentAreaIndex(-1), _wimaBridge(nullptr), _joinedArea(this),
_serviceArea(this), _corridor(this), _TSComplexItem(nullptr), _joinedAreaValid(false), _arrivalPathLength(0), _returnPathLength(0),
_surveyRefChanging(false), _measurementAreaChanging(false), _TSComplexItem(nullptr), _surveyRefChanging(false),
_corridorChanging(false), _serviceAreaChanging(false), _measurementAreaChanging(false), _corridorChanging(false),
_syncronizedWithController(false), _readyForSync(false) { _serviceAreaChanging(false), _syncronizedWithController(false),
_readyForSync(false) {
_lastMeasurementAreaPath = _measurementArea.path(); _lastMeasurementAreaPath = _measurementArea.path();
_lastServiceAreaPath = _serviceArea.path(); _lastServiceAreaPath = _serviceArea.path();
_lastCorridorPath = _corridor.path(); _lastCorridorPath = _corridor.path();
......
...@@ -49,16 +49,16 @@ public: ...@@ -49,16 +49,16 @@ public:
Q_PROPERTY(bool readyForSync READ readyForSync NOTIFY readyForSyncChanged) Q_PROPERTY(bool readyForSync READ readyForSync NOTIFY readyForSyncChanged)
// Property accessors // Property accessors
PlanMasterController *masterController(void) { return _masterController; } PlanMasterController *masterController(void);
MissionController *missionController(void) { return _missionController; } MissionController *missionController(void);
QmlObjectListModel *visualItems(void); QmlObjectListModel *visualItems(void);
int currentPolygonIndex(void) const { return _currentAreaIndex; } int currentPolygonIndex(void) const;
QString currentFile(void) const { return _currentFile; } QString currentFile(void) const;
QStringList loadNameFilters(void) const; QStringList loadNameFilters(void) const;
QStringList saveNameFilters(void) const; QStringList saveNameFilters(void) const;
QString fileExtension(void) const { return wimaFileExtension; } QString fileExtension(void) const;
QGeoCoordinate joinedAreaCenter(void) const; QGeoCoordinate joinedAreaCenter(void) const;
WimaBridge *wimaBridge(void) { return _wimaBridge; } WimaBridge *wimaBridge(void);
// Property setters // Property setters
void setMasterController(PlanMasterController *masterController); void setMasterController(PlanMasterController *masterController);
...@@ -145,22 +145,22 @@ private: ...@@ -145,22 +145,22 @@ private:
PlanMasterController *_masterController; PlanMasterController *_masterController;
MissionController *_missionController; MissionController *_missionController;
int _currentAreaIndex; int _currentAreaIndex;
QString _currentFile; // file for saveing QString _currentFile;
WimaBridge *_wimaBridge; // container for data exchange with WimaController // container for data exchange with WimaController
QmlObjectListModel _visualItems; // contains all visible areas WimaBridge *_wimaBridge;
WimaJoinedArea _joinedArea; // joined area fromed by _measurementArea,
// _serviceArea, _corridor
bool _joinedAreaValid; bool _joinedAreaValid;
WimaMeasurementArea _measurementArea; // measurement area WimaMeasurementArea _measurementArea;
WimaServiceArea _serviceArea; // area for supplying WimaServiceArea _serviceArea;
WimaCorridor WimaCorridor _corridor;
_corridor; // corridor connecting _measurementArea and _serviceArea // contains all visible areas
unsigned long QmlObjectListModel _visualItems;
_arrivalPathLength; // the number waypoints the arrival path consists of // joined area fromed by _measurementArea, _serviceArea, _corridor
// (path from takeoff to first measurement point) WimaJoinedArea _joinedArea;
unsigned long // path from takeoff to first measurement point
_returnPathLength; // the number waypoints the return path consists of unsigned long _arrivalPathLength;
// (path from last measurement point to land) // path from last measurement point to land
unsigned long _returnPathLength;
CircularSurvey *_TSComplexItem; // pointer to the CircularSurvey item in CircularSurvey *_TSComplexItem; // pointer to the CircularSurvey item in
// _missionController.visualItems() // _missionController.visualItems()
......
...@@ -7,8 +7,6 @@ ...@@ -7,8 +7,6 @@
* *
****************************************************************************/ ****************************************************************************/
// original file: SurveyMapVisual.qml
import QtQuick 2.3 import QtQuick 2.3
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtLocation 5.3 import QtLocation 5.3
......
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