Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
47641f63
Commit
47641f63
authored
Sep 26, 2020
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
wima planer edited
parent
1ac83998
Changes
17
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
17 changed files
with
555 additions
and
1030 deletions
+555
-1030
CircularSurveyItemEditor.qml
src/PlanView/CircularSurveyItemEditor.qml
+48
-24
CSWorker.cpp
src/Wima/CSWorker.cpp
+1
-1
CS_old.cc
src/Wima/CS_old.cc
+0
-737
CircularSurvey.cc
src/Wima/CircularSurvey.cc
+228
-44
CircularSurvey.h
src/Wima/CircularSurvey.h
+24
-12
WimaJoinedAreaData.cc
src/Wima/Geometry/WimaJoinedAreaData.cc
+26
-36
WimaMeasurementAreaData.cc
src/Wima/Geometry/WimaMeasurementAreaData.cc
+49
-35
WimaMeasurementAreaData.h
src/Wima/Geometry/WimaMeasurementAreaData.h
+19
-18
WimaController.cc
src/Wima/WimaController.cc
+36
-32
WimaController.h
src/Wima/WimaController.h
+8
-13
WimaPlanData.cc
src/Wima/WimaPlanData.cc
+8
-0
WimaPlanData.h
src/Wima/WimaPlanData.h
+5
-7
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+11
-14
WimaPlaner.h
src/Wima/WimaPlaner.h
+1
-0
CircularSurvey.SettingsGroup.json
src/Wima/json/CircularSurvey.SettingsGroup.json
+13
-25
CircularSurveyMapVisual.qml
src/WimaView/CircularSurveyMapVisual.qml
+77
-31
WimaServiceAreaMapVisual.qml
src/WimaView/WimaServiceAreaMapVisual.qml
+1
-1
No files found.
src/PlanView/CircularSurveyItemEditor.qml
View file @
47641f63
...
...
@@ -64,6 +64,7 @@ Rectangle {
GridLayout
{
id
:
generalGrid
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
_margin
...
...
@@ -75,7 +76,48 @@ Rectangle {
FactTextField
{
fact
:
missionItem
.
cameraCalc
.
distanceToSurface
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 {
columns
:
2
visible
:
transectsHeader
.
checked
QGCLabel
{
text
:
qsTr
(
"
D
elta R
"
)
}
QGCLabel
{
text
:
qsTr
(
"
D
istance
"
)
}
FactTextField
{
fact
:
missionItem
.
deltaR
fact
:
missionItem
.
transectDistance
Layout.fillWidth
:
true
//onUpdated: rSlider.value = missionItem.deltaR.value
}
/*QGCSlider {
...
...
@@ -113,18 +154,16 @@ Rectangle {
updateValueWhileDragging: true
}*/
QGCLabel
{
text
:
qsTr
(
"
Delta
Alpha
"
)
}
QGCLabel
{
text
:
qsTr
(
"
Alpha
"
)
}
FactTextField
{
fact
:
missionItem
.
deltaA
lpha
fact
:
missionItem
.
a
lpha
Layout.fillWidth
:
true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
QGCLabel
{
text
:
qsTr
(
"
Min. Length
"
)
}
FactTextField
{
fact
:
missionItem
.
transectM
inLength
fact
:
missionItem
.
m
inLength
Layout.fillWidth
:
true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
}
...
...
@@ -148,21 +187,6 @@ Rectangle {
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
}
}
}
...
...
src/Wima/CSWorker.cpp
View file @
47641f63
...
...
@@ -73,7 +73,7 @@ void RoutingWorker::run() {
auto
&
transectsInfo
=
pRouteData
->
transectsInfo
;
auto
&
route
=
pRouteData
->
route
;
const
auto
routingStart
=
std
::
chrono
::
high_resolution_clock
::
now
();
const
auto
maxRoutingTime
=
std
::
chrono
::
minutes
(
1
);
const
auto
maxRoutingTime
=
std
::
chrono
::
minutes
(
1
0
);
const
auto
routingEnd
=
routingStart
+
maxRoutingTime
;
const
auto
&
restart
=
this
->
_restart
;
auto
stopLambda
=
[
&
restart
,
routingEnd
]
{
...
...
src/Wima/CS_old.cc
deleted
100644 → 0
View file @
1ac83998
This diff is collapsed.
Click to expand it.
src/Wima/CircularSurvey.cc
View file @
47641f63
This diff is collapsed.
Click to expand it.
src/Wima/CircularSurvey.h
View file @
47641f63
...
...
@@ -13,6 +13,11 @@ class CircularSurvey : public TransectStyleComplexItem {
Q_OBJECT
public:
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 flyView true: Created for use in the Fly View, false: Created for
...
...
@@ -25,9 +30,11 @@ public:
Q_PROPERTY
(
QGeoCoordinate
refPoint
READ
refPoint
WRITE
setRefPoint
NOTIFY
refPointChanged
)
Q_PROPERTY
(
Fact
*
deltaR
READ
deltaR
CONSTANT
)
Q_PROPERTY
(
Fact
*
deltaAlpha
READ
deltaAlpha
CONSTANT
)
Q_PROPERTY
(
Fact
*
transectMinLength
READ
transectMinLength
CONSTANT
)
Q_PROPERTY
(
Fact
*
transectDistance
READ
transectDistance
CONSTANT
)
Q_PROPERTY
(
Fact
*
alpha
READ
alpha
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
hidePolygon
READ
hidePolygon
NOTIFY
hidePolygonChanged
)
...
...
@@ -42,13 +49,16 @@ public:
// Property getters
QGeoCoordinate
refPoint
()
const
;
Fact
*
deltaR
();
Fact
*
deltaAlpha
();
Fact
*
transectMinLength
();
Fact
*
transectDistance
();
Fact
*
alpha
();
Fact
*
minLength
();
Fact
*
type
();
int
typeCount
()
const
;
bool
calculating
()
const
;
bool
hidePolygon
()
const
;
QGeoCoordinate
depot
()
const
;
QList
<
QGeoCoordinate
>
safeArea
()
const
;
const
QList
<
QList
<
QGeoCoordinate
>>
&
rawTransects
()
const
;
// Overrides
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
...
...
@@ -67,9 +77,10 @@ public:
double
additionalTimeDelay
(
void
)
const
override
final
;
static
const
char
*
settingsGroup
;
static
const
char
*
deltaRName
;
static
const
char
*
deltaAlphaName
;
static
const
char
*
transectMinLengthName
;
static
const
char
*
transectDistanceName
;
static
const
char
*
alphaName
;
static
const
char
*
minLengthName
;
static
const
char
*
typeName
;
static
const
char
*
CircularSurveyName
;
static
const
char
*
refPointLongitudeName
;
static
const
char
*
refPointLatitudeName
;
...
...
@@ -97,16 +108,17 @@ private:
// center of the circular lanes, e.g. base station
QGeoCoordinate
_referencePoint
;
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
// distance between two neighbour circles
SettingsFact
_
deltaR
;
SettingsFact
_
transectDistance
;
// angle discretisation of the circles
SettingsFact
_
deltaA
lpha
;
SettingsFact
_
a
lpha
;
// minimal transect lenght, transects are rejected if they are shorter than
// this value
SettingsFact
_minLength
;
SettingsFact
_type
;
// Worker
using
PtrWorker
=
std
::
shared_ptr
<
RoutingWorker
>
;
PtrWorker
_pWorker
;
PtrRoutingData
_workerOutput
;
...
...
src/Wima/Geometry/WimaJoinedAreaData.cc
View file @
47641f63
...
...
@@ -3,21 +3,18 @@
const
char
*
WimaJoinedAreaData
::
typeString
=
"WimaJoinedAreaData"
;
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
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
}
WimaJoinedAreaData
::
WimaJoinedAreaData
(
const
WimaJoinedArea
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
WimaJoinedAreaData
::
WimaJoinedAreaData
(
const
WimaJoinedArea
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
}
/*!
...
...
@@ -25,11 +22,11 @@ WimaJoinedAreaData::WimaJoinedAreaData(const WimaJoinedArea &other, QObject *par
*
* Assigns \a other to the invoking object.
*/
WimaJoinedAreaData
&
WimaJoinedAreaData
::
operator
=
(
const
WimaJoinedAreaData
&
other
)
{
assign
(
other
);
WimaJoinedAreaData
&
WimaJoinedAreaData
::
operator
=
(
const
WimaJoinedAreaData
&
other
)
{
assign
(
other
);
return
*
this
;
return
*
this
;
}
/*!
...
...
@@ -37,36 +34,29 @@ WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedAreaData &othe
*
* Assigns \a other to the invoking object.
*/
WimaJoinedAreaData
&
WimaJoinedAreaData
::
operator
=
(
const
WimaJoinedArea
&
other
)
{
assign
(
other
);
return
*
this
;
WimaJoinedAreaData
&
WimaJoinedAreaData
::
operator
=
(
const
WimaJoinedArea
&
other
)
{
assign
(
other
);
return
*
this
;
}
QString
WimaJoinedAreaData
::
type
()
const
{
return
this
->
typeString
;
}
QString
WimaJoinedAreaData
::
type
()
const
{
return
this
->
typeString
;
}
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedAreaData
&
other
)
{
WimaAreaData
::
assign
(
other
);
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedAreaData
&
other
)
{
WimaAreaData
::
assign
(
other
);
}
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedArea
&
other
)
{
WimaAreaData
::
assign
(
other
);
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedArea
&
other
)
{
WimaAreaData
::
assign
(
other
);
}
/*!
* \class WimaAreaData::WimaJoinedAreaData
* \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
* does not provied any interface to a grafical user interface, neiter it uses the QGC Fact System.
* It is designed to exchange data between the \c WimaPlaner and the \c WimaController class. And it
* is the derived from WimaAreaData.
* Class to store and exchange data of a \c WimaJoinedArea Object. In contrast
* to \c WimaJoinedArea this class does not provied any interface to a grafical
* user interface, neiter it uses the QGC Fact System. It is designed to
* exchange data between the \c WimaPlaner and the \c WimaController class. And
* it is the derived from WimaAreaData.
*
* \sa WimaJoinedArea, WimaAreaData
*/
src/Wima/Geometry/WimaMeasurementAreaData.cc
View file @
47641f63
#include "WimaMeasurementAreaData.h"
#include "SnakeTile.h"
const
char
*
WimaMeasurementAreaData
::
typeString
=
"WimaMeasurementAreaData"
;
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
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
}
WimaMeasurementAreaData
::
WimaMeasurementAreaData
(
const
WimaMeasurementArea
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
WimaMeasurementAreaData
::
WimaMeasurementAreaData
(
const
WimaMeasurementArea
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{
*
this
=
other
;
}
/*!
...
...
@@ -25,11 +23,11 @@ WimaMeasurementAreaData::WimaMeasurementAreaData(const WimaMeasurementArea &othe
*
* Assigns \a other to the invoking object.
*/
WimaMeasurementAreaData
&
WimaMeasurementAreaData
::
operator
=
(
const
WimaMeasurementAreaData
&
other
)
{
assign
(
other
);
WimaMeasurementAreaData
&
WimaMeasurementAreaData
::
operator
=
(
const
WimaMeasurementAreaData
&
other
)
{
assign
(
other
);
return
*
this
;
return
*
this
;
}
/*!
...
...
@@ -37,28 +35,44 @@ WimaMeasurementAreaData &WimaMeasurementAreaData::operator=(const WimaMeasuremen
*
* Assigns \a other to the invoking object.
*/
WimaMeasurementAreaData
&
WimaMeasurementAreaData
::
operator
=
(
const
WimaMeasurementArea
&
other
)
{
assign
(
other
);
return
*
this
;
}
WimaMeasurementAreaData
&
WimaMeasurementAreaData
::
operator
=
(
const
WimaMeasurementArea
&
other
)
{
assign
(
other
);
QString
WimaMeasurementAreaData
::
type
()
const
{
return
this
->
typeString
;
return
*
this
;
}
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementAreaData
&
other
)
{
WimaAreaData
::
assign
(
other
);
QString
WimaMeasurementAreaData
::
type
()
const
{
return
this
->
typeString
;
}
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
)
{
WimaAreaData
::
assign
(
other
);
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementArea
&
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."
;
}
}
src/Wima/Geometry/WimaMeasurementAreaData.h
View file @
47641f63
#pragma once
#include <QObject>
#include <QGeoCoordinate>
#include <QObject>
#include "WimaAreaData.h"
#include "WimaMeasurementArea.h"
class
WimaMeasurementAreaData
:
public
WimaAreaData
{
Q_OBJECT
class
WimaMeasurementAreaData
:
public
WimaAreaData
{
Q_OBJECT
public:
WimaMeasurementAreaData
(
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
(
const
WimaMeasurementAreaData
&
other
,
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
(
const
WimaMeasurementArea
&
other
,
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementAreaData
&
other
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementArea
&
other
);
WimaMeasurementAreaData
(
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
(
const
WimaMeasurementAreaData
&
other
,
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
(
const
WimaMeasurementArea
&
other
,
QObject
*
parent
=
nullptr
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementAreaData
&
other
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementArea
&
other
);
QString
type
()
const
;
WimaMeasurementAreaData
*
Clone
()
const
{
return
new
WimaMeasurementAreaData
(
*
this
);}
QString
type
()
const
;
WimaMeasurementAreaData
*
Clone
()
const
{
return
new
WimaMeasurementAreaData
(
*
this
);
}
static
const
char
*
typeString
;
static
const
char
*
typeString
;
signals:
public
slots
:
protected:
void
assign
(
const
WimaMeasurementAreaData
&
other
);
void
assign
(
const
WimaMeasurementArea
&
other
);
void
assign
(
const
WimaMeasurementAreaData
&
other
);
void
assign
(
const
WimaMeasurementArea
&
other
);
private:
// see WimaMeasurementArea.h for explanation
// see WimaMeasurementArea.h for explanation
QmlObjectListModel
tiles
;
};
src/Wima/WimaController.cc
View file @
47641f63
...
...
@@ -423,38 +423,42 @@ bool WimaController::setWimaPlanData(QSharedPointer<WimaPlanData> planData) {
emit
visualItemsChanged
();
// extract mission items
auto
tempMissionItems
=
planData
->
missionItems
();
if
(
tempMissionItems
.
size
()
<
1
)
{
qWarning
(
"WimaController: Mission items from WimaPlaner empty!"
);
return
false
;
}
qWarning
()
<<
"WimaController:"
;
for
(
auto
*
item
:
tempMissionItems
)
{
qWarning
()
<<
item
->
coordinate
();
_defaultWM
.
push_back
(
item
->
coordinate
());
}
_WMSettings
.
setHomePosition
(
QGeoCoordinate
(
_serviceArea
.
depot
().
latitude
(),
_serviceArea
.
depot
().
longitude
(),
0
));
qWarning
()
<<
"service area depot: "
<<
_serviceArea
.
depot
();
if
(
!
_defaultWM
.
reset
())
{
qWarning
()
<<
"_defaultWM.reset() failed"
;
return
false
;
}
emit
missionItemsChanged
();
emit
currentMissionItemsChanged
();
emit
waypointPathChanged
();
emit
currentWaypointPathChanged
();
// Update Snake Data Manager
_snakeThread
.
setMeasurementArea
(
_measurementArea
.
coordinateList
());
_snakeThread
.
setServiceArea
(
_serviceArea
.
coordinateList
());
_snakeThread
.
setCorridor
(
_corridor
.
coordinateList
());
_currentThread
->
start
();
// Copy transects.
this
->
_rawTransects
=
planData
->
transects
();
// // extract mission items
// auto tempMissionItems = planData->missionItems();
// if (tempMissionItems.size() < 1) {
// qWarning("WimaController: Mission items from WimaPlaner empty!");
// return false;
// }
// qWarning() << "WimaController:";
// for (auto *item : tempMissionItems) {
// qWarning() << item->coordinate();
// _defaultWM.push_back(item->coordinate());
// }
// _WMSettings.setHomePosition(QGeoCoordinate(
// _serviceArea.depot().latitude(), _serviceArea.depot().longitude(),
// 0));
// qWarning() << "service area depot: " << _serviceArea.depot();
// if (!_defaultWM.reset()) {
// qWarning() << "_defaultWM.reset() failed";
// return false;
// }
// emit missionItemsChanged();
// emit currentMissionItemsChanged();
// emit waypointPathChanged();
// emit currentWaypointPathChanged();
// // Update Snake Data Manager
// _snakeThread.setMeasurementArea(_measurementArea.coordinateList());
// _snakeThread.setServiceArea(_serviceArea.coordinateList());
// _snakeThread.setCorridor(_corridor.coordinateList());
// _currentThread->start();
_localPlanDataValid
=
true
;
return
true
;
...
...
src/Wima/WimaController.h
View file @
47641f63
...
...
@@ -254,8 +254,8 @@ private:
// Wima Data.
QmlObjectListModel
_areas
;
// contains all visible areas
WimaJoinedAreaData
_joinedArea
;
// joined area fromed by opArea, serArea, _corridor
// joined area fromed by opArea, serArea, _corridor
WimaJoinedAreaData
_joinedArea
;
WimaMeasurementAreaData
_measurementArea
;
// measurement area
WimaServiceAreaData
_serviceArea
;
// area for supplying
WimaCorridorData
_corridor
;
// corridor connecting opArea and serArea
...
...
@@ -274,11 +274,11 @@ private:
// Settings Facts.
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_enableWimaController
;
// enables or disables the wimaControler
SettingsFact
_overlapWaypoints
;
// determines the number of overlapping waypoint
s
// between two consecutive mission phases
SettingsFact
_maxWaypointsPerPhase
;
// determines the maximum number waypoints
// per phase
// determines the number of overlapping waypoints between two consecutive
// mission phase
s
SettingsFact
_overlapWaypoints
;
// determines the maximum number waypoints per phase
SettingsFact
_maxWaypointsPerPhase
;
SettingsFact
_nextPhaseStartWaypointIndex
;
// index (displayed on the map, -1 to get
// index of item in _missionItems) of the
...
...
@@ -294,11 +294,6 @@ private:
SettingsFact
_arrivalReturnSpeed
;
// arrival and return path speed
SettingsFact
_altitude
;
// mission altitude
SettingsFact
_enableSnake
;
// Enable Snake (see snake.h)
SettingsFact
_snakeTileWidth
;
SettingsFact
_snakeTileHeight
;
SettingsFact
_snakeMinTileArea
;
SettingsFact
_snakeLineDistance
;
SettingsFact
_snakeMinTransectLength
;
// Smart RTL.
QTimer
_smartRTLTimer
;
...
...
@@ -308,7 +303,7 @@ private:
double
_measurementPathLength
;
// the lenght of the phase in meters
// Snake
Q
mlObjectListModel
tile
s
;
Q
List
<
QList
<
QGeoCoordinate
>>
_rawTransect
s
;
SnakeThread
_snakeThread
;
// Snake Data Manager
SnakeThread
_emptyThread
;
SnakeThread
*
_currentThread
;
...
...
src/Wima/WimaPlanData.cc
View file @
47641f63
...
...
@@ -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)
*
...
...
@@ -110,6 +114,10 @@ const QList<const WimaAreaData *> &WimaPlanData::areaList() const {
return
_areaList
;
}
const
QList
<
QList
<
QGeoCoordinate
>>
&
WimaPlanData
::
transects
()
const
{
return
_transects
;
}
const
QList
<
MissionItem
*>
&
WimaPlanData
::
missionItems
()
const
{
return
_missionItems
;
}
...
...
src/Wima/WimaPlanData.h
View file @
47641f63
#pragma once
#include <QGeoCoordinate>
#include <QObject>
#include "Geometry/WimaAreaData.h"
...
...
@@ -7,7 +8,6 @@
#include "Geometry/WimaJoinedAreaData.h"
#include "Geometry/WimaMeasurementAreaData.h"
#include "Geometry/WimaServiceAreaData.h"
#include "MissionItem.h"
class
WimaPlanData
:
public
QObject
{
Q_OBJECT
...
...
@@ -20,7 +20,8 @@ public:
void
append
(
const
WimaJoinedAreaData
&
areaData
);
void
append
(
const
WimaServiceAreaData
&
areaData
);
void
append
(
const
WimaCorridorData
&
areaData
);
void
append
(
const
WimaMeasurementAreaData
&
areaData
);
void
setTransects
(
const
QList
<
QList
<
QGeoCoordinate
>>
&
transects
);
//!
//! \brief append
//! \param missionItems
...
...
@@ -29,14 +30,11 @@ public:
void
clear
();
const
QList
<
const
WimaAreaData
*>
&
areaList
()
const
;
const
QList
<
MissionItem
*>
&
missionItem
s
()
const
;
const
QList
<
QList
<
QGeoCoordinate
>>
&
transect
s
()
const
;
signals:
void
areaListChanged
();
private:
void
_clearAndDeleteMissionItems
();
private:
WimaJoinedAreaData
_joinedArea
;
WimaServiceAreaData
_serviceArea
;
...
...
@@ -44,5 +42,5 @@ private:
WimaMeasurementAreaData
_measurementArea
;
QList
<
const
WimaAreaData
*>
_areaList
;
QList
<
MissionItem
*>
_missionItem
s
;
QList
<
QList
<
QGeoCoordinate
>>
_transect
s
;
};
src/Wima/WimaPlaner.cc
View file @
47641f63
...
...
@@ -666,17 +666,21 @@ void WimaPlaner::updatePolygonInteractivity(int index) {
void
WimaPlaner
::
synchronize
()
{
if
(
_wimaBridge
!=
nullptr
)
{
if
(
_needsUpdate
)
return
;
auto
planData
=
toPlanData
(
);
(
void
)
_wimaBridge
->
setWimaPlanData
(
planData
)
;
this
->
_synchronized
=
true
;
emit
synchronizedChanged
();
if
(
readyForSynchronization
())
{
auto
planData
=
toPlanData
()
;
(
void
)
_wimaBridge
->
setWimaPlanData
(
planData
);
this
->
_synchronized
=
true
;
emit
synchronizedChanged
()
;
}
}
else
{
qWarning
(
"WimaPlaner::uploadToContainer(): no container assigned."
);
}
}
bool
WimaPlaner
::
readyForSynchronization
()
{
return
!
_needsUpdate
&&
_measurementArea
.
ready
();
}
bool
WimaPlaner
::
shortestPath
(
const
QGeoCoordinate
&
start
,
const
QGeoCoordinate
&
destination
,
QVector
<
QGeoCoordinate
>
&
path
)
{
...
...
@@ -737,14 +741,7 @@ QSharedPointer<WimaPlanData> WimaPlaner::toPlanData() {
planData
->
append
(
WimaJoinedAreaData
(
_joinedArea
));
// convert mission items to mavlink commands
QList
<
MissionItem
*>
missionItems
;
_TSComplexItem
->
appendMissionItems
(
missionItems
,
nullptr
);
// store mavlink commands
qWarning
()
<<
"WimaPlaner"
;
for
(
auto
*
item
:
missionItems
)
{
qWarning
()
<<
item
->
coordinate
();
}
planData
->
append
(
missionItems
);
planData
->
setTransects
(
this
->
_TSComplexItem
->
rawTransects
());
return
planData
;
}
...
...
src/Wima/WimaPlaner.h
View file @
47641f63
...
...
@@ -84,6 +84,7 @@ public:
Q_INVOKABLE
bool
update
();
/// Pushes the generated mission data to the wimaController.
Q_INVOKABLE
void
synchronize
();
Q_INVOKABLE
bool
readyForSynchronization
();
Q_INVOKABLE
void
saveToCurrent
();
Q_INVOKABLE
void
saveToFile
(
const
QString
&
filename
);
Q_INVOKABLE
bool
loadFromCurrent
();
...
...
src/Wima/json/CircularSurvey.SettingsGroup.json
View file @
47641f63
[
{
"name"
:
"
DeltaR
"
,
"shortDescription"
:
"The distance between t
wo consecutive circle
s."
,
"name"
:
"
TransectDistance
"
,
"shortDescription"
:
"The distance between t
ransect
s."
,
"type"
:
"double"
,
"units"
:
"m"
,
"min"
:
0.3
,
...
...
@@ -9,18 +9,18 @@
"defaultValue"
:
20.0
},
{
"name"
:
"
Delta
Alpha"
,
"shortDescription"
:
"Angle discretisation o
f the circles
."
,
"name"
:
"Alpha"
,
"shortDescription"
:
"Angle discretisation o
r transect angle (depending on type)
."
,
"type"
:
"double"
,
"units"
:
"Deg"
,
"min"
:
0
.3
,
"max"
:
9
0
,
"min"
:
0
,
"max"
:
18
0
,
"decimalPlaces"
:
1
,
"defaultValue"
:
5.0
},
{
"name"
:
"
Transect
MinLength"
,
"shortDescription"
:
"The minimal
length transects must have to be accepted
."
,
"name"
:
"MinLength"
,
"shortDescription"
:
"The minimal
transect length
."
,
"type"
:
"double"
,
"units"
:
"m"
,
"min"
:
0.3
,
...
...
@@ -28,23 +28,11 @@
"defaultValue"
:
5.0
},
{
"name"
:
"FixedDirection"
,
"shortDescription"
:
"Determines whether all transects have the same direction or not."
,
"type"
:
"bool"
,
"defaultValue"
:
1
},
{
"name"
:
"Reverse"
,
"shortDescription"
:
"Reverses the transect path."
,
"type"
:
"bool"
,
"name"
:
"Type"
,
"shortDescription"
:
"Survey Type."
,
"type"
:
"uint64"
,
"min"
:
0
,
"max"
:
1
,
"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
}
]
src/WimaView/CircularSurveyMapVisual.qml
View file @
47641f63
...
...
@@ -27,29 +27,68 @@ Item {
property
var
_missionItem
:
object
property
var
_mapPolygon
:
object
.
surveyAreaPolygon
property
var
_
visualT
ransectsComponent
property
var
_
t
ransectsComponent
property
var
_entryCoordinate
property
var
_exitCoordinate
property
var
_refPoint
property
bool
showRefPoint
:
_missionItem
.
type
.
value
===
0
// type == Circular
signal
clicked
(
int
sequenceNumber
)
function
_addVisualElements
()
{
_visualTransectsComponent
=
visualTransectsComponent
.
createObject
(
map
)
_entryCoordinate
=
entryPointComponent
.
createObject
(
map
)
_exitCoordinate
=
exitPointComponent
.
createObject
(
map
)
_refPoint
=
refPointComponent
.
createObject
(
map
)
map
.
addMapItem
(
_visualTransectsComponent
)
map
.
addMapItem
(
_entryCoordinate
)
map
.
addMapItem
(
_exitCoordinate
)
map
.
addMapItem
(
_refPoint
)
function
_addTransectsComponent
(){
if
(
!
_transectsComponent
){
_transectsComponent
=
visualTransectsComponent
.
createObject
(
map
)
map
.
addMapItem
(
_transectsComponent
)
}
}
function
_addExitCoordinate
(){
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
()
{
_visualTransectsComponent
.
destroy
()
_entryCoordinate
.
destroy
()
_exitCoordinate
.
destroy
()
_refPoint
.
destroy
()
function
_destroyRefPoint
(){
if
(
_refPoint
){
_refPoint
.
destroy
()
_refPoint
=
undefined
}
}
function
_destroyTransectsComponent
(){
if
(
_transectsComponent
){
_transectsComponent
.
destroy
()
_transectsComponent
=
undefined
}
}
/// Add an initial 4 sided polygon if there is none
...
...
@@ -83,20 +122,33 @@ Item {
}
}
function
_setRefPoint
()
{
_missionItem
.
resetReference
();
}
Component.onCompleted
:
{
if
(
_m
issionItem
.
visualTransectPoints
.
length
===
0
)
{
if
(
_m
apPolygon
.
count
===
0
)
{
_addInitialPolygon
()
_
setRefPoint
()
_
missionItem
.
resetReference
();
}
_addVisualElements
()
_addEntryCoordinate
()
_addExitCoordinate
()
if
(
showRefPoint
){
_addRefPoint
()
}
_addTransectsComponent
()
}
Component
.
onDestruction
:
{
_destroyVisualElements
()
_destroyEntryCoordinate
()
_destroyExitCoordinate
()
_destroyRefPoint
()
_destroyTransectsComponent
()
}
onShowRefPointChanged
:
{
if
(
showRefPoint
){
_addRefPoint
()
}
else
{
_destroyRefPoint
()
}
}
WimaMapPolygonVisuals
{
...
...
@@ -117,9 +169,10 @@ Item {
id
:
visualTransectsComponent
MapPolyline
{
property
var
transects
:
_missionItem
.
visualTransectPoints
line.color
:
"
white
"
line.width
:
2
path
:
_missionItem
.
visualTransectPoints
path
:
transects
.
length
>
0
?
transects
:
[]
}
}
...
...
@@ -174,20 +227,13 @@ Item {
checked
:
_missionItem
.
isCurrentItem
coordinate
:
_missionItem
.
refPoint
property
var
refPoint
:
_missionItem
.
refPoint
onRefPointChanged
:
{
if
(
refPoint
!==
coordinate
)
{
coordinate
=
refPoint
}
}
onClicked
:
{
_root
.
clicked
(
_missionItem
.
sequenceNumber
)
}
onDragReleased
:
{
_missionItem
.
refPoint
=
coordinate
coordinate
=
Qt
.
binding
(
function
(){
return
_missionItem
.
refPoint
})
}
}
}
...
...
src/WimaView/WimaServiceAreaMapVisual.qml
View file @
47641f63
...
...
@@ -104,7 +104,7 @@ Item {
Component
.
onCompleted
:
{
_addInitialPolygon
()
if
(
interactive
){
if
(
showDepot
){
_addDepot
()
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment