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
4666c881
Commit
4666c881
authored
Sep 02, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
123
parent
6fb21c6f
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
58 additions
and
49 deletions
+58
-49
ToDo.txt
ToDo.txt
+2
-1
CircularSurveyItemEditor.qml
src/PlanView/CircularSurveyItemEditor.qml
+1
-1
CircularSurveyComplexItem.cc
src/Wima/CircularSurveyComplexItem.cc
+38
-34
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+3
-0
CoordinateIndicator.qml
src/WimaView/CoordinateIndicator.qml
+2
-2
DragCoordinate.qml
src/WimaView/DragCoordinate.qml
+9
-9
SphericalSurveyMapVisual.qml
src/WimaView/SphericalSurveyMapVisual.qml
+3
-2
No files found.
ToDo.txt
View file @
4666c881
optimize
circular survey
(improve) optimisation
circular survey
profile survey
add dijkstra to flight view
add save and load to circular survey
src/PlanView/CircularSurveyItemEditor.qml
View file @
4666c881
...
...
@@ -110,7 +110,7 @@ Rectangle {
Layout.columnSpan
:
2
Layout.preferredHeight
:
ScreenTools
.
defaultFontPixelHeight
*
1.5
onValueChanged
:
missionItem
.
deltaAlpha
.
value
=
value
Component.onCompleted
:
value
=
missionItem
.
deltaAlpha
.
defaultV
alue
Component.onCompleted
:
value
=
missionItem
.
deltaAlpha
.
v
alue
updateValueWhileDragging
:
true
}
}
...
...
src/Wima/CircularSurveyComplexItem.cc
View file @
4666c881
...
...
@@ -247,43 +247,47 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
}
}
// // optimize path to lawn pattern
// if (fullPath.size() == 0)
// return;
// QList<QPointF> currentSection = fullPath.takeFirst();
// QList<QList<QPointF>> optiPath; // optimized path
// while( !fullPath.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
// for (int i = 0; i < fullPath.size(); i++) {
// auto iteratorPath = fullPath[i];
// double dist = PlanimetryCalculus::distance(endVertex, iteratorPath.first());
// if ( dist < minDist ) {
// minDist = dist;
// index = i;
// }
// dist = PlanimetryCalculus::distance(endVertex, iteratorPath.last());
// if (dist < minDist) {
// minDist = dist;
// index = i;
// reversePath = true;
// }
// }
// currentSection = fullPath.takeAt(index);
// if (reversePath) {
// PolygonCalculus::reversePath(currentSection);
// }
// }
// optimize path to lawn pattern
if
(
fullPath
.
size
()
==
0
)
return
;
QList
<
QPointF
>
currentSection
=
fullPath
.
takeFirst
();
if
(
currentSection
.
isEmpty
()
)
return
;
QList
<
QList
<
QPointF
>>
optiPath
;
// optimized path
while
(
!
fullPath
.
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
for
(
int
i
=
0
;
i
<
fullPath
.
size
();
i
++
)
{
auto
iteratorPath
=
fullPath
[
i
];
double
dist
=
PlanimetryCalculus
::
distance
(
endVertex
,
iteratorPath
.
first
());
if
(
dist
<
minDist
)
{
minDist
=
dist
;
index
=
i
;
}
dist
=
PlanimetryCalculus
::
distance
(
endVertex
,
iteratorPath
.
last
());
if
(
dist
<
minDist
)
{
minDist
=
dist
;
index
=
i
;
reversePath
=
true
;
}
}
currentSection
=
fullPath
.
takeAt
(
index
);
if
(
reversePath
)
{
PolygonCalculus
::
reversePath
(
currentSection
);
}
}
optiPath
.
append
(
currentSection
);
// append last section
// convert to CoordInfo_t
//
for ( const QList<QPointF> &transect : optiPath) {
for
(
const
QList
<
QPointF
>
&
transect
:
fullPath
)
{
for
(
const
QList
<
QPointF
>
&
transect
:
optiPath
)
{
//
for ( const QList<QPointF> &transect : fullPath) {
QList
<
QGeoCoordinate
>
geoPath
=
toGeo
(
transect
,
_referencePoint
);
QList
<
CoordInfo_t
>
transectList
;
for
(
const
QGeoCoordinate
&
coordinate
:
geoPath
)
{
...
...
src/Wima/WimaPlaner.cc
View file @
4666c881
...
...
@@ -299,8 +299,11 @@ bool WimaPlaner::updateMission()
}
QGeoCoordinate
start
=
_serviceArea
.
center
();
QGeoCoordinate
end
=
survey
->
coordinate
();
#ifdef QT_DEBUG
if
(
!
_visualItems
.
contains
(
&
_joinedArea
))
_visualItems
.
append
(
&
_joinedArea
);
#endif
QList
<
QGeoCoordinate
>
path
;
if
(
!
calcShortestPath
(
start
,
end
,
path
))
{
...
...
src/WimaView/CoordinateIndicator.qml
View file @
4666c881
...
...
@@ -11,7 +11,7 @@ MapQuickItem {
property
int
sequenceNumber
property
string
label
//property bool visible
property
bool
checked
signal
clicked
...
...
@@ -21,7 +21,7 @@ MapQuickItem {
sourceItem
:
MissionItemIndexLabel
{
id
:
_label
checked
:
_item
.
visible
checked
:
_item
.
checked
label
:
_item
.
label
index
:
_item
.
sequenceNumber
gimbalYaw
:
0
...
...
src/WimaView/DragCoordinate.qml
View file @
4666c881
...
...
@@ -22,11 +22,11 @@ import QGroundControl.FlightMap 1.0
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
//property var visibl
e
property
var
coordinate
property
int
sequenceNumber
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
property
var
coordinat
e
property
int
sequenceNumber
property
bool
checked
property
var
_itemVisual
property
bool
_itemVisualShowing
:
false
...
...
@@ -66,7 +66,7 @@ Item {
Component.onCompleted
:
{
showItemVisuals
()
if
(
visible
&&
map
.
planView
)
{
if
(
checked
&&
map
.
planView
)
{
showDragArea
()
}
}
...
...
@@ -76,8 +76,8 @@ Item {
hideItemVisuals
()
}
on
Visible
Changed
:
{
if
(
visible
)
{
on
Checked
Changed
:
{
if
(
checked
)
{
showDragArea
()
}
else
{
hideDragArea
()
...
...
@@ -102,7 +102,7 @@ Item {
CoordinateIndicator
{
label
:
"
Reference
"
visible
:
_root
.
visible
checked
:
_root
.
checked
z
:
QGroundControl
.
zOrderMapItems
sequenceNumber
:
_root
.
sequenceNumber
coordinate
:
_root
.
coordinate
...
...
src/WimaView/SphericalSurveyMapVisual.qml
View file @
4666c881
...
...
@@ -173,10 +173,11 @@ Item {
map
:
_root
.
map
qgcView
:
_root
.
qgcView
z
:
QGroundControl
.
zOrderMapItems
visible
:
_missionItem
.
isCurrentItem
checked
:
_missionItem
.
isCurrentItem
coordinate
:
_missionItem
.
refPoint
onCoordinateChanged
:
_missionItem
.
refPoint
=
coordinate
onCoordinateChanged
:
_missionItem
.
refPoint
=
coordinate
onClicked
:
_root
.
clicked
(
_missionItem
.
sequenceNumber
)
}
}
}
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