Commit 47641f63 authored by Valentin Platzgummer's avatar Valentin Platzgummer

wima planer edited

parent 1ac83998
...@@ -64,6 +64,7 @@ Rectangle { ...@@ -64,6 +64,7 @@ Rectangle {
GridLayout { GridLayout {
id: generalGrid
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
columnSpacing: _margin columnSpacing: _margin
...@@ -75,7 +76,48 @@ Rectangle { ...@@ -75,7 +76,48 @@ Rectangle {
FactTextField { FactTextField {
fact: missionItem.cameraCalc.distanceToSurface fact: missionItem.cameraCalc.distanceToSurface
Layout.fillWidth: true Layout.fillWidth: true
//onUpdated: rSlider.value = missionItem.deltaR.value }
QGCCheckBox {
id: relAlt
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
Layout.fillWidth: true
Layout.columnSpan: 2
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
}
QGCLabel {
text: qsTr("Type")
Layout.columnSpan: 2
}
property var typeFact: missionItem.type
property int type: typeFact.value
property var names: ["Circular", "Linear"]
ExclusiveGroup{id: typeGroup}
Repeater{
model: missionItem.typeCount
QGCRadioButton {
checked: index === generalGrid.type
text: qsTr(generalGrid.names[index])
onCheckedChanged: {
if (checked){
missionItem.type.value = index
}
checked = Qt.binding(function(){ return index === generalGrid.type})
}
}
} }
} }
...@@ -92,11 +134,10 @@ Rectangle { ...@@ -92,11 +134,10 @@ Rectangle {
columns: 2 columns: 2
visible: transectsHeader.checked visible: transectsHeader.checked
QGCLabel { text: qsTr("Delta R") } QGCLabel { text: qsTr("Distance") }
FactTextField { FactTextField {
fact: missionItem.deltaR fact: missionItem.transectDistance
Layout.fillWidth: true Layout.fillWidth: true
//onUpdated: rSlider.value = missionItem.deltaR.value
} }
/*QGCSlider { /*QGCSlider {
...@@ -113,18 +154,16 @@ Rectangle { ...@@ -113,18 +154,16 @@ Rectangle {
updateValueWhileDragging: true updateValueWhileDragging: true
}*/ }*/
QGCLabel { text: qsTr("Delta Alpha") } QGCLabel { text: qsTr("Alpha") }
FactTextField { FactTextField {
fact: missionItem.deltaAlpha fact: missionItem.alpha
Layout.fillWidth: true Layout.fillWidth: true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
} }
QGCLabel { text: qsTr("Min. Length") } QGCLabel { text: qsTr("Min. Length") }
FactTextField { FactTextField {
fact: missionItem.transectMinLength fact: missionItem.minLength
Layout.fillWidth: true Layout.fillWidth: true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
} }
} }
...@@ -148,21 +187,6 @@ Rectangle { ...@@ -148,21 +187,6 @@ Rectangle {
Layout.fillWidth: true Layout.fillWidth: true
} }
QGCCheckBox {
id: relAlt
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
Layout.fillWidth: true
Layout.columnSpan: 2
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
}
} }
......
...@@ -73,7 +73,7 @@ void RoutingWorker::run() { ...@@ -73,7 +73,7 @@ void RoutingWorker::run() {
auto &transectsInfo = pRouteData->transectsInfo; auto &transectsInfo = pRouteData->transectsInfo;
auto &route = pRouteData->route; auto &route = pRouteData->route;
const auto routingStart = std::chrono::high_resolution_clock::now(); const auto routingStart = std::chrono::high_resolution_clock::now();
const auto maxRoutingTime = std::chrono::minutes(1); const auto maxRoutingTime = std::chrono::minutes(10);
const auto routingEnd = routingStart + maxRoutingTime; const auto routingEnd = routingStart + maxRoutingTime;
const auto &restart = this->_restart; const auto &restart = this->_restart;
auto stopLambda = [&restart, routingEnd] { auto stopLambda = [&restart, routingEnd] {
......
This diff is collapsed.
This diff is collapsed.
...@@ -13,6 +13,11 @@ class CircularSurvey : public TransectStyleComplexItem { ...@@ -13,6 +13,11 @@ class CircularSurvey : public TransectStyleComplexItem {
Q_OBJECT Q_OBJECT
public: public:
using PtrRoutingData = QSharedPointer<RoutingData>; using PtrRoutingData = QSharedPointer<RoutingData>;
enum class Type {
Circular = 0,
Linear = 1,
Count = 2 // Must me last, onyl for counting
};
/// @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
...@@ -25,9 +30,11 @@ public: ...@@ -25,9 +30,11 @@ public:
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 *transectDistance READ transectDistance CONSTANT)
Q_PROPERTY(Fact *deltaAlpha READ deltaAlpha CONSTANT) Q_PROPERTY(Fact *alpha READ alpha CONSTANT)
Q_PROPERTY(Fact *transectMinLength READ transectMinLength CONSTANT) Q_PROPERTY(Fact *minLength READ minLength CONSTANT)
Q_PROPERTY(Fact *type READ type CONSTANT)
Q_PROPERTY(int typeCount READ typeCount CONSTANT)
Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged) Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged)
Q_PROPERTY(bool hidePolygon READ hidePolygon NOTIFY hidePolygonChanged) Q_PROPERTY(bool hidePolygon READ hidePolygon NOTIFY hidePolygonChanged)
...@@ -42,13 +49,16 @@ public: ...@@ -42,13 +49,16 @@ public:
// Property getters // Property getters
QGeoCoordinate refPoint() const; QGeoCoordinate refPoint() const;
Fact *deltaR(); Fact *transectDistance();
Fact *deltaAlpha(); Fact *alpha();
Fact *transectMinLength(); Fact *minLength();
Fact *type();
int typeCount() const;
bool calculating() const; bool calculating() const;
bool hidePolygon() const; bool hidePolygon() const;
QGeoCoordinate depot() const; QGeoCoordinate depot() const;
QList<QGeoCoordinate> safeArea() const; QList<QGeoCoordinate> safeArea() const;
const QList<QList<QGeoCoordinate>> &rawTransects() const;
// Overrides // Overrides
bool load(const QJsonObject &complexObject, int sequenceNumber, bool load(const QJsonObject &complexObject, int sequenceNumber,
...@@ -67,9 +77,10 @@ public: ...@@ -67,9 +77,10 @@ public:
double additionalTimeDelay(void) const override final; double additionalTimeDelay(void) const override final;
static const char *settingsGroup; static const char *settingsGroup;
static const char *deltaRName; static const char *transectDistanceName;
static const char *deltaAlphaName; static const char *alphaName;
static const char *transectMinLengthName; static const char *minLengthName;
static const char *typeName;
static const char *CircularSurveyName; static const char *CircularSurveyName;
static const char *refPointLongitudeName; static const char *refPointLongitudeName;
static const char *refPointLatitudeName; static const char *refPointLatitudeName;
...@@ -97,16 +108,17 @@ private: ...@@ -97,16 +108,17 @@ private:
// center of the circular lanes, e.g. base station // center of the circular lanes, e.g. base station
QGeoCoordinate _referencePoint; QGeoCoordinate _referencePoint;
QMap<QString, FactMetaData *> _metaDataMap; QMap<QString, FactMetaData *> _metaDataMap;
// distance between two neighbour circles // distance between two neighbour circles
SettingsFact _deltaR; SettingsFact _transectDistance;
// angle discretisation of the circles // angle discretisation of the circles
SettingsFact _deltaAlpha; SettingsFact _alpha;
// 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;
SettingsFact _type;
// Worker
using PtrWorker = std::shared_ptr<RoutingWorker>; using PtrWorker = std::shared_ptr<RoutingWorker>;
PtrWorker _pWorker; PtrWorker _pWorker;
PtrRoutingData _workerOutput; PtrRoutingData _workerOutput;
......
...@@ -3,21 +3,18 @@ ...@@ -3,21 +3,18 @@
const char *WimaJoinedAreaData::typeString = "WimaJoinedAreaData"; const char *WimaJoinedAreaData::typeString = "WimaJoinedAreaData";
WimaJoinedAreaData::WimaJoinedAreaData(QObject *parent) WimaJoinedAreaData::WimaJoinedAreaData(QObject *parent)
:WimaAreaData (parent) : WimaAreaData(parent) {}
{
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedAreaData &other,
QObject *parent)
: WimaAreaData(parent) {
*this = other;
} }
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedAreaData &other, QObject *parent) WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other,
: WimaAreaData (parent) QObject *parent)
{ : WimaAreaData(parent) {
*this = other; *this = other;
}
WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, QObject *parent)
: WimaAreaData (parent)
{
*this = other;
} }
/*! /*!
...@@ -25,11 +22,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, QObject *par ...@@ -25,11 +22,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, QObject *par
* *
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedAreaData &other) WimaJoinedAreaData &WimaJoinedAreaData::
{ operator=(const WimaJoinedAreaData &other) {
assign(other); assign(other);
return *this; return *this;
} }
/*! /*!
...@@ -37,36 +34,29 @@ WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedAreaData &othe ...@@ -37,36 +34,29 @@ WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedAreaData &othe
* *
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) {
{ assign(other);
assign(other); return *this;
return *this;
} }
QString WimaJoinedAreaData::type() const QString WimaJoinedAreaData::type() const { return this->typeString; }
{
return this->typeString;
}
void WimaJoinedAreaData::assign(const WimaJoinedAreaData &other) void WimaJoinedAreaData::assign(const WimaJoinedAreaData &other) {
{ WimaAreaData::assign(other);
WimaAreaData::assign(other);
} }
void WimaJoinedAreaData::assign(const WimaJoinedArea &other) void WimaJoinedAreaData::assign(const WimaJoinedArea &other) {
{ WimaAreaData::assign(other);
WimaAreaData::assign(other);
} }
/*! /*!
* \class WimaAreaData::WimaJoinedAreaData * \class WimaAreaData::WimaJoinedAreaData
* \brief Class to store and exchange data of a \c WimaJoinedAreaData Object. * \brief Class to store and exchange data of a \c WimaJoinedAreaData Object.
* Class to store and exchange data of a \c WimaJoinedArea Object. In contrast to \c WimaJoinedArea this class * Class to store and exchange data of a \c WimaJoinedArea Object. In contrast
* does not provied any interface to a grafical user interface, neiter it uses the QGC Fact System. * to \c WimaJoinedArea this class does not provied any interface to a grafical
* It is designed to exchange data between the \c WimaPlaner and the \c WimaController class. And it * user interface, neiter it uses the QGC Fact System. It is designed to
* is the derived from WimaAreaData. * exchange data between the \c WimaPlaner and the \c WimaController class. And
* it is the derived from WimaAreaData.
* *
* \sa WimaJoinedArea, WimaAreaData * \sa WimaJoinedArea, WimaAreaData
*/ */
#include "WimaMeasurementAreaData.h" #include "WimaMeasurementAreaData.h"
#include "SnakeTile.h"
const char *WimaMeasurementAreaData::typeString = "WimaMeasurementAreaData"; const char *WimaMeasurementAreaData::typeString = "WimaMeasurementAreaData";
WimaMeasurementAreaData::WimaMeasurementAreaData(QObject *parent) WimaMeasurementAreaData::WimaMeasurementAreaData(QObject *parent)
: WimaAreaData(parent) : WimaAreaData(parent) {}
{
WimaMeasurementAreaData::WimaMeasurementAreaData(
const WimaMeasurementAreaData &other, QObject *parent)
: WimaAreaData(parent) {
*this = other;
} }
WimaMeasurementAreaData::WimaMeasurementAreaData(const WimaMeasurementAreaData &other, QObject *parent) WimaMeasurementAreaData::WimaMeasurementAreaData(
: WimaAreaData (parent) const WimaMeasurementArea &other, QObject *parent)
{ : WimaAreaData(parent) {
*this = other; *this = other;
}
WimaMeasurementAreaData::WimaMeasurementAreaData(const WimaMeasurementArea &other, QObject *parent)
: WimaAreaData (parent)
{
*this = other;
} }
/*! /*!
...@@ -25,11 +23,11 @@ WimaMeasurementAreaData::WimaMeasurementAreaData(const WimaMeasurementArea &othe ...@@ -25,11 +23,11 @@ WimaMeasurementAreaData::WimaMeasurementAreaData(const WimaMeasurementArea &othe
* *
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaMeasurementAreaData &WimaMeasurementAreaData::operator=(const WimaMeasurementAreaData &other) WimaMeasurementAreaData &WimaMeasurementAreaData::
{ operator=(const WimaMeasurementAreaData &other) {
assign(other); assign(other);
return *this; return *this;
} }
/*! /*!
...@@ -37,28 +35,44 @@ WimaMeasurementAreaData &WimaMeasurementAreaData::operator=(const WimaMeasuremen ...@@ -37,28 +35,44 @@ WimaMeasurementAreaData &WimaMeasurementAreaData::operator=(const WimaMeasuremen
* *
* Assigns \a other to the invoking object. * Assigns \a other to the invoking object.
*/ */
WimaMeasurementAreaData &WimaMeasurementAreaData::operator=(const WimaMeasurementArea &other) WimaMeasurementAreaData &WimaMeasurementAreaData::
{ operator=(const WimaMeasurementArea &other) {
assign(other); assign(other);
return *this;
}
QString WimaMeasurementAreaData::type() const return *this;
{
return this->typeString;
} }
void WimaMeasurementAreaData::assign(const WimaMeasurementAreaData &other) QString WimaMeasurementAreaData::type() const { return this->typeString; }
{
WimaAreaData::assign(other); void WimaMeasurementAreaData::assign(const WimaMeasurementAreaData &other) {
WimaAreaData::assign(other);
this->tiles.clearAndDeleteContents();
for (std::size_t i = 0; i < other.tiles.count(); ++i) {
auto *obj = other.tiles.get(i);
auto *tile = qobject_cast<SnakeTile *>(obj);
if (tile != nullptr) {
this->tiles.append(new SnakeTile(*tile, this));
} else {
qWarning() << "WimaMeasurementAreaData::assign(): type cast failed.";
}
}
} }
void WimaMeasurementAreaData::assign(const WimaMeasurementArea &other) void WimaMeasurementAreaData::assign(const WimaMeasurementArea &other) {
{ WimaAreaData::assign(other);
WimaAreaData::assign(other); this->tiles.clearAndDeleteContents();
if (other.ready()) {
for (std::size_t i = 0; i < other.tiles()->count(); ++i) {
auto *obj = other.tiles()->get(i);
auto *tile = qobject_cast<SnakeTile *>(obj);
if (tile != nullptr) {
this->tiles.append(new SnakeTile(*tile, this));
} else {
qWarning() << "WimaMeasurementAreaData::assign(): type cast failed.";
}
}
} else {
qWarning()
<< "WimaMeasurementAreaData::assign(): WimaMeasurementArea not ready.";
}
} }
#pragma once #pragma once
#include <QObject>
#include <QGeoCoordinate> #include <QGeoCoordinate>
#include <QObject>
#include "WimaAreaData.h" #include "WimaAreaData.h"
#include "WimaMeasurementArea.h" #include "WimaMeasurementArea.h"
class WimaMeasurementAreaData : public WimaAreaData {
Q_OBJECT
class WimaMeasurementAreaData : public WimaAreaData
{
Q_OBJECT
public: public:
WimaMeasurementAreaData(QObject *parent = nullptr); WimaMeasurementAreaData(QObject *parent = nullptr);
WimaMeasurementAreaData(const WimaMeasurementAreaData &other, QObject *parent = nullptr); WimaMeasurementAreaData(const WimaMeasurementAreaData &other,
WimaMeasurementAreaData(const WimaMeasurementArea &other, QObject *parent = nullptr); QObject *parent = nullptr);
WimaMeasurementAreaData& operator=(const WimaMeasurementAreaData &other); WimaMeasurementAreaData(const WimaMeasurementArea &other,
WimaMeasurementAreaData& operator=(const WimaMeasurementArea &other); QObject *parent = nullptr);
WimaMeasurementAreaData &operator=(const WimaMeasurementAreaData &other);
WimaMeasurementAreaData &operator=(const WimaMeasurementArea &other);
QString type() const; QString type() const;
WimaMeasurementAreaData *Clone() const {return new WimaMeasurementAreaData(*this);} WimaMeasurementAreaData *Clone() const {
return new WimaMeasurementAreaData(*this);
}
static const char* typeString; static const char *typeString;
signals: signals:
public slots: public slots:
protected: protected:
void assign(const WimaMeasurementAreaData &other); void assign(const WimaMeasurementAreaData &other);
void assign(const WimaMeasurementArea &other); void assign(const WimaMeasurementArea &other);
private: private:
// see WimaMeasurementArea.h for explanation // see WimaMeasurementArea.h for explanation
QmlObjectListModel tiles;
}; };
...@@ -423,38 +423,42 @@ bool WimaController::setWimaPlanData(QSharedPointer<WimaPlanData> planData) { ...@@ -423,38 +423,42 @@ bool WimaController::setWimaPlanData(QSharedPointer<WimaPlanData> planData) {
emit visualItemsChanged(); emit visualItemsChanged();
// extract mission items // Copy transects.
auto tempMissionItems = planData->missionItems(); this->_rawTransects = planData->transects();
if (tempMissionItems.size() < 1) {
qWarning("WimaController: Mission items from WimaPlaner empty!"); // // extract mission items
return false; // auto tempMissionItems = planData->missionItems();
} // if (tempMissionItems.size() < 1) {
// qWarning("WimaController: Mission items from WimaPlaner empty!");
qWarning() << "WimaController:"; // return false;
for (auto *item : tempMissionItems) { // }
qWarning() << item->coordinate();
_defaultWM.push_back(item->coordinate()); // qWarning() << "WimaController:";
} // for (auto *item : tempMissionItems) {
// qWarning() << item->coordinate();
_WMSettings.setHomePosition(QGeoCoordinate( // _defaultWM.push_back(item->coordinate());
_serviceArea.depot().latitude(), _serviceArea.depot().longitude(), 0)); // }
qWarning() << "service area depot: " << _serviceArea.depot();
// _WMSettings.setHomePosition(QGeoCoordinate(
if (!_defaultWM.reset()) { // _serviceArea.depot().latitude(), _serviceArea.depot().longitude(),
qWarning() << "_defaultWM.reset() failed"; // 0));
return false; // qWarning() << "service area depot: " << _serviceArea.depot();
}
// if (!_defaultWM.reset()) {
emit missionItemsChanged(); // qWarning() << "_defaultWM.reset() failed";
emit currentMissionItemsChanged(); // return false;
emit waypointPathChanged(); // }
emit currentWaypointPathChanged();
// emit missionItemsChanged();
// Update Snake Data Manager // emit currentMissionItemsChanged();
_snakeThread.setMeasurementArea(_measurementArea.coordinateList()); // emit waypointPathChanged();
_snakeThread.setServiceArea(_serviceArea.coordinateList()); // emit currentWaypointPathChanged();
_snakeThread.setCorridor(_corridor.coordinateList());
_currentThread->start(); // // Update Snake Data Manager
// _snakeThread.setMeasurementArea(_measurementArea.coordinateList());
// _snakeThread.setServiceArea(_serviceArea.coordinateList());
// _snakeThread.setCorridor(_corridor.coordinateList());
// _currentThread->start();
_localPlanDataValid = true; _localPlanDataValid = true;
return true; return true;
......
...@@ -254,8 +254,8 @@ private: ...@@ -254,8 +254,8 @@ private:
// Wima Data. // Wima Data.
QmlObjectListModel _areas; // contains all visible areas QmlObjectListModel _areas; // contains all visible areas
WimaJoinedAreaData // joined area fromed by opArea, serArea, _corridor
_joinedArea; // joined area fromed by opArea, serArea, _corridor WimaJoinedAreaData _joinedArea;
WimaMeasurementAreaData _measurementArea; // measurement area WimaMeasurementAreaData _measurementArea; // measurement area
WimaServiceAreaData _serviceArea; // area for supplying WimaServiceAreaData _serviceArea; // area for supplying
WimaCorridorData _corridor; // corridor connecting opArea and serArea WimaCorridorData _corridor; // corridor connecting opArea and serArea
...@@ -274,11 +274,11 @@ private: ...@@ -274,11 +274,11 @@ private:
// Settings Facts. // Settings Facts.
QMap<QString, FactMetaData *> _metaDataMap; QMap<QString, FactMetaData *> _metaDataMap;
SettingsFact _enableWimaController; // enables or disables the wimaControler SettingsFact _enableWimaController; // enables or disables the wimaControler
SettingsFact // determines the number of overlapping waypoints between two consecutive
_overlapWaypoints; // determines the number of overlapping waypoints // mission phases
// between two consecutive mission phases SettingsFact _overlapWaypoints;
SettingsFact _maxWaypointsPerPhase; // determines the maximum number waypoints // determines the maximum number waypoints per phase
// per phase SettingsFact _maxWaypointsPerPhase;
SettingsFact SettingsFact
_nextPhaseStartWaypointIndex; // index (displayed on the map, -1 to get _nextPhaseStartWaypointIndex; // index (displayed on the map, -1 to get
// index of item in _missionItems) of the // index of item in _missionItems) of the
...@@ -294,11 +294,6 @@ private: ...@@ -294,11 +294,6 @@ private:
SettingsFact _arrivalReturnSpeed; // arrival and return path speed SettingsFact _arrivalReturnSpeed; // arrival and return path speed
SettingsFact _altitude; // mission altitude SettingsFact _altitude; // mission altitude
SettingsFact _enableSnake; // Enable Snake (see snake.h) SettingsFact _enableSnake; // Enable Snake (see snake.h)
SettingsFact _snakeTileWidth;
SettingsFact _snakeTileHeight;
SettingsFact _snakeMinTileArea;
SettingsFact _snakeLineDistance;
SettingsFact _snakeMinTransectLength;
// Smart RTL. // Smart RTL.
QTimer _smartRTLTimer; QTimer _smartRTLTimer;
...@@ -308,7 +303,7 @@ private: ...@@ -308,7 +303,7 @@ private:
double _measurementPathLength; // the lenght of the phase in meters double _measurementPathLength; // the lenght of the phase in meters
// Snake // Snake
QmlObjectListModel tiles; QList<QList<QGeoCoordinate>> _rawTransects;
SnakeThread _snakeThread; // Snake Data Manager SnakeThread _snakeThread; // Snake Data Manager
SnakeThread _emptyThread; SnakeThread _emptyThread;
SnakeThread *_currentThread; SnakeThread *_currentThread;
......
...@@ -76,6 +76,10 @@ void WimaPlanData::append(const WimaCorridorData &areaData) { ...@@ -76,6 +76,10 @@ void WimaPlanData::append(const WimaCorridorData &areaData) {
} }
} }
void WimaPlanData::setTransects(const QList<QList<QGeoCoordinate>> &transects) {
this->_transects = transects;
}
/*! /*!
* \fn void WimaPlanData::append(const WimaServiceAreaData &areaData) * \fn void WimaPlanData::append(const WimaServiceAreaData &areaData)
* *
...@@ -110,6 +114,10 @@ const QList<const WimaAreaData *> &WimaPlanData::areaList() const { ...@@ -110,6 +114,10 @@ const QList<const WimaAreaData *> &WimaPlanData::areaList() const {
return _areaList; return _areaList;
} }
const QList<QList<QGeoCoordinate>> &WimaPlanData::transects() const {
return _transects;
}
const QList<MissionItem *> &WimaPlanData::missionItems() const { const QList<MissionItem *> &WimaPlanData::missionItems() const {
return _missionItems; return _missionItems;
} }
......
#pragma once #pragma once
#include <QGeoCoordinate>
#include <QObject> #include <QObject>
#include "Geometry/WimaAreaData.h" #include "Geometry/WimaAreaData.h"
...@@ -7,7 +8,6 @@ ...@@ -7,7 +8,6 @@
#include "Geometry/WimaJoinedAreaData.h" #include "Geometry/WimaJoinedAreaData.h"
#include "Geometry/WimaMeasurementAreaData.h" #include "Geometry/WimaMeasurementAreaData.h"
#include "Geometry/WimaServiceAreaData.h" #include "Geometry/WimaServiceAreaData.h"
#include "MissionItem.h"
class WimaPlanData : public QObject { class WimaPlanData : public QObject {
Q_OBJECT Q_OBJECT
...@@ -20,7 +20,8 @@ public: ...@@ -20,7 +20,8 @@ public:
void append(const WimaJoinedAreaData &areaData); void append(const WimaJoinedAreaData &areaData);
void append(const WimaServiceAreaData &areaData); void append(const WimaServiceAreaData &areaData);
void append(const WimaCorridorData &areaData); void append(const WimaCorridorData &areaData);
void append(const WimaMeasurementAreaData &areaData);
void setTransects(const QList<QList<QGeoCoordinate>> &transects);
//! //!
//! \brief append //! \brief append
//! \param missionItems //! \param missionItems
...@@ -29,14 +30,11 @@ public: ...@@ -29,14 +30,11 @@ public:
void clear(); void clear();
const QList<const WimaAreaData *> &areaList() const; const QList<const WimaAreaData *> &areaList() const;
const QList<MissionItem *> &missionItems() const; const QList<QList<QGeoCoordinate>> &transects() const;
signals: signals:
void areaListChanged(); void areaListChanged();
private:
void _clearAndDeleteMissionItems();
private: private:
WimaJoinedAreaData _joinedArea; WimaJoinedAreaData _joinedArea;
WimaServiceAreaData _serviceArea; WimaServiceAreaData _serviceArea;
...@@ -44,5 +42,5 @@ private: ...@@ -44,5 +42,5 @@ private:
WimaMeasurementAreaData _measurementArea; WimaMeasurementAreaData _measurementArea;
QList<const WimaAreaData *> _areaList; QList<const WimaAreaData *> _areaList;
QList<MissionItem *> _missionItems; QList<QList<QGeoCoordinate>> _transects;
}; };
...@@ -666,17 +666,21 @@ void WimaPlaner::updatePolygonInteractivity(int index) { ...@@ -666,17 +666,21 @@ void WimaPlaner::updatePolygonInteractivity(int index) {
void WimaPlaner::synchronize() { void WimaPlaner::synchronize() {
if (_wimaBridge != nullptr) { if (_wimaBridge != nullptr) {
if (_needsUpdate) if (readyForSynchronization()) {
return; auto planData = toPlanData();
auto planData = toPlanData(); (void)_wimaBridge->setWimaPlanData(planData);
(void)_wimaBridge->setWimaPlanData(planData); this->_synchronized = true;
this->_synchronized = true; emit synchronizedChanged();
emit synchronizedChanged(); }
} else { } else {
qWarning("WimaPlaner::uploadToContainer(): no container assigned."); qWarning("WimaPlaner::uploadToContainer(): no container assigned.");
} }
} }
bool WimaPlaner::readyForSynchronization() {
return !_needsUpdate && _measurementArea.ready();
}
bool WimaPlaner::shortestPath(const QGeoCoordinate &start, bool WimaPlaner::shortestPath(const QGeoCoordinate &start,
const QGeoCoordinate &destination, const QGeoCoordinate &destination,
QVector<QGeoCoordinate> &path) { QVector<QGeoCoordinate> &path) {
...@@ -737,14 +741,7 @@ QSharedPointer<WimaPlanData> WimaPlaner::toPlanData() { ...@@ -737,14 +741,7 @@ QSharedPointer<WimaPlanData> WimaPlaner::toPlanData() {
planData->append(WimaJoinedAreaData(_joinedArea)); planData->append(WimaJoinedAreaData(_joinedArea));
// convert mission items to mavlink commands // convert mission items to mavlink commands
QList<MissionItem *> missionItems; planData->setTransects(this->_TSComplexItem->rawTransects());
_TSComplexItem->appendMissionItems(missionItems, nullptr);
// store mavlink commands
qWarning() << "WimaPlaner";
for (auto *item : missionItems) {
qWarning() << item->coordinate();
}
planData->append(missionItems);
return planData; return planData;
} }
......
...@@ -84,6 +84,7 @@ public: ...@@ -84,6 +84,7 @@ public:
Q_INVOKABLE bool update(); Q_INVOKABLE bool update();
/// Pushes the generated mission data to the wimaController. /// Pushes the generated mission data to the wimaController.
Q_INVOKABLE void synchronize(); Q_INVOKABLE void synchronize();
Q_INVOKABLE bool readyForSynchronization();
Q_INVOKABLE void saveToCurrent(); Q_INVOKABLE void saveToCurrent();
Q_INVOKABLE void saveToFile(const QString &filename); Q_INVOKABLE void saveToFile(const QString &filename);
Q_INVOKABLE bool loadFromCurrent(); Q_INVOKABLE bool loadFromCurrent();
......
[ [
{ {
"name": "DeltaR", "name": "TransectDistance",
"shortDescription": "The distance between two consecutive circles.", "shortDescription": "The distance between transects.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
...@@ -9,18 +9,18 @@ ...@@ -9,18 +9,18 @@
"defaultValue": 20.0 "defaultValue": 20.0
}, },
{ {
"name": "DeltaAlpha", "name": "Alpha",
"shortDescription": "Angle discretisation of the circles.", "shortDescription": "Angle discretisation or transect angle (depending on type).",
"type": "double", "type": "double",
"units": "Deg", "units": "Deg",
"min": 0.3, "min": 0,
"max": 90, "max": 180,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 5.0 "defaultValue": 5.0
}, },
{ {
"name": "TransectMinLength", "name": "MinLength",
"shortDescription": "The minimal length transects must have to be accepted.", "shortDescription": "The minimal transect length.",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0.3, "min": 0.3,
...@@ -28,23 +28,11 @@ ...@@ -28,23 +28,11 @@
"defaultValue": 5.0 "defaultValue": 5.0
}, },
{ {
"name": "FixedDirection", "name": "Type",
"shortDescription": "Determines whether all transects have the same direction or not.", "shortDescription": "Survey Type.",
"type": "bool", "type": "uint64",
"defaultValue": 1 "min": 0,
}, "max": 1,
{
"name": "Reverse",
"shortDescription": "Reverses the transect path.",
"type": "bool",
"defaultValue": 0 "defaultValue": 0
},
{
"name": "MaxWaypoints",
"shortDescription": "The maximum number of waypoints the circular survey can containt. To many waypoints cause a performance hit.",
"type": "uint32",
"defaultValue": 2000,
"min": 1,
"max": 20000
} }
] ]
...@@ -27,29 +27,68 @@ Item { ...@@ -27,29 +27,68 @@ Item {
property var _missionItem: object property var _missionItem: object
property var _mapPolygon: object.surveyAreaPolygon property var _mapPolygon: object.surveyAreaPolygon
property var _visualTransectsComponent property var _transectsComponent
property var _entryCoordinate property var _entryCoordinate
property var _exitCoordinate property var _exitCoordinate
property var _refPoint property var _refPoint
property bool showRefPoint: _missionItem.type.value === 0 // type == Circular
signal clicked(int sequenceNumber) signal clicked(int sequenceNumber)
function _addVisualElements() { function _addTransectsComponent(){
_visualTransectsComponent = visualTransectsComponent.createObject(map) if (!_transectsComponent){
_entryCoordinate = entryPointComponent.createObject(map) _transectsComponent = visualTransectsComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map) map.addMapItem(_transectsComponent)
_refPoint = refPointComponent.createObject(map) }
map.addMapItem(_visualTransectsComponent) }
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate) function _addExitCoordinate(){
map.addMapItem(_refPoint) if (!_exitCoordinate){
_exitCoordinate = exitPointComponent.createObject(map)
map.addMapItem(_exitCoordinate)
}
}
function _addEntryCoordinate(){
if (!_entryCoordinate){
_entryCoordinate = entryPointComponent.createObject(map)
map.addMapItem(_entryCoordinate)
}
}
function _addRefPoint(){
if (!_refPoint){
_refPoint = refPointComponent.createObject(map)
map.addMapItem(_refPoint)
}
}
function _destroyEntryCoordinate(){
if (_entryCoordinate){
_entryCoordinate.destroy()
_entryCoordinate = undefined
}
}
function _destroyExitCoordinate(){
if (_exitCoordinate){
_exitCoordinate.destroy()
_exitCoordinate = undefined
}
} }
function _destroyVisualElements() { function _destroyRefPoint(){
_visualTransectsComponent.destroy() if (_refPoint){
_entryCoordinate.destroy() _refPoint.destroy()
_exitCoordinate.destroy() _refPoint = undefined
_refPoint.destroy() }
}
function _destroyTransectsComponent(){
if (_transectsComponent){
_transectsComponent.destroy()
_transectsComponent = undefined
}
} }
/// Add an initial 4 sided polygon if there is none /// Add an initial 4 sided polygon if there is none
...@@ -83,20 +122,33 @@ Item { ...@@ -83,20 +122,33 @@ Item {
} }
} }
function _setRefPoint() {
_missionItem.resetReference();
}
Component.onCompleted: { Component.onCompleted: {
if ( _missionItem.visualTransectPoints.length === 0 ) { if ( _mapPolygon.count === 0 ) {
_addInitialPolygon() _addInitialPolygon()
_setRefPoint() _missionItem.resetReference();
} }
_addVisualElements() _addEntryCoordinate()
_addExitCoordinate()
if (showRefPoint){
_addRefPoint()
}
_addTransectsComponent()
} }
Component.onDestruction: { Component.onDestruction: {
_destroyVisualElements() _destroyEntryCoordinate()
_destroyExitCoordinate()
_destroyRefPoint()
_destroyTransectsComponent()
}
onShowRefPointChanged: {
if (showRefPoint){
_addRefPoint()
} else {
_destroyRefPoint()
}
} }
WimaMapPolygonVisuals { WimaMapPolygonVisuals {
...@@ -117,9 +169,10 @@ Item { ...@@ -117,9 +169,10 @@ Item {
id: visualTransectsComponent id: visualTransectsComponent
MapPolyline { MapPolyline {
property var transects: _missionItem.visualTransectPoints
line.color: "white" line.color: "white"
line.width: 2 line.width: 2
path: _missionItem.visualTransectPoints path: transects.length > 0 ? transects : []
} }
} }
...@@ -174,20 +227,13 @@ Item { ...@@ -174,20 +227,13 @@ Item {
checked: _missionItem.isCurrentItem checked: _missionItem.isCurrentItem
coordinate: _missionItem.refPoint coordinate: _missionItem.refPoint
property var refPoint: _missionItem.refPoint
onRefPointChanged: {
if (refPoint !== coordinate) {
coordinate = refPoint
}
}
onClicked: { onClicked: {
_root.clicked(_missionItem.sequenceNumber) _root.clicked(_missionItem.sequenceNumber)
} }
onDragReleased: { onDragReleased: {
_missionItem.refPoint = coordinate _missionItem.refPoint = coordinate
coordinate = Qt.binding(function (){return _missionItem.refPoint})
} }
} }
} }
......
...@@ -104,7 +104,7 @@ Item { ...@@ -104,7 +104,7 @@ Item {
Component.onCompleted: { Component.onCompleted: {
_addInitialPolygon() _addInitialPolygon()
if (interactive){ if (showDepot){
_addDepot() _addDepot()
} }
} }
......
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