Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
470c9ab4
Commit
470c9ab4
authored
Aug 20, 2019
by
Valentin Platzgummer
Browse files
bug inside circ survey
parent
5005f97c
Changes
10
Hide whitespace changes
Inline
Side-by-side
qgroundcontrol.qrc
View file @
470c9ab4
...
...
@@ -221,6 +221,7 @@
<file alias="QGroundControl/Controls/WimaCorridorMapVisual.qml">src/WimaView/WimaCorridorMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaMeasurementAreaEditor.qml">src/WimaView/WimaMeasurementAreaEditor.qml</file>
<file alias="QGroundControl/Controls/SpericalSurveyMapVisual.qml">src/WimaView/SphericalSurveyMapVisual.qml</file>
<file alias="CircularSurveyItemEditor.qml">src/PlanView/CircularSurveyItemEditor.qml</file>
</qresource>
<qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
...
...
@@ -266,6 +267,7 @@
<file alias="Vehicle/WindFact.json">src/Vehicle/WindFact.json</file>
<file alias="Video.SettingsGroup.json">src/Settings/Video.SettingsGroup.json</file>
<file alias="WimaMeasurementArea.SettingsGroup.json">src/Wima/WimaMeasurementArea.SettingsGroup.json</file>
<file alias="CircularSurvey.SettingsGroup.json">src/Wima/CircularSurvey.SettingsGroup.json</file>
</qresource>
<qresource prefix="/MockLink">
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
...
...
src/PlanView/CircularSurveyItemEditor.qml
0 → 100644
View file @
470c9ab4
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtQuick
.
Controls
.
Styles
1.4
import
QtQuick
.
Dialogs
1.2
import
QtQuick
.
Extras
1.4
import
QtQuick
.
Layouts
1.2
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Vehicle
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FactSystem
1.0
import
QGroundControl
.
FactControls
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
FlightMap
1.0
Rectangle
{
id
:
_root
height
:
visible
?
(
editorColumn
.
height
+
(
_margin
*
2
))
:
0
width
:
availableWidth
color
:
qgcPal
.
windowShadeDark
radius
:
_radius
// The following properties must be available up the hierarchy chain
//property real availableWidth ///< Width for control
//property var missionItem ///< Mission Item for editor
property
real
_margin
:
ScreenTools
.
defaultFontPixelWidth
/
2
property
real
_fieldWidth
:
ScreenTools
.
defaultFontPixelWidth
*
10.5
property
var
_vehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
?
QGroundControl
.
multiVehicleManager
.
activeVehicle
:
QGroundControl
.
multiVehicleManager
.
offlineEditingVehicle
property
real
_cameraMinTriggerInterval
:
missionItem
.
cameraCalc
.
minTriggerInterval
.
rawValue
function
polygonCaptureStarted
()
{
missionItem
.
clearPolygon
()
}
function
polygonCaptureFinished
(
coordinates
)
{
for
(
var
i
=
0
;
i
<
coordinates
.
length
;
i
++
)
{
missionItem
.
addPolygonCoordinate
(
coordinates
[
i
])
}
}
function
polygonAdjustVertex
(
vertexIndex
,
vertexCoordinate
)
{
missionItem
.
adjustPolygonCoordinate
(
vertexIndex
,
vertexCoordinate
)
}
function
polygonAdjustStarted
()
{
}
function
polygonAdjustFinished
()
{
}
QGCPalette
{
id
:
qgcPal
;
colorGroupEnabled
:
true
}
Column
{
id
:
editorColumn
anchors.margins
:
_margin
anchors.top
:
parent
.
top
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
SectionHeader
{
id
:
transectsHeader
text
:
qsTr
(
"
Transects
"
)
}
GridLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
columnSpacing
:
_margin
rowSpacing
:
_margin
columns
:
2
visible
:
transectsHeader
.
checked
QGCLabel
{
text
:
qsTr
(
"
Delta R
"
)
}
FactTextField
{
fact
:
missionItem
.
deltaR
Layout.fillWidth
:
true
//onUpdated: rSlider.value = missionItem.deltaR.value
}
/*QGCSlider {
id: rSlider
minimumValue: 0.1
maximumValue: 20
stepSize: 0.1
tickmarksEnabled: false
Layout.fillWidth: true
Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.deltaR.value = value
Component.onCompleted: value = missionItem.deltaR.value
updateValueWhileDragging: true
}*/
QGCLabel
{
text
:
qsTr
(
"
Delta Alpha
"
)
}
FactTextField
{
fact
:
missionItem
.
deltaAlpha
Layout.fillWidth
:
true
onUpdated
:
angleSlider
.
value
=
missionItem
.
deltaAlpha
.
value
}
QGCSlider
{
id
:
angleSlider
minimumValue
:
0.1
maximumValue
:
20
stepSize
:
0.1
tickmarksEnabled
:
false
Layout.fillWidth
:
true
Layout.columnSpan
:
2
Layout.preferredHeight
:
ScreenTools
.
defaultFontPixelHeight
*
1.5
onValueChanged
:
missionItem
.
deltaAlpha
.
value
=
value
Component.onCompleted
:
value
=
missionItem
.
deltaAlpha
.
value
updateValueWhileDragging
:
true
}
}
ColumnLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
transectsHeader
.
checked
QGCButton
{
text
:
qsTr
(
"
Rotate Entry Point
"
)
onClicked
:
missionItem
.
rotateEntryPoint
();
}
/*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
FactCheckBox {
text: qsTr("Split concave polygons")
fact: _splitConcave
visible: _splitConcave.visible
property Fact _splitConcave: missionItem.splitConcavePolygons
}
*/
QGCCheckBox
{
id
:
relAlt
Layout.alignment
:
Qt
.
AlignLeft
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
Connections
{
target
:
missionItem
.
cameraCalc
onDistanceToSurfaceRelativeChanged
:
relAlt
.
checked
=
missionItem
.
cameraCalc
.
distanceToSurfaceRelative
}
}
}
SectionHeader
{
id
:
terrainHeader
text
:
qsTr
(
"
Terrain
"
)
checked
:
missionItem
.
followTerrain
}
ColumnLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
terrainHeader
.
checked
QGCCheckBox
{
id
:
followsTerrainCheckBox
text
:
qsTr
(
"
Vehicle follows terrain
"
)
checked
:
missionItem
.
followTerrain
onClicked
:
missionItem
.
followTerrain
=
checked
}
GridLayout
{
Layout.fillWidth
:
true
columnSpacing
:
_margin
rowSpacing
:
_margin
columns
:
2
visible
:
followsTerrainCheckBox
.
checked
QGCLabel
{
text
:
qsTr
(
"
Tolerance
"
)
}
FactTextField
{
fact
:
missionItem
.
terrainAdjustTolerance
Layout.fillWidth
:
true
}
QGCLabel
{
text
:
qsTr
(
"
Max Climb Rate
"
)
}
FactTextField
{
fact
:
missionItem
.
terrainAdjustMaxClimbRate
Layout.fillWidth
:
true
}
QGCLabel
{
text
:
qsTr
(
"
Max Descent Rate
"
)
}
FactTextField
{
fact
:
missionItem
.
terrainAdjustMaxDescentRate
Layout.fillWidth
:
true
}
}
}
SectionHeader
{
id
:
statsHeader
text
:
qsTr
(
"
Statistics
"
)
}
//TransectStyleComplexItemStats { }
}
// Column
}
// Rectangle
src/Wima/Circle.cc
View file @
470c9ab4
...
...
@@ -127,8 +127,7 @@ QList<QPointF> Circle::approximateSektor(double angleDiscretisation, double alph
}
// check if input is valid
if
(
fabs
(
angleDiscretisation
)
>
fabs
(
deltaAlpha
)
||
qFuzzyIsNull
(
angleDiscretisation
))
if
(
qFuzzyIsNull
(
angleDiscretisation
))
return
QList
<
QPointF
>
();
...
...
src/Wima/CircularSurvey.SettingsGroup.json
0 → 100644
View file @
470c9ab4
[
{
"name"
:
"DeltaR"
,
"shortDescription"
:
"The distance between two consecutive circles."
,
"type"
:
"double"
,
"units"
:
"m"
,
"min"
:
0.3
,
"decimalPlaces"
:
1
,
"defaultValue"
:
3
},
{
"name"
:
"DeltaAlpha"
,
"shortDescription"
:
"Angle discretisation of the circles."
,
"type"
:
"double"
,
"units"
:
"Deg"
,
"min"
:
0.3
,
"decimalPlaces"
:
1
,
"defaultValue"
:
0.5
}
]
src/Wima/CircularSurveyComplexItem.cc
View file @
470c9ab4
...
...
@@ -2,13 +2,24 @@
const
char
*
CircularSurveyComplexItem
::
settingsGroup
=
"Survey"
;
const
char
*
CircularSurveyComplexItem
::
deltaRName
=
"DeltaR"
;
const
char
*
CircularSurveyComplexItem
::
deltaAlphaName
=
"DeltaAlpha"
;
CircularSurveyComplexItem
::
CircularSurveyComplexItem
(
Vehicle
*
vehicle
,
bool
flyView
,
const
QString
&
kmlOrShpFile
,
QObject
*
parent
)
:
TransectStyleComplexItem
(
vehicle
,
flyView
,
settingsGroup
,
parent
)
,
_referencePoint
(
QGeoCoordinate
(
47.770859
,
16.531076
,
0
))
:
TransectStyleComplexItem
(
vehicle
,
flyView
,
settingsGroup
,
parent
)
,
_referencePoint
(
QGeoCoordinate
(
47.770859
,
16.531076
,
0
))
,
_metaDataMap
(
FactMetaData
::
createMapFromJsonFile
(
QStringLiteral
(
":/json/CircularSurvey.SettingsGroup.json"
),
this
))
,
_deltaR
(
settingsGroup
,
_metaDataMap
[
deltaRName
])
,
_deltaAlpha
(
settingsGroup
,
_metaDataMap
[
deltaAlphaName
])
{
_editorQml
=
"qrc:/qml/CircularSurveyItemEditor.qml"
;
//connect(&_deltaR, &Fact::valueChanged, this, &CircularSurveyComplexItem::_setDirty);
//connect(&_deltaAlpha, &Fact::valueChanged, this, &CircularSurveyComplexItem::_setDirty);
connect
(
&
_updateTimer
,
&
QTimer
::
timeout
,
this
,
&
CircularSurveyComplexItem
::
_updateItem
);
_updateTimer
.
start
(
100
);
}
void
CircularSurveyComplexItem
::
setRefPoint
(
const
QGeoCoordinate
&
refPt
)
...
...
@@ -25,6 +36,16 @@ QGeoCoordinate CircularSurveyComplexItem::refPoint() const
return
_referencePoint
;
}
Fact
*
CircularSurveyComplexItem
::
deltaR
()
{
return
&
_deltaR
;
}
Fact
*
CircularSurveyComplexItem
::
deltaAlpha
()
{
return
&
_deltaAlpha
;
}
bool
CircularSurveyComplexItem
::
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
{
return
false
;
...
...
@@ -75,8 +96,17 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
QVector
<
double
>
distances
;
for
(
const
QPointF
&
p
:
surveyPolygon
)
distances
.
append
(
norm
(
p
));
double
dalpha
=
2.1
/
180
*
M_PI
;
// radiants
double
dr
=
3
;
// meter
// 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
;
double
dalpha
=
_deltaAlpha
.
rawValue
().
toDouble
()
/
180
*
M_PI
;
// radiants
double
dr
=
_deltaR
.
rawValue
().
toDouble
();
// meter
double
r_min
=
dr
;
// meter
double
r_max
=
(
*
std
::
max_element
(
distances
.
begin
(),
distances
.
end
()));
// meter
...
...
@@ -88,16 +118,16 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
for
(
const
QPointF
&
p
:
surveyPolygon
)
angles
.
append
(
truncateAngle
(
angle
(
p
)));
// determine r_min by successive approximation
double
r
=
r_m
ax
-
dr
;
while
(
r
>
r_m
in
)
{
double
r
=
r_m
in
;
while
(
r
<
r_m
ax
)
{
Circle
circle
(
r
,
origin
);
if
(
!
intersects
(
circle
,
surveyPolygon
))
{
if
(
intersects
(
circle
,
surveyPolygon
))
{
r_min
=
r
;
break
;
}
r
-
=
dr
;
r
+
=
dr
;
}
originInside
=
false
;
}
...
...
@@ -176,14 +206,14 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
double
alpha1
=
angle
(
entryPoints
[
k
]);
double
alpha2
=
angle
(
exitPoints
[(
k
+
offset
)
%
entryPoints
.
size
()]);
QList
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
dalpha
,
alpha1
,
alpha2
);
QList
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
double
(
dalpha
)
,
alpha1
,
alpha2
);
// use shortestPath() here if necessary, could be a problem if dr >>
if
(
sectorPath
.
size
()
>
0
)
currPolyPath
.
append
(
sectorPath
);
}
}
else
if
(
originInside
)
{
// circle fully inside polygon
QList
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
dalpha
,
0
,
2
*
M_PI
);
QList
<
QPointF
>
sectorPath
=
circle
.
approximateSektor
(
double
(
dalpha
)
,
0
,
2
*
M_PI
);
// use shortestPath() here if necessary, could be a problem if dr >>
currPolyPath
.
append
(
sectorPath
);
}
...
...
@@ -195,6 +225,8 @@ 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
()
)
{
...
...
@@ -249,6 +281,15 @@ void CircularSurveyComplexItem::_recalcCameraShots()
}
void
CircularSurveyComplexItem
::
_updateItem
()
{
if
(
_dirty
)
{
_rebuildTransects
();
setDirty
(
false
);
}
}
/*!
\class CircularSurveyComplexItem
\inmodule Wima
...
...
src/Wima/CircularSurveyComplexItem.h
View file @
470c9ab4
...
...
@@ -18,12 +18,16 @@ public:
CircularSurveyComplexItem
(
Vehicle
*
vehicle
,
bool
flyView
,
const
QString
&
kmlOrShpFile
,
QObject
*
parent
);
Q_PROPERTY
(
QGeoCoordinate
refPoint
READ
refPoint
WRITE
setRefPoint
NOTIFY
refPointChanged
)
Q_PROPERTY
(
Fact
*
deltaR
READ
deltaR
CONSTANT
)
Q_PROPERTY
(
Fact
*
deltaAlpha
READ
deltaAlpha
CONSTANT
)
// Property setters
void
setRefPoint
(
const
QGeoCoordinate
&
refPt
);
// Property getters
QGeoCoordinate
refPoint
()
const
;
QGeoCoordinate
refPoint
()
const
;
Fact
*
deltaR
();
Fact
*
deltaAlpha
();
// Overrides from ComplexMissionItem
bool
load
(
const
QJsonObject
&
complexObject
,
int
sequenceNumber
,
QString
&
errorString
)
final
;
...
...
@@ -43,7 +47,9 @@ public:
bool
readyForSave
(
void
)
const
final
;
double
additionalTimeDelay
(
void
)
const
final
;
static
const
char
*
settingsGroup
;
static
const
char
*
settingsGroup
;
static
const
char
*
deltaRName
;
static
const
char
*
deltaAlphaName
;
signals:
void
refPointChanged
();
...
...
@@ -53,9 +59,19 @@ private slots:
void
_rebuildTransectsPhase1
(
void
)
final
;
void
_recalcComplexDistance
(
void
)
final
;
void
_recalcCameraShots
(
void
)
final
;
void
_updateItem
(
void
);
signals:
private:
QGeoCoordinate
_referencePoint
;
// center of the circular lanes, e.g. base station
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_deltaR
;
SettingsFact
_deltaAlpha
;
QTimer
_updateTimer
;
};
...
...
src/Wima/CircularSurveyToDo.txt
deleted
100644 → 0
View file @
5005f97c
add refpt gui and edit constructor
src/Wima/ToDo.txt
0 → 100644
View file @
470c9ab4
add refpt gui and edit constructor
new path optim required for circ survey
add gui elements for circ survey
solve bug for cantFindPath.wima on Desktop/WimaPath
src/Wima/doc/SkriptDO.pdf
0 → 100644
View file @
470c9ab4
File added
src/WimaView/SphericalSurveyMapVisual.qml
View file @
470c9ab4
...
...
@@ -78,12 +78,17 @@ Item {
_mapPolygon
.
appendVertex
(
topRightCoord
)
_mapPolygon
.
appendVertex
(
bottomRightCoord
)
_mapPolygon
.
appendVertex
(
bottomLeftCoord
)
}
}
}
function
_setRefPoint
()
{
_missionItem
.
refPoint
=
map
.
toCoordinate
(
map
.
centerViewport
.
x
,
map
.
centerViewport
.
y
,
false
/* clipToViewPort */
)
}
Component.onCompleted
:
{
_addInitialPolygon
()
_addVisualElements
()
_setRefPoint
()
}
Component.onDestruction
:
{
...
...
@@ -152,4 +157,24 @@ Item {
}
}
}
// Ref. point (Base Station)
Component
{
id
:
refPointComponent
MapQuickItem
{
anchorPoint.x
:
sourceItem
.
anchorPointX
anchorPoint.y
:
sourceItem
.
anchorPointY
z
:
QGroundControl
.
zOrderMapItems
coordinate
:
_missionItem
.
refPoint
visible
:
_missionItem
.
refPoint
.
isValid
sourceItem
:
MissionItemIndexLabel
{
index
:
_missionItem
.
sequenceNumber
label
:
"
Ref.
"
checked
:
_missionItem
.
isCurrentItem
onClicked
:
_root
.
clicked
(
_missionItem
.
sequenceNumber
)
}
}
}
}
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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