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
da286265
Commit
da286265
authored
Jan 14, 2020
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
CircularSurvey::rebuildTransectsPhase1 split in slow and fast version
parent
46eb801f
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
320 additions
and
224 deletions
+320
-224
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+3
-5
CircularSurvey.SettingsGroup.json
src/Wima/CircularSurvey.SettingsGroup.json
+2
-1
CircularSurveyComplexItem.cc
src/Wima/CircularSurveyComplexItem.cc
+308
-113
CircularSurveyComplexItem.h
src/Wima/CircularSurveyComplexItem.h
+3
-3
OptimisationTools_delLater.cc
src/Wima/OptimisationTools_delLater.cc
+0
-90
CircularSurveyMapVisual.qml
src/WimaView/CircularSurveyMapVisual.qml
+3
-11
WimaMapPolygonVisuals.qml
src/WimaView/WimaMapPolygonVisuals.qml
+1
-1
No files found.
src/MissionManager/TransectStyleComplexItem.cc
View file @
da286265
...
...
@@ -357,12 +357,10 @@ void TransectStyleComplexItem::_rebuildTransects(void)
return
;
}
//CALLGRIND_TOGGLE_COLLECT;
//auto startTime = std::chrono::high_resolution_clock::now();
auto
startTime
=
std
::
chrono
::
high_resolution_clock
::
now
();
_rebuildTransectsPhase1
();
//auto delta = std::chrono::duration_cast<std::chrono::microseconds>(std::chrono::high_resolution_clock::now() - startTime).count();
//qWarning() << "TransectStyleComplexItem::_rebuildTransects(): time: " << delta << " us";
//CALLGRIND_TOGGLE_COLLECT;
auto
delta
=
std
::
chrono
::
duration_cast
<
std
::
chrono
::
microseconds
>
(
std
::
chrono
::
high_resolution_clock
::
now
()
-
startTime
).
count
();
qWarning
()
<<
"TransectStyleComplexItem::_rebuildTransects(): time: "
<<
delta
<<
" us"
;
if
(
_followTerrain
)
{
// Query the terrain data. Once available terrain heights will be calculated
...
...
src/Wima/CircularSurvey.SettingsGroup.json
View file @
da286265
...
...
@@ -44,6 +44,7 @@
"shortDescription"
:
"The maximum number of waypoints the circular survey can containt. To many waypoints cause a performance hit."
,
"type"
:
"uint32"
,
"defaultValue"
:
2000
,
"min"
:
1
"min"
:
1
,
"max"
:
20000
}
]
src/Wima/CircularSurveyComplexItem.cc
View file @
da286265
...
...
@@ -37,6 +37,7 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV
,
_reverseOnly
(
false
)
,
_referencePointBeingChanged
(
false
)
,
_updateCounter
(
0
)
,
_transectsDiry
(
true
)
{
Q_UNUSED
(
kmlOrShpFile
)
_editorQml
=
"qrc:/qml/CircularSurveyItemEditor.qml"
;
...
...
@@ -56,11 +57,6 @@ void CircularSurveyComplexItem::resetReference()
setRefPoint
(
_surveyAreaPolygon
.
center
());
}
void
CircularSurveyComplexItem
::
setReferencePointBeingChanged
(
bool
changeing
)
{
_referencePointBeingChanged
=
changeing
;
}
void
CircularSurveyComplexItem
::
setRefPoint
(
const
QGeoCoordinate
&
refPt
)
{
if
(
refPt
!=
_referencePoint
){
...
...
@@ -206,6 +202,8 @@ void CircularSurveyComplexItem::save(QJsonArray &planItems)
void
CircularSurveyComplexItem
::
appendMissionItems
(
QList
<
MissionItem
*>
&
items
,
QObject
*
missionItemParent
)
{
if
(
_transectsDiry
)
return
;
if
(
_loadedMissionItems
.
count
())
{
// We have mission items from the loaded plan, use those
_appendLoadedMissionItems
(
items
,
missionItemParent
);
...
...
@@ -218,7 +216,8 @@ void CircularSurveyComplexItem::appendMissionItems(QList<MissionItem *> &items,
void
CircularSurveyComplexItem
::
_appendLoadedMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
//qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";
if
(
_transectsDiry
)
return
;
int
seqNum
=
_sequenceNumber
;
for
(
const
MissionItem
*
loadedMissionItem
:
_loadedMissionItems
)
{
...
...
@@ -235,11 +234,11 @@ void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>&
// Now build the mission items from the transect points
if
(
_transectsDiry
)
return
;
MissionItem
*
item
;
int
seqNum
=
_sequenceNumber
;
// bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
// bool addTriggerAtBeginning = !hoverAndCaptureEnabled() && imagesEverywhere;
//bool firstOverallPoint = true;
MAV_FRAME
mavFrame
=
followTerrain
()
||
!
_cameraCalc
.
distanceToSurfaceRelative
()
?
MAV_FRAME_GLOBAL
:
MAV_FRAME_GLOBAL_RELATIVE_ALT
;
...
...
@@ -261,89 +260,8 @@ void CircularSurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>&
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
// implement capture if desired
// if (hoverAndCaptureEnabled()) {
// item = new MissionItem(seqNum++,
// MAV_CMD_IMAGE_START_CAPTURE,
// MAV_FRAME_MISSION,
// 0, // Reserved (Set to 0)
// 0, // Interval (none)
// 1, // Take 1 photo
// qQNaN(), qQNaN(), qQNaN(), qQNaN(), // param 4-7 reserved
// true, // autoContinue
// false, // isCurrentItem
// missionItemParent);
// items.append(item);
// }
// if (firstOverallPoint && addTriggerAtBeginning) {
// // Start triggering
// addTriggerAtBeginning = false;
// item = new MissionItem(seqNum++,
// MAV_CMD_DO_SET_CAM_TRIGG_DIST,
// MAV_FRAME_MISSION,
// triggerDistance(), // trigger distance
// 0, // shutter integration (ignore)
// 1, // trigger immediately when starting
// 0, 0, 0, 0, // param 4-7 unused
// true, // autoContinue
// false, // isCurrentItem
// missionItemParent);
// items.append(item);
// }
//firstOverallPoint = false;
// // Possibly add trigger start/stop to survey area entrance/exit
// if (triggerCamera() && !hoverAndCaptureEnabled() && transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge) {
// if (transectEntry) {
// // Start of transect, always start triggering. We do this even if we are taking images everywhere.
// // This allows a restart of the mission in mid-air without losing images from the entire mission.
// // At most you may lose part of a transect.
// item = new MissionItem(seqNum++,
// MAV_CMD_DO_SET_CAM_TRIGG_DIST,
// MAV_FRAME_MISSION,
// triggerDistance(), // trigger distance
// 0, // shutter integration (ignore)
// 1, // trigger immediately when starting
// 0, 0, 0, 0, // param 4-7 unused
// true, // autoContinue
// false, // isCurrentItem
// missionItemParent);
// items.append(item);
// transectEntry = false;
// } else if (!imagesEverywhere && !transectEntry){
// // End of transect, stop triggering
// item = new MissionItem(seqNum++,
// MAV_CMD_DO_SET_CAM_TRIGG_DIST,
// MAV_FRAME_MISSION,
// 0, // stop triggering
// 0, // shutter integration (ignore)
// 0, // trigger immediately when starting
// 0, 0, 0, 0, // param 4-7 unused
// true, // autoContinue
// false, // isCurrentItem
// missionItemParent);
// items.append(item);
// }
// }
}
}
// implemetn photo capture if desired
// if (triggerCamera() && !hoverAndCaptureEnabled() && imagesEverywhere) {
// // Stop triggering
// MissionItem* item = new MissionItem(seqNum++,
// MAV_CMD_DO_SET_CAM_TRIGG_DIST,
// MAV_FRAME_MISSION,
// 0, // stop triggering
// 0, // shutter integration (ignore)
// 0, // trigger immediately when starting
// 0, 0, 0, 0, // param 4-7 unused
// true, // autoContinue
// false, // isCurrentItem
// missionItemParent);
// items.append(item);
// }
}
void
CircularSurveyComplexItem
::
applyNewAltitude
(
double
newAltitude
)
...
...
@@ -374,6 +292,253 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
using
namespace
PolygonCalculus
;
using
namespace
PlanimetryCalculus
;
_transectsDiry
=
true
;
// rebuild not necessary?
if
(
!
_isInitialized
||
_referencePointBeingChanged
)
return
;
_updateCounter
++
;
unsigned
int
waypointCounter
=
0
;
// If the transects are getting rebuilt then any previously loaded mission items are now invalid
if
(
_loadedMissionItemsParent
)
{
_loadedMissionItems
.
clear
();
_loadedMissionItemsParent
->
deleteLater
();
_loadedMissionItemsParent
=
nullptr
;
}
// check if input is valid
if
(
_surveyAreaPolygon
.
count
()
<
3
)
{
_transects
.
clear
();
return
;
}
// reverse transects and return
if
(
_reverseOnly
)
{
_reverseOnly
=
false
;
if
(
_transects
.
size
()
>
1
)
{
QList
<
QList
<
CoordInfo_t
>>
transectsReverse
;
transectsReverse
.
reserve
(
_transects
.
size
());
for
(
auto
list
:
_transects
)
{
QList
<
CoordInfo_t
>
listReverse
;
for
(
auto
coordinate
:
list
)
listReverse
.
prepend
(
coordinate
);
transectsReverse
.
prepend
(
listReverse
);
}
_transects
=
transectsReverse
;
return
;
}
}
_transects
.
clear
();
QPolygonF
surveyPolygon
=
toQPolygonF
(
toCartesian2D
(
_surveyAreaPolygon
.
coordinateList
(),
_referencePoint
));
// some more checks
if
(
!
PolygonCalculus
::
isSimplePolygon
(
surveyPolygon
))
{
_transects
.
clear
();
return
;
}
// even more checks
if
(
!
PolygonCalculus
::
hasClockwiseWinding
(
surveyPolygon
))
PolygonCalculus
::
reversePath
(
surveyPolygon
);
QVector
<
double
>
distances
;
for
(
const
QPointF
&
p
:
surveyPolygon
)
distances
.
append
(
norm
(
p
));
// check if input is valid
if
(
_deltaAlpha
.
rawValue
()
>
_deltaAlpha
.
rawMax
()
&&
_deltaAlpha
.
rawValue
()
<
_deltaAlpha
.
rawMin
())
return
;
if
(
_deltaR
.
rawValue
()
>
_deltaR
.
rawMax
()
&&
_deltaR
.
rawValue
()
<
_deltaR
.
rawMin
())
return
;
// fetch input data
double
dalpha
=
_deltaAlpha
.
rawValue
().
toDouble
()
/
180.0
*
M_PI
;
// radiants
double
dr
=
_deltaR
.
rawValue
().
toDouble
();
// meter
double
lmin
=
_transectMinLength
.
rawValue
().
toDouble
();
double
r_min
=
dr
;
// meter
double
r_max
=
(
*
std
::
max_element
(
distances
.
begin
(),
distances
.
end
()));
// meter
unsigned
int
maxWaypoints
=
_maxWaypoints
.
rawValue
().
toUInt
();
QPointF
origin
(
0
,
0
);
IntersectType
type
;
bool
originInside
=
true
;
if
(
!
contains
(
surveyPolygon
,
origin
,
type
))
{
QVector
<
double
>
angles
;
for
(
const
QPointF
&
p
:
surveyPolygon
)
angles
.
append
(
truncateAngle
(
angle
(
p
)));
// determine r_min by successive approximation
double
r
=
r_min
;
while
(
r
<
r_max
)
{
Circle
circle
(
r
,
origin
);
if
(
intersects
(
circle
,
surveyPolygon
))
{
r_min
=
r
;
break
;
}
r
+=
dr
;
}
originInside
=
false
;
}
// generate transects
QVector
<
QVector
<
QPointF
>>
transectPath
;
double
r
=
r_min
;
while
(
r
<
r_max
)
{
Circle
circle
(
r
,
origin
);
QVector
<
QPointFVector
>
intersectPoints
;
QVector
<
IntersectType
>
typeList
;
QVector
<
QPair
<
int
,
int
>>
neighbourList
;
if
(
intersects
(
circle
,
surveyPolygon
,
intersectPoints
,
neighbourList
,
typeList
))
{
// intersection Points between circle and polygon, entering polygon
// when walking in counterclockwise direction along circle
QPointFList
entryPoints
;
// intersection Points between circle and polygon, leaving polygon
// when walking in counterclockwise direction along circle
QPointFList
exitPoints
;
// determine entryPoints and exit Points
for
(
int
j
=
0
;
j
<
intersectPoints
.
size
();
j
++
)
{
QVector
<
QPointF
>
intersects
=
intersectPoints
[
j
];
// one pt = tangent, two pt = sekant
QPointF
p1
=
surveyPolygon
[
neighbourList
[
j
].
first
];
QPointF
p2
=
surveyPolygon
[
neighbourList
[
j
].
second
];
QLineF
intersetLine
(
p1
,
p2
);
double
lineAngle
=
angle
(
intersetLine
);
// int n = 16;
// for (int i = -n; i <= n; i++) {
// double alpha = 2*M_PI*double(i)/double(n);
// qDebug() << i << " " << alpha << " " << truncateAngle(alpha);
// }
for
(
QPointF
ipt
:
intersects
)
{
double
circleTangentAngle
=
angle
(
ipt
)
+
M_PI_2
;
// compare line angle and circle tangent at intersection point
// to determine between exit and entry point
// qDebug() << "lineAngle" << lineAngle*180/M_PI;
// qDebug() << "circleTangentAngle" << circleTangentAngle*180/M_PI;
// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle));
// qDebug() << "!qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI): " << !qFuzzyIsNull(truncateAngle(lineAngle - circleTangentAngle - M_PI));
if
(
!
qFuzzyIsNull
(
truncateAngle
(
lineAngle
-
circleTangentAngle
))
&&
!
qFuzzyIsNull
(
truncateAngle
(
lineAngle
-
circleTangentAngle
-
M_PI
)
))
{
if
(
truncateAngle
(
circleTangentAngle
-
lineAngle
)
>
M_PI
)
{
entryPoints
.
append
(
ipt
);
}
else
{
exitPoints
.
append
(
ipt
);
}
}
}
}
// sort
std
::
sort
(
entryPoints
.
begin
(),
entryPoints
.
end
(),
[](
QPointF
p1
,
QPointF
p2
)
{
return
angle
(
p1
)
<
angle
(
p2
);
});
std
::
sort
(
exitPoints
.
begin
(),
exitPoints
.
end
(),
[](
QPointF
p1
,
QPointF
p2
)
{
return
angle
(
p1
)
<
angle
(
p2
);
});
// match entry and exit points
int
offset
=
0
;
double
minAngle
=
std
::
numeric_limits
<
double
>::
infinity
();
for
(
int
k
=
0
;
k
<
exitPoints
.
size
();
k
++
)
{
QPointF
pt
=
exitPoints
[
k
];
double
alpha
=
truncateAngle
(
angle
(
pt
)
-
angle
(
entryPoints
[
0
]));
if
(
minAngle
>
alpha
)
{
minAngle
=
alpha
;
offset
=
k
;
}
}
// generate circle sectors
for
(
int
k
=
0
;
k
<
entryPoints
.
size
();
k
++
)
{
double
alpha1
=
angle
(
entryPoints
[
k
]);
double
alpha2
=
angle
(
exitPoints
[(
k
+
offset
)
%
entryPoints
.
size
()]);
double
dAlpha
=
truncateAngle
(
alpha2
-
alpha1
);
int
numNodes
=
int
(
ceil
(
dAlpha
/
dalpha
))
+
1
;
// qDebug() << "alpha1" << alpha1;
// qDebug() << "alpha2" << alpha2;
// qDebug() << "dAlpha" << dAlpha;
// qDebug() << "numNodes" << numNodes;
QVector
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
numNodes
,
alpha1
,
alpha2
);
// use shortestPath() here if necessary, could be a problem if dr >>
if
(
sectorPath
.
size
()
>
0
)
{
waypointCounter
+=
uint
(
sectorPath
.
size
());
if
(
waypointCounter
>
maxWaypoints
)
return
;
transectPath
.
append
(
sectorPath
);
}
}
}
else
if
(
originInside
)
{
// circle fully inside polygon
int
numNodes
=
int
(
ceil
(
2
*
M_PI
/
dalpha
))
+
1
;
QVector
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
numNodes
,
0
,
2
*
M_PI
);
// use shortestPath() here if necessary, could be a problem if dr >>
waypointCounter
+=
uint
(
sectorPath
.
size
());
if
(
waypointCounter
>
maxWaypoints
)
return
;
transectPath
.
append
(
sectorPath
);
}
r
+=
dr
;
}
if
(
transectPath
.
size
()
==
0
)
return
;
// remove short transects
for
(
int
i
=
0
;
i
<
transectPath
.
size
();
i
++
)
{
auto
transect
=
transectPath
[
i
];
double
len
=
0
;
for
(
int
j
=
0
;
j
<
transect
.
size
()
-
1
;
++
j
)
{
len
+=
PlanimetryCalculus
::
distance
(
transect
[
j
],
transect
[
j
+
1
]);
}
if
(
len
<
lmin
)
transectPath
.
removeAt
(
i
--
);
}
if
(
transectPath
.
size
()
==
0
)
return
;
// convert to CoordInfo_t
for
(
auto
path
:
transectPath
){
QVector
<
QGeoCoordinate
>
geoPath
=
toGeo
(
path
,
_referencePoint
);
QList
<
CoordInfo_t
>
transectList
;
transectList
.
reserve
(
geoPath
.
size
());
for
(
const
QGeoCoordinate
&
coordinate
:
geoPath
)
{
CoordInfo_t
coordinfo
=
{
coordinate
,
CoordTypeInterior
};
transectList
.
append
(
coordinfo
);
}
_transects
.
append
(
transectList
);
}
qDebug
()
<<
"CircularSurveyComplexItem::_rebuildTransectsPhase1(): calls: "
<<
_updateCounter
;
}
void
CircularSurveyComplexItem
::
_rebuildTransectsSlow
()
{
using
namespace
GeoUtilities
;
using
namespace
PolygonCalculus
;
using
namespace
PlanimetryCalculus
;
// rebuild not necessary?
if
(
!
_isInitialized
||
_referencePointBeingChanged
)
return
;
...
...
@@ -595,53 +760,63 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
return
;
// optimize path to snake or zig-zag pattern
bool
isSnakePattern
=
_isSnakePath
.
rawValue
().
toBool
();
QVector
<
QPointF
>
currentSection
=
transectPath
.
takeFirst
();
if
(
currentSection
.
isEmpty
()
)
return
;
QVector
<
QPointF
>
optiPath
;
// optimized path
const
bool
isSnakePathBool
=
_isSnakePath
.
rawValue
().
toBool
();
QVector
<
QPointF
>
currentSection
=
transectPath
.
takeFirst
();
if
(
currentSection
.
isEmpty
()
)
return
;
QVector
<
QPointF
>
optimizedPath
(
currentSection
);
bool
reversePath
=
true
;
// controlls if currentSection gets reversed, has nothing todo with _reverseOnly
while
(
!
transectPath
.
empty
()
)
{
optiPath
.
append
(
currentSection
);
QPointF
endVertex
=
currentSection
.
last
();
double
minDist
=
std
::
numeric_limits
<
double
>::
infinity
();
int
index
=
0
;
bool
reversePath
=
false
;
// iterate over all paths in fullPath and assign the one with the shortest distance to endVertex to currentSection
QVector
<
QPointF
>
connectorPath
;
for
(
int
i
=
0
;
i
<
transectPath
.
size
();
i
++
)
{
auto
iteratorPath
=
transectPath
[
i
];
double
dist
=
PlanimetryCalculus
::
distance
(
endVertex
,
iteratorPath
.
first
());
if
(
dist
<
minDist
)
{
minDist
=
dist
;
index
=
i
;
reversePath
=
false
;
QVector
<
QPointF
>
iteratorPath
=
transectPath
[
i
];
QVector
<
QPointF
>
tempConnectorPath
;
bool
retVal
;
if
(
reversePath
&&
isSnakePathBool
)
{
retVal
=
PolygonCalculus
::
shortestPath
(
surveyPolygon
,
endVertex
,
iteratorPath
.
last
(),
tempConnectorPath
);
}
else
{
retVal
=
PolygonCalculus
::
shortestPath
(
surveyPolygon
,
endVertex
,
iteratorPath
.
first
(),
tempConnectorPath
);
}
dist
=
PlanimetryCalculus
::
distance
(
endVertex
,
iteratorPath
.
last
());
if
(
!
retVal
)
qWarning
(
"CircularSurveyComplexItem::_rebuildTransectsPhase1: internal error; false shortestPath"
);
double
dist
=
0
;
for
(
int
i
=
0
;
i
<
tempConnectorPath
.
size
()
-
1
;
++
i
)
dist
+=
PlanimetryCalculus
::
distance
(
tempConnectorPath
[
i
],
tempConnectorPath
[
i
+
1
]);
if
(
dist
<
minDist
)
{
minDist
=
dist
;
index
=
i
;
reversePath
=
true
;
connectorPath
=
tempConnectorPath
;
}
}
currentSection
=
transectPath
.
takeAt
(
index
);
if
(
reversePath
&&
isSnakePat
tern
)
{
if
(
reversePath
&&
isSnakePat
hBool
)
{
PolygonCalculus
::
reversePath
(
currentSection
);
}
}
optiPath
.
append
(
currentSection
);
// append last section
reversePath
^=
true
;
// toggle
if
(
optiPath
.
size
()
>
_maxWaypoints
.
rawValue
().
toInt
())
optimizedPath
.
append
(
connectorPath
);
optimizedPath
.
append
(
currentSection
);
}
if
(
optimizedPath
.
size
()
>
_maxWaypoints
.
rawValue
().
toInt
())
return
;
// convert to CoordInfo_t
if
(
_reverse
.
rawValue
().
toBool
())
PolygonCalculus
::
reversePath
(
optiPath
);
PolygonCalculus
::
reversePath
(
opti
mized
Path
);
QVector
<
QGeoCoordinate
>
geoPath
=
toGeo
(
optiPath
,
_referencePoint
);
QVector
<
QGeoCoordinate
>
geoPath
=
toGeo
(
opti
mized
Path
,
_referencePoint
);
QList
<
CoordInfo_t
>
transectList
;
transectList
.
reserve
(
optiPath
.
size
());
transectList
.
reserve
(
opti
mized
Path
.
size
());
for
(
const
QGeoCoordinate
&
coordinate
:
geoPath
)
{
CoordInfo_t
coordinfo
=
{
coordinate
,
CoordTypeInterior
};
transectList
.
append
(
coordinfo
);
...
...
@@ -649,12 +824,16 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
_transects
.
append
(
transectList
);
qDebug
()
<<
"CircularSurveyComplexItem::_rebuildTransectsPhase1(): calls: "
<<
_updateCounter
;
_transectsDiry
=
false
;
}
void
CircularSurveyComplexItem
::
_recalcComplexDistance
()
{
_complexDistance
=
0
;
if
(
_transectsDiry
)
return
;
for
(
int
i
=
0
;
i
<
_visualTransectPoints
.
count
()
-
1
;
i
++
)
{
_complexDistance
+=
_visualTransectPoints
[
i
].
value
<
QGeoCoordinate
>
().
distanceTo
(
_visualTransectPoints
[
i
+
1
].
value
<
QGeoCoordinate
>
());
}
...
...
@@ -673,6 +852,22 @@ void CircularSurveyComplexItem::_reverseTransects()
_rebuildTransects
();
}
bool
CircularSurveyComplexItem
::
_shortestPath
(
const
QGeoCoordinate
&
start
,
const
QGeoCoordinate
&
destination
,
QVector
<
QGeoCoordinate
>
shortestPath
)
{
using
namespace
GeoUtilities
;
using
namespace
PolygonCalculus
;
QVector
<
QPointF
>
path2D
;
bool
retVal
=
PolygonCalculus
::
shortestPath
(
toQPolygonF
(
toCartesian2D
(
this
->
surveyAreaPolygon
()
->
coordinateList
(),
/*origin*/
start
)),
/*start point*/
QPointF
(
0
,
0
),
/*destination*/
toCartesian2D
(
destination
,
start
),
/*shortest path*/
path2D
);
if
(
retVal
)
shortestPath
.
append
(
toGeo
(
path2D
,
/*origin*/
start
));
return
retVal
;
}
Fact
*
CircularSurveyComplexItem
::
transectMinLength
()
...
...
src/Wima/CircularSurveyComplexItem.h
View file @
da286265
...
...
@@ -28,7 +28,6 @@ public:
Q_PROPERTY
(
bool
isInitialized
READ
isInitialized
WRITE
setIsInitialized
NOTIFY
isInitializedChanged
)
Q_INVOKABLE
void
resetReference
(
void
);
Q_INVOKABLE
void
setReferencePointBeingChanged
(
bool
changeing
);
// used by gui to indicate a changeing reference point (dagging by user)
// Property setters
void
setRefPoint
(
const
QGeoCoordinate
&
refPt
);
...
...
@@ -90,9 +89,11 @@ signals:
private
slots
:
// Overrides from TransectStyleComplexItem
void
_rebuildTransectsPhase1
(
void
)
final
;
// do not call this function, it is called by TransectStyleComplexItem::_rebuildTransects()
void
_rebuildTransectsSlow
(
void
);
// the slow version of _rebuildTransectsPhase1 which properly connects the _transects
void
_recalcComplexDistance
(
void
)
final
;
void
_recalcCameraShots
(
void
)
final
;
void
_reverseTransects
(
void
);
bool
_shortestPath
(
const
QGeoCoordinate
&
start
,
const
QGeoCoordinate
&
destination
,
QVector
<
QGeoCoordinate
>
shortestPath
);
signals:
...
...
@@ -121,8 +122,7 @@ private:
bool
_referencePointBeingChanged
;
// is set to true by gui, if user is changeing the reference point
int
_updateCounter
;
int
_transectsDiry
;
};
...
...
src/Wima/OptimisationTools_delLater.cc
deleted
100644 → 0
View file @
46eb801f
#include "OptimisationTools.h"
#include <QPointF>
namespace
OptimisationTools
{
namespace
{
}
bool
dijkstraAlgorithm
(
const
int
numNodes
,
const
int
startIndex
,
const
int
endIndex
,
QVector
<
int
>
&
elementPath
,
std
::
function
<
double
(
const
int
,
const
int
)
>
distance
)
{
if
(
numNodes
<
0
||
startIndex
<
0
||
endIndex
<
0
||
endIndex
>=
numNodes
||
startIndex
>=
numNodes
||
endIndex
==
startIndex
)
{
return
false
;
}
// distanceToStart[i] contains the distance of element[i] to element[startIndex] (after successful algorithm termination)
QVector
<
double
>
distanceToStart
(
numNodes
,
std
::
numeric_limits
<
qreal
>::
infinity
());
// elementPredecessor[i] contains the predecessor of element[i]
QVector
<
int
>
elementPredecessor
(
numNodes
,
-
1
);
// Elements will be successively removed from this list during the execution of the Dijkstra Algorithm.
QVector
<
int
>
workingSet
;
workingSet
.
reserve
(
numNodes
);
//fill workingSet with 0, 1, ..., numNodes-1
for
(
int
i
=
0
;
i
<
numNodes
;
i
++
)
workingSet
.
append
(
i
);
distanceToStart
[
startIndex
]
=
0
;
// Dijkstra Algorithm
// https://de.wikipedia.org/wiki/Dijkstra-Algorithmus
while
(
workingSet
.
size
()
>
0
)
{
// serach Node with minimal distance
double
minDist
=
std
::
numeric_limits
<
qreal
>::
infinity
();
int
minIndex
=
-
1
;
// index of element with least distance to element[startIndex]
for
(
int
i
=
0
;
i
<
workingSet
.
size
();
i
++
)
{
int
e
=
workingSet
[
i
];
double
dist
=
distanceToStart
[
e
];
if
(
dist
<
minDist
)
{
minDist
=
dist
;
minIndex
=
i
;
}
}
if
(
minIndex
==
-
1
)
return
false
;
int
u
=
workingSet
.
takeAt
(
minIndex
);
if
(
u
==
endIndex
)
// shortest path found
break
;
//update distance
double
distanceU
=
distanceToStart
[
u
];
for
(
int
i
=
0
;
i
<
workingSet
.
size
();
i
++
)
{
int
v
=
workingSet
[
i
];
double
dist
=
distance
(
u
,
v
);
// is ther a alternative path which is shorter?
double
alternative
=
distanceU
+
dist
;
if
(
alternative
<
distanceToStart
[
v
])
{
distanceToStart
[
v
]
=
alternative
;
elementPredecessor
[
v
]
=
u
;
}
}
}
// end Djikstra Algorithm
// reverse assemble elementPath
int
e
=
endIndex
;
while
(
1
)
{
if
(
e
==
-
1
)
{
if
(
elementPath
[
0
]
==
startIndex
)
// check if starting point was reached
break
;
return
false
;
}
elementPath
.
prepend
(
e
);
//Update Node
e
=
elementPredecessor
[
e
];
}
return
true
;
}
// end anonymous namespace
}
// end OptimisationTools namespace
src/WimaView/CircularSurveyMapVisual.qml
View file @
da286265
...
...
@@ -103,7 +103,7 @@ Item {
_destroyVisualElements
()
}
QGC
MapPolygonVisuals
{
Wima
MapPolygonVisuals
{
id
:
mapPolygonVisuals
qgcView
:
_root
.
qgcView
mapControl
:
map
...
...
@@ -179,7 +179,6 @@ Item {
property
var
refPoint
:
_missionItem
.
refPoint
onCoordinateChanged
:
_missionItem
.
refPoint
=
coordinate
onRefPointChanged
:
{
if
(
refPoint
!==
coordinate
)
{
coordinate
=
refPoint
...
...
@@ -188,17 +187,10 @@ Item {
onClicked
:
{
_root
.
clicked
(
_missionItem
.
sequenceNumber
)
_missionItem
.
setReferencePointBeingChanged
(
true
)
}
onDragClicked
:
{
// replace with entered
_missionItem
.
setReferencePointBeingChanged
(
true
)
console
.
log
(
'
onDragClicked
'
)
}
onDragReleased
:
{
// replace with exited
_missionItem
.
setReferencePointBeingChanged
(
false
)
console
.
log
(
'
onDragReleased
'
)
onDragReleased
:
{
_missionItem
.
refPoint
=
coordinate
}
}
}
...
...
src/WimaView/WimaMapPolygonVisuals.qml
View file @
da286265
...
...
@@ -20,7 +20,7 @@ import QGroundControl.Controls 1.0
import
QGroundControl
.
FlightMap
1.0
import
QGroundControl
.
ShapeFileHelper
1.0
///
QGC
MapPolygon map visuals
///
Wima
MapPolygon map visuals
Item
{
id
:
_root
...
...
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