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
296a43ce
Commit
296a43ce
authored
Mar 30, 2017
by
Gus Grubba
Committed by
GitHub
Mar 30, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #4895 from DonLakeFlyer/NoImageInTurnaround
Plan: Support for images in turnaround on/off
parents
0f8466d6
827eddf3
Changes
10
Hide whitespace changes
Inline
Side-by-side
Showing
10 changed files
with
309 additions
and
173 deletions
+309
-173
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+1
-1
CameraSection.cc
src/MissionManager/CameraSection.cc
+18
-16
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+5
-5
MissionController.cc
src/MissionManager/MissionController.cc
+2
-4
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+6
-5
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+2
-1
Survey.SettingsGroup.json
src/MissionManager/Survey.SettingsGroup.json
+13
-1
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+157
-66
SurveyMissionItem.h
src/MissionManager/SurveyMissionItem.h
+30
-11
SurveyItemEditor.qml
src/PlanView/SurveyItemEditor.qml
+75
-63
No files found.
src/MissionManager/CameraSection.FactMetaData.json
View file @
296a43ce
...
...
@@ -12,7 +12,7 @@
"shortDescription"
:
"Specify the distance between each photo"
,
"type"
:
"double"
,
"units"
:
"m"
,
"min"
:
0
,
"min"
:
0
.1
,
"decimalPlaces"
:
1
,
"defaultValue"
:
1
},
...
...
src/MissionManager/CameraSection.cc
View file @
296a43ce
...
...
@@ -229,36 +229,40 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
else
{
stopLooking
=
true
;
}
stopLooking
=
true
;
break
;
case
MAV_CMD_DO_SET_CAM_TRIGG_DIST
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
>=
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
// At this point we don't know if we have a stop taking photos pair, or a single distance trigger where the user specified 0
// We need to look at the next item to check for the stop taking photos pari
// At this point we don't know if we have a stop taking photos pair, or just a distance trigger
if
(
missionItem
.
param1
()
==
0
&&
scanIndex
<
visualItems
->
count
()
-
1
)
{
// Possible stop taking photos pair
SimpleMissionItem
*
nextItem
=
visualItems
->
value
<
SimpleMissionItem
*>
(
scanIndex
+
1
);
if
(
nextItem
)
{
missionItem
=
nextItem
->
missionItem
();
if
((
MAV_CMD
)
item
->
command
()
==
MAV_CMD_IMAGE_STOP_CAPTURE
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
MissionItem
&
nextMissionItem
=
nextItem
->
missionItem
();
if
(
nextMissionItem
.
command
()
==
MAV_CMD_IMAGE_STOP_CAPTURE
&&
nextMissionItem
.
param1
()
==
0
&&
nextMissionItem
.
param2
()
==
0
&&
nextMissionItem
.
param3
()
==
0
&&
nextMissionItem
.
param4
()
==
0
&&
nextMissionItem
.
param5
()
==
0
&&
nextMissionItem
.
param6
()
==
0
&&
nextMissionItem
.
param7
()
==
0
)
{
// We found a stop taking photos pair
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
StopTakingPhotos
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
stopLooking
=
true
;
break
;
}
}
}
// We didn't find a stop taking photos pair, so this is a regular trigger distance item
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
TakePhotoIntervalDistance
);
cameraPhotoIntervalDistance
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
break
;
// We didn't find a stop taking photos pair, check for trigger distance
if
(
missionItem
.
param1
()
>
0
)
{
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
TakePhotoIntervalDistance
);
cameraPhotoIntervalDistance
()
->
setRawValue
(
missionItem
.
param1
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
stopLooking
=
true
;
break
;
}
}
stopLooking
=
true
;
break
;
...
...
@@ -268,9 +272,8 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
TakeVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
else
{
stopLooking
=
true
;
}
stopLooking
=
true
;
break
;
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
...
...
@@ -278,9 +281,8 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
StopTakingVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
else
{
stopLooking
=
true
;
}
stopLooking
=
true
;
break
;
default:
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
296a43ce
...
...
@@ -817,11 +817,11 @@
}
},
{
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"category"
:
"Camera"
,
"id"
:
206
,
"rawName"
:
"MAV_CMD_DO_SET_CAM_TRIGG_DIST"
,
"friendlyName"
:
"Camera trigger distance"
,
"description"
:
"Set camera trigger distance."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Distance"
,
"default"
:
25
,
...
...
src/MissionManager/MissionController.cc
View file @
296a43ce
...
...
@@ -1555,10 +1555,8 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
}
SimpleMissionItem
*
simpleItem
=
qobject_cast
<
SimpleMissionItem
*>
(
visualItem
);
if
(
simpleItem
&&
simpleItem
->
cameraSection
()
->
available
())
{
scanIndex
++
;
simpleItem
->
scanForSections
(
visualItems
,
scanIndex
,
vehicle
);
continue
;
if
(
simpleItem
)
{
simpleItem
->
scanForSections
(
visualItems
,
scanIndex
+
1
,
vehicle
);
}
scanIndex
++
;
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
296a43ce
...
...
@@ -655,16 +655,17 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return
_cameraSection
->
available
()
?
_cameraSection
->
specifiedGimbalYaw
()
:
missionItem
().
specifiedGimbalYaw
();
}
void
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
)
bool
SimpleMissionItem
::
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
)
{
Q_UNUSED
(
vehicle
)
;
bool
sectionFound
=
false
;
qDebug
()
<<
"SimpleMissionItem::scanForSections"
<<
scanIndex
<<
_cameraSection
->
available
(
);
Q_UNUSED
(
vehicle
);
if
(
_cameraSection
->
available
())
{
bool
sectionFound
=
_cameraSection
->
scanForCameraSection
(
visualItems
,
scanIndex
);
qDebug
()
<<
sectionFound
;
sectionFound
=
_cameraSection
->
scanForCameraSection
(
visualItems
,
scanIndex
);
}
return
sectionFound
;
}
void
SimpleMissionItem
::
_updateCameraSection
(
void
)
...
...
src/MissionManager/SimpleMissionItem.h
View file @
296a43ce
...
...
@@ -48,7 +48,8 @@ public:
/// @param visualItems List of all visual items
/// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission
void
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
);
/// @return true: section found
bool
scanForSections
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
,
Vehicle
*
vehicle
);
// Property accesors
...
...
src/MissionManager/Survey.SettingsGroup.json
View file @
296a43ce
...
...
@@ -130,6 +130,18 @@
"units"
:
"m"
,
"defaultValue"
:
25
},
{
"name"
:
"CameraTriggerInTurnaround"
,
"shortDescription"
:
"Camera continues taking images in turnarounds."
,
"type"
:
"bool"
,
"defaultValue"
:
false
},
{
"name"
:
"HoverAndCapture"
,
"shortDescription"
:
"Hover at each image point and take image"
,
"type"
:
"bool"
,
"defaultValue"
:
false
},
{
"name"
:
"CameraOrientationLandscape"
,
"shortDescription"
:
"Camera on vehicle is in landscape orientation."
,
...
...
@@ -140,7 +152,7 @@
"name"
:
"FixedValueIsAltitude"
,
"shortDescription"
:
"The altitude is kep constant while ground resolution changes."
,
"type"
:
"bool"
,
"defaultValue"
:
0
"defaultValue"
:
false
},
{
"name"
:
"Camera"
,
...
...
src/MissionManager/SurveyMissionItem.cc
View file @
296a43ce
...
...
@@ -30,6 +30,8 @@ const char* SurveyMissionItem::_jsonGridSpacingKey = "spacing";
const
char
*
SurveyMissionItem
::
_jsonTurnaroundDistKey
=
"turnAroundDistance"
;
const
char
*
SurveyMissionItem
::
_jsonCameraTriggerKey
=
"cameraTrigger"
;
const
char
*
SurveyMissionItem
::
_jsonCameraTriggerDistanceKey
=
"cameraTriggerDistance"
;
const
char
*
SurveyMissionItem
::
_jsonCameraTriggerInTurnaroundKey
=
"cameraTriggerInTurnaround"
;
const
char
*
SurveyMissionItem
::
_jsonHoverAndCaptureKey
=
"hoverAndCapture"
;
const
char
*
SurveyMissionItem
::
_jsonGroundResolutionKey
=
"groundResolution"
;
const
char
*
SurveyMissionItem
::
_jsonFrontalOverlapKey
=
"imageFrontalOverlap"
;
const
char
*
SurveyMissionItem
::
_jsonSideOverlapKey
=
"imageSideOverlap"
;
...
...
@@ -52,6 +54,8 @@ const char* SurveyMissionItem::gridAngleName = "GridAngle";
const
char
*
SurveyMissionItem
::
gridSpacingName
=
"GridSpacing"
;
const
char
*
SurveyMissionItem
::
turnaroundDistName
=
"TurnaroundDist"
;
const
char
*
SurveyMissionItem
::
cameraTriggerDistanceName
=
"CameraTriggerDistance"
;
const
char
*
SurveyMissionItem
::
cameraTriggerInTurnaroundName
=
"CameraTriggerInTurnaround"
;
const
char
*
SurveyMissionItem
::
hoverAndCaptureName
=
"HoverAndCapture"
;
const
char
*
SurveyMissionItem
::
groundResolutionName
=
"GroundResolution"
;
const
char
*
SurveyMissionItem
::
frontalOverlapName
=
"FrontalOverlap"
;
const
char
*
SurveyMissionItem
::
sideOverlapName
=
"SideOverlap"
;
...
...
@@ -83,6 +87,8 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
,
_turnaroundDistFact
(
settingsGroup
,
_metaDataMap
[
turnaroundDistName
])
,
_cameraTriggerFact
(
settingsGroup
,
_metaDataMap
[
cameraTriggerName
])
,
_cameraTriggerDistanceFact
(
settingsGroup
,
_metaDataMap
[
cameraTriggerDistanceName
])
,
_cameraTriggerInTurnaroundFact
(
settingsGroup
,
_metaDataMap
[
cameraTriggerInTurnaroundName
])
,
_hoverAndCaptureFact
(
settingsGroup
,
_metaDataMap
[
hoverAndCaptureName
])
,
_groundResolutionFact
(
settingsGroup
,
_metaDataMap
[
groundResolutionName
])
,
_frontalOverlapFact
(
settingsGroup
,
_metaDataMap
[
frontalOverlapName
])
,
_sideOverlapFact
(
settingsGroup
,
_metaDataMap
[
sideOverlapName
])
...
...
@@ -102,10 +108,13 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
_turnaroundDistFact
.
setRawValue
(
0
);
}
connect
(
&
_gridSpacingFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_gridAngleFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_turnaroundDistFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_gridSpacingFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_gridAngleFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_turnaroundDistFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_cameraTriggerDistanceFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_cameraTriggerInTurnaroundFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_hoverAndCaptureFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
connect
(
&
_gridAltitudeFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_updateCoordinateAltitude
);
// Signal to Qml when camera value changes so it can recalc
...
...
@@ -261,8 +270,8 @@ int SurveyMissionItem::lastSequenceNumber(void) const
{
int
lastSeq
=
_sequenceNumber
;
if
(
_
g
ridPoints
.
count
())
{
lastSeq
+=
_
g
ridPoints
.
count
()
-
1
;
if
(
_
simpleG
ridPoints
.
count
())
{
lastSeq
+=
_
simpleG
ridPoints
.
count
()
-
1
;
if
(
_cameraTriggerFact
.
rawValue
().
toBool
())
{
// Account for two trigger messages
lastSeq
+=
2
;
...
...
@@ -495,8 +504,8 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
double
SurveyMissionItem
::
greatestDistanceTo
(
const
QGeoCoordinate
&
other
)
const
{
double
greatestDistance
=
0.0
;
for
(
int
i
=
0
;
i
<
_
g
ridPoints
.
count
();
i
++
)
{
QGeoCoordinate
currentCoord
=
_
g
ridPoints
[
i
].
value
<
QGeoCoordinate
>
();
for
(
int
i
=
0
;
i
<
_
simpleG
ridPoints
.
count
();
i
++
)
{
QGeoCoordinate
currentCoord
=
_
simpleG
ridPoints
[
i
].
value
<
QGeoCoordinate
>
();
double
distance
=
currentCoord
.
distanceTo
(
other
);
if
(
distance
>
greatestDistance
)
{
greatestDistance
=
distance
;
...
...
@@ -521,11 +530,16 @@ bool SurveyMissionItem::specifiesCoordinate(void) const
void
SurveyMissionItem
::
_clearGrid
(
void
)
{
// Bug workaround
while
(
_
g
ridPoints
.
count
()
>
1
)
{
_
g
ridPoints
.
takeLast
();
while
(
_
simpleG
ridPoints
.
count
()
>
1
)
{
_
simpleG
ridPoints
.
takeLast
();
}
emit
gridPointsChanged
();
_gridPoints
.
clear
();
_simpleGridPoints
.
clear
();
}
void
_calcCameraShots
()
{
}
void
SurveyMissionItem
::
_generateGrid
(
void
)
...
...
@@ -535,10 +549,11 @@ void SurveyMissionItem::_generateGrid(void)
return
;
}
_
g
ridPoints
.
clear
();
_
simpleG
ridPoints
.
clear
();
QList
<
QPointF
>
polygonPoints
;
QList
<
QPointF
>
gridPoints
;
QList
<
QPointF
>
polygonPoints
;
QList
<
QPointF
>
gridPoints
;
QList
<
QList
<
QPointF
>>
gridSegments
;
// Convert polygon to Qt coordinate system (y positive is down)
qCDebug
(
SurveyMissionItemLog
)
<<
"Convert polygon"
;
...
...
@@ -561,7 +576,7 @@ void SurveyMissionItem::_generateGrid(void)
_setCoveredArea
(
0.5
*
fabs
(
coveredArea
));
// Generate grid
_gridGenerator
(
polygonPoints
,
gridPoints
);
_gridGenerator
(
polygonPoints
,
gridPoints
,
gridSegments
);
double
surveyDistance
=
0.0
;
// Convert to Geo and set altitude
...
...
@@ -574,11 +589,16 @@ void SurveyMissionItem::_generateGrid(void)
QGeoCoordinate
geoCoord
;
convertNedToGeo
(
-
point
.
y
(),
point
.
x
(),
0
,
tangentOrigin
,
&
geoCoord
);
_
g
ridPoints
+=
QVariant
::
fromValue
(
geoCoord
);
_
simpleG
ridPoints
+=
QVariant
::
fromValue
(
geoCoord
);
}
_setSurveyDistance
(
surveyDistance
);
if
(
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
()
>
0
)
{
_setCameraShots
((
int
)
floor
(
surveyDistance
/
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
()));
// Set camera shots here if taking images in turnaround (otherwise it's in _gridGenerator)
double
triggerDistance
=
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
();
if
(
triggerDistance
>
0
)
{
if
(
_cameraTriggerInTurnaroundFact
.
rawValue
().
toBool
())
{
_setCameraShots
((
int
)
ceil
(
surveyDistance
/
triggerDistance
));
}
}
else
{
_setCameraShots
(
0
);
}
...
...
@@ -586,11 +606,11 @@ void SurveyMissionItem::_generateGrid(void)
emit
gridPointsChanged
();
emit
lastSequenceNumberChanged
(
lastSequenceNumber
());
if
(
_
g
ridPoints
.
count
())
{
QGeoCoordinate
coordinate
=
_
g
ridPoints
.
first
().
value
<
QGeoCoordinate
>
();
if
(
_
simpleG
ridPoints
.
count
())
{
QGeoCoordinate
coordinate
=
_
simpleG
ridPoints
.
first
().
value
<
QGeoCoordinate
>
();
coordinate
.
setAltitude
(
_gridAltitudeFact
.
rawValue
().
toDouble
());
setCoordinate
(
coordinate
);
QGeoCoordinate
exitCoordinate
=
_
g
ridPoints
.
last
().
value
<
QGeoCoordinate
>
();
QGeoCoordinate
exitCoordinate
=
_
simpleG
ridPoints
.
last
().
value
<
QGeoCoordinate
>
();
exitCoordinate
.
setAltitude
(
_gridAltitudeFact
.
rawValue
().
toDouble
());
_setExitCoordinate
(
exitCoordinate
);
}
...
...
@@ -718,14 +738,15 @@ void SurveyMissionItem::_adjustLineDirection(const QList<QLineF>& lineList, QLis
}
}
void
SurveyMissionItem
::
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QPointF
>&
gridPoi
nts
)
void
SurveyMissionItem
::
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QPointF
>&
simpleGridPoints
,
QList
<
QList
<
QPointF
>>&
gridSegme
nts
)
{
double
gridAngle
=
_gridAngleFact
.
rawValue
().
toDouble
();
double
gridSpacing
=
_gridSpacingFact
.
rawValue
().
toDouble
();
qCDebug
(
SurveyMissionItemLog
)
<<
"SurveyMissionItem::_gridGenerator gridSpacing:gridAngle"
<<
gridSpacing
<<
gridAngle
;
gridPoints
.
clear
();
simpleGridPoints
.
clear
();
gridSegments
.
clear
();
// Convert polygon to bounding rect
...
...
@@ -778,74 +799,139 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi
QList
<
QLineF
>
resultLines
;
_adjustLineDirection
(
intersectLines
,
resultLines
);
// Turn into a path
float
turnaroundDist
=
_turnaroundDistFact
.
rawValue
().
toDouble
();
// Calc camera shots here if there are no images in turnaround
double
triggerDistance
=
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
();
if
(
triggerDistance
>
0
&&
!
_cameraTriggerInTurnaroundFact
.
rawValue
().
toBool
())
{
int
cameraShots
=
0
;
for
(
int
i
=
0
;
i
<
resultLines
.
count
();
i
++
)
{
cameraShots
+=
(
int
)
ceil
(
resultLines
[
i
].
length
()
/
triggerDistance
);
}
_setCameraShots
(
cameraShots
);
}
// Turn into a path
for
(
int
i
=
0
;
i
<
resultLines
.
count
();
i
++
)
{
QList
<
QPointF
>
segmentPoints
;
const
QLineF
&
line
=
resultLines
[
i
];
QPointF
turnaroundOffset
=
line
.
p2
()
-
line
.
p1
();
turnaroundOffset
=
turnaroundOffset
*
turnaroundDist
/
sqrt
(
pow
(
turnaroundOffset
.
x
(),
2.0
)
+
pow
(
turnaroundOffset
.
y
(),
2.0
));
turnaroundOffset
=
turnaroundOffset
*
turnaroundDist
/
sqrt
(
pow
(
turnaroundOffset
.
x
(),
2
)
+
pow
(
turnaroundOffset
.
y
(),
2
));
if
(
i
&
1
)
{
if
(
turnaroundDist
>
0.0
)
{
gridPoints
<<
line
.
p2
()
+
turnaroundOffset
<<
line
.
p2
()
<<
line
.
p1
()
<<
line
.
p1
()
-
turnaroundOffset
;
simpleGridPoints
<<
line
.
p2
()
+
turnaroundOffset
<<
line
.
p2
()
<<
line
.
p1
()
<<
line
.
p1
()
-
turnaroundOffset
;
segmentPoints
<<
line
.
p2
()
+
turnaroundOffset
<<
line
.
p2
()
<<
line
.
p1
()
<<
line
.
p1
()
-
turnaroundOffset
;
}
else
{
gridPoints
<<
line
.
p2
()
<<
line
.
p1
();
simpleGridPoints
<<
line
.
p2
()
<<
line
.
p1
();
segmentPoints
<<
line
.
p2
()
<<
line
.
p1
();
}
}
else
{
if
(
turnaroundDist
>
0.0
)
{
gridPoints
<<
line
.
p1
()
-
turnaroundOffset
<<
line
.
p1
()
<<
line
.
p2
()
<<
line
.
p2
()
+
turnaroundOffset
;
simpleGridPoints
<<
line
.
p1
()
-
turnaroundOffset
<<
line
.
p1
()
<<
line
.
p2
()
<<
line
.
p2
()
+
turnaroundOffset
;
segmentPoints
<<
line
.
p1
()
-
turnaroundOffset
<<
line
.
p1
()
<<
line
.
p2
()
<<
line
.
p2
()
+
turnaroundOffset
;
}
else
{
gridPoints
<<
line
.
p1
()
<<
line
.
p2
();
simpleGridPoints
<<
line
.
p1
()
<<
line
.
p2
();
segmentPoints
<<
line
.
p1
()
<<
line
.
p2
();
}
}
gridSegments
.
append
(
segmentPoints
);
}
}
int
SurveyMissionItem
::
_appendWaypointToMission
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QGeoCoordinate
&
coord
,
CameraTriggerCode
cameraTrigger
,
QObject
*
missionItemParent
)
{
double
altitude
=
_gridAltitudeFact
.
rawValue
().
toDouble
();
bool
altitudeRelative
=
_gridAltitudeRelativeFact
.
rawValue
().
toBool
();
double
triggerDistance
=
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
();
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_NAV_WAYPOINT
,
altitudeRelative
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
0.0
,
0.0
,
0.0
,
0.0
,
// param 1-4 unused
coord
.
latitude
(),
coord
.
longitude
(),
altitude
,
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
if
(
cameraTrigger
!=
CameraTriggerNone
)
{
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
cameraTrigger
==
CameraTriggerOn
?
triggerDistance
:
0
,
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
return
seqNum
;
}
void
SurveyMissionItem
::
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
{
int
seqNum
=
_sequenceNumber
;
for
(
int
i
=
0
;
i
<
_gridPoints
.
count
();
i
++
)
{
QGeoCoordinate
coord
=
_gridPoints
[
i
].
value
<
QGeoCoordinate
>
();
double
altitude
=
_gridAltitudeFact
.
rawValue
().
toDouble
();
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
MAV_CMD_NAV_WAYPOINT
,
// MAV_CMD
_gridAltitudeRelativeFact
.
rawValue
().
toBool
()
?
MAV_FRAME_GLOBAL_RELATIVE_ALT
:
MAV_FRAME_GLOBAL
,
// MAV_FRAME
0.0
,
0.0
,
0.0
,
0.0
,
// param 1-4
coord
.
latitude
(),
coord
.
longitude
(),
altitude
,
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
int
seqNum
=
_sequenceNumber
;
bool
hasTurnaround
=
_turnaroundDistFact
.
rawValue
().
toDouble
()
>
0
;
bool
triggerCamera
=
_cameraTriggerFact
.
rawValue
().
toBool
();
bool
imagesEverywhere
=
triggerCamera
&&
_cameraTriggerInTurnaroundFact
.
rawValue
().
toBool
();
int
i
=
0
;
while
(
i
<
_simpleGridPoints
.
count
())
{
CameraTriggerCode
cameraTrigger
;
QGeoCoordinate
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
// Either waypoint entering polygon of turnaround point for start of new transect
cameraTrigger
=
imagesEverywhere
?
(
i
==
0
?
CameraTriggerOn
:
CameraTriggerNone
)
:
(
hasTurnaround
?
CameraTriggerNone
:
CameraTriggerOn
);
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
cameraTrigger
,
missionItemParent
);
if
(
hasTurnaround
)
{
// Waypoint entering the polygon
if
(
++
i
>=
_simpleGridPoints
.
count
())
{
qWarning
()
<<
"Bad grid generation"
;
break
;
}
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
cameraTrigger
=
imagesEverywhere
?
CameraTriggerNone
:
CameraTriggerOn
;
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
cameraTrigger
,
missionItemParent
);
}
if
(
_cameraTriggerFact
.
rawValue
().
toBool
()
&&
i
==
0
)
{
// Turn on camera
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// MAV_CMD
MAV_FRAME_MISSION
,
// MAV_FRAME
_cameraTriggerDistanceFact
.
rawValue
().
toDouble
(),
// trigger distance
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
// param 2-7
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
// Waypoint exiting polygon
if
(
++
i
>=
_simpleGridPoints
.
count
())
{
qWarning
()
<<
"Bad grid generation"
;
break
;
}
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
cameraTrigger
=
imagesEverywhere
?
CameraTriggerNone
:
CameraTriggerOff
;
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
cameraTrigger
,
missionItemParent
);
if
(
hasTurnaround
)
{
// Waypoint at the end of transect
if
(
++
i
>=
_simpleGridPoints
.
count
())
{
qWarning
()
<<
"Bad grid generation"
;
break
;
}
coord
=
_simpleGridPoints
[
i
].
value
<
QGeoCoordinate
>
();
cameraTrigger
=
CameraTriggerNone
;
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
cameraTrigger
,
missionItemParent
);
}
i
++
;
}
if
(
_cameraTriggerFact
.
rawValue
().
toBool
()
)
{
// Turn off camera
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
// sequence number
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
// MAV_CMD
MAV_FRAME_MISSION
,
// MAV_FRAME
0.0
,
// trigger distance
0
.0
,
0.0
,
0.0
,
0.0
,
0.0
,
0.0
,
// param 2-7
true
,
// autoContinue
false
,
// isCurrentItem
if
(
imagesEverywhere
)
{
// Turn off camera
at end of survey
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
0.0
,
// trigger distance (off)
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
...
...
@@ -883,3 +969,8 @@ void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFligh
emit
timeBetweenShotsChanged
();
}
}
void
SurveyMissionItem
::
_setDirty
(
void
)
{
setDirty
(
true
);
}
src/MissionManager/SurveyMissionItem.h
View file @
296a43ce
...
...
@@ -32,6 +32,8 @@ public:
Q_PROPERTY
(
Fact
*
turnaroundDist
READ
turnaroundDist
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraTrigger
READ
cameraTrigger
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraTriggerDistance
READ
cameraTriggerDistance
CONSTANT
)
Q_PROPERTY
(
Fact
*
cameraTriggerInTurnaround
READ
cameraTriggerInTurnaround
CONSTANT
)
Q_PROPERTY
(
Fact
*
hoverAndCapture
READ
hoverAndCapture
CONSTANT
)
Q_PROPERTY
(
Fact
*
groundResolution
READ
groundResolution
CONSTANT
)
Q_PROPERTY
(
Fact
*
frontalOverlap
READ
frontalOverlap
CONSTANT
)
Q_PROPERTY
(
Fact
*
sideOverlap
READ
sideOverlap
CONSTANT
)
...
...
@@ -68,7 +70,7 @@ public:
QVariantList
polygonPath
(
void
)
{
return
_polygonPath
;
}
QmlObjectListModel
*
polygonModel
(
void
)
{
return
&
_polygonModel
;
}
QVariantList
gridPoints
(
void
)
{
return
_
g
ridPoints
;
}
QVariantList
gridPoints
(
void
)
{
return
_
simpleG
ridPoints
;
}
Fact
*
manualGrid
(
void
)
{
return
&
_manualGridFact
;
}
Fact
*
gridAltitude
(
void
)
{
return
&
_gridAltitudeFact
;
}
...
...
@@ -78,6 +80,8 @@ public:
Fact
*
turnaroundDist
(
void
)
{
return
&
_turnaroundDistFact
;
}
Fact
*
cameraTrigger
(
void
)
{
return
&
_cameraTriggerFact
;
}
Fact
*
cameraTriggerDistance
(
void
)
{
return
&
_cameraTriggerDistanceFact
;
}
Fact
*
cameraTriggerInTurnaround
(
void
)
{
return
&
_cameraTriggerInTurnaroundFact
;
}
Fact
*
hoverAndCapture
(
void
)
{
return
&
_hoverAndCaptureFact
;
}
Fact
*
groundResolution
(
void
)
{
return
&
_groundResolutionFact
;
}
Fact
*
frontalOverlap
(
void
)
{
return
&
_frontalOverlapFact
;
}
Fact
*
sideOverlap
(
void
)
{
return
&
_sideOverlapFact
;
}
...
...
@@ -141,6 +145,8 @@ public:
static
const
char
*
gridSpacingName
;
static
const
char
*
turnaroundDistName
;
static
const
char
*
cameraTriggerDistanceName
;
static
const
char
*
cameraTriggerInTurnaroundName
;
static
const
char
*
hoverAndCaptureName
;
static
const
char
*
groundResolutionName
;
static
const
char
*
frontalOverlapName
;
static
const
char
*
sideOverlapName
;
...
...
@@ -166,14 +172,21 @@ signals:
private
slots
:
void
_cameraTriggerChanged
(
void
);
void
_setDirty
(
void
);
private:
enum
CameraTriggerCode
{
CameraTriggerNone
,
CameraTriggerOn
,
CameraTriggerOff
};
void
_clear
(
void
);
void
_setExitCoordinate
(
const
QGeoCoordinate
&
coordinate
);
void
_clearGrid
(
void
);
void
_generateGrid
(
void
);
void
_updateCoordinateAltitude
(
void
);
void
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QPointF
>&
gridPoi
nts
);
void
_gridGenerator
(
const
QList
<
QPointF
>&
polygonPoints
,
QList
<
QPointF
>&
simpleGridPoints
,
QList
<
QList
<
QPointF
>>&
gridSegme
nts
);
QPointF
_rotatePoint
(
const
QPointF
&
point
,
const
QPointF
&
origin
,
double
angle
);
void
_intersectLinesWithRect
(
const
QList
<
QLineF
>&
lineList
,
const
QRectF
&
boundRect
,
QList
<
QLineF
>&
resultLines
);
void
_intersectLinesWithPolygon
(
const
QList
<
QLineF
>&
lineList
,
const
QPolygonF
&
polygon
,
QList
<
QLineF
>&
resultLines
);
...
...
@@ -182,15 +195,17 @@ private:
void
_setCameraShots
(
int
cameraShots
);
void
_setCoveredArea
(
double
coveredArea
);
void
_cameraValueChanged
(
void
);
int
_sequenceNumber
;
bool
_dirty
;
QVariantList
_polygonPath
;
QmlObjectListModel
_polygonModel
;
QVariantList
_gridPoints
;
QGeoCoordinate
_coordinate
;
QGeoCoordinate
_exitCoordinate
;
bool
_cameraOrientationFixed
;
int
_appendWaypointToMission
(
QList
<
MissionItem
*>&
items
,
int
seqNum
,
QGeoCoordinate
&
coord
,
CameraTriggerCode
cameraTrigger
,
QObject
*
missionItemParent
);
int
_sequenceNumber
;
bool
_dirty
;
QVariantList
_polygonPath
;
QmlObjectListModel
_polygonModel
;
QVariantList
_simpleGridPoints
;
///< Grid points for drawing simple grid visuals
QList
<
QList
<
QGeoCoordinate
>>
_gridSegments
;
///< Internal grid line segments including grid exit and turnaround point
QGeoCoordinate
_coordinate
;
QGeoCoordinate
_exitCoordinate
;
bool
_cameraOrientationFixed
;
double
_surveyDistance
;
int
_cameraShots
;
...
...
@@ -208,6 +223,8 @@ private:
SettingsFact
_turnaroundDistFact
;
SettingsFact
_cameraTriggerFact
;
SettingsFact
_cameraTriggerDistanceFact
;
SettingsFact
_cameraTriggerInTurnaroundFact
;
SettingsFact
_hoverAndCaptureFact
;
SettingsFact
_groundResolutionFact
;
SettingsFact
_frontalOverlapFact
;
SettingsFact
_sideOverlapFact
;
...
...
@@ -229,6 +246,8 @@ private:
static
const
char
*
_jsonTurnaroundDistKey
;
static
const
char
*
_jsonCameraTriggerKey
;
static
const
char
*
_jsonCameraTriggerDistanceKey
;
static
const
char
*
_jsonCameraTriggerInTurnaroundKey
;
static
const
char
*
_jsonHoverAndCaptureKey
;
static
const
char
*
_jsonGroundResolutionKey
;
static
const
char
*
_jsonFrontalOverlapKey
;
static
const
char
*
_jsonSideOverlapKey
;
...
...
src/PlanView/SurveyItemEditor.qml
View file @
296a43ce
...
...
@@ -180,40 +180,73 @@ Rectangle {
spacing
:
_margin
SectionHeader
{
id
:
cameraHeader
text
:
qsTr
(
"
Camera
"
)
showSpacer
:
false
}
QGCComboBox
{
id
:
gridTypeCombo
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
model
:
_cameraList
currentIndex
:
-
1
onActivated
:
{
if
(
index
==
_gridTypeManual
)
{
missionItem
.
manualGrid
.
value
=
true
}
else
if
(
index
==
_gridTypeCustomCamera
)
{
missionItem
.
manualGrid
.
value
=
false
missionItem
.
camera
.
value
=
gridTypeCombo
.
textAt
(
index
)
missionItem
.
cameraOrientationFixed
=
false
}
else
{
missionItem
.
manualGrid
.
value
=
false
missionItem
.
camera
.
value
=
gridTypeCombo
.
textAt
(
index
)
_noCameraValueRecalc
=
true
var
listIndex
=
index
-
_gridTypeCamera
missionItem
.
cameraSensorWidth
.
rawValue
=
_vehicleCameraList
[
listIndex
].
sensorWidth
missionItem
.
cameraSensorHeight
.
rawValue
=
_vehicleCameraList
[
listIndex
].
sensorHeight
missionItem
.
cameraResolutionWidth
.
rawValue
=
_vehicleCameraList
[
listIndex
].
imageWidth
missionItem
.
cameraResolutionHeight
.
rawValue
=
_vehicleCameraList
[
listIndex
].
imageHeight
missionItem
.
cameraFocalLength
.
rawValue
=
_vehicleCameraList
[
listIndex
].
focalLength
missionItem
.
cameraOrientationLandscape
.
rawValue
=
_vehicleCameraList
[
listIndex
].
landscape
?
1
:
0
missionItem
.
cameraOrientationFixed
=
_vehicleCameraList
[
listIndex
].
fixedOrientation
_noCameraValueRecalc
=
false
recalcFromCameraValues
()
spacing
:
_margin
visible
:
cameraHeader
.
checked
QGCComboBox
{
id
:
gridTypeCombo
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
model
:
_cameraList
currentIndex
:
-
1
onActivated
:
{
if
(
index
==
_gridTypeManual
)
{
missionItem
.
manualGrid
.
value
=
true
}
else
if
(
index
==
_gridTypeCustomCamera
)
{
missionItem
.
manualGrid
.
value
=
false
missionItem
.
camera
.
value
=
gridTypeCombo
.
textAt
(
index
)
missionItem
.
cameraOrientationFixed
=
false
}
else
{
missionItem
.
manualGrid
.
value
=
false
missionItem
.
camera
.
value
=
gridTypeCombo
.
textAt
(
index
)
_noCameraValueRecalc
=
true
var
listIndex
=
index
-
_gridTypeCamera
missionItem
.
cameraSensorWidth
.
rawValue
=
_vehicleCameraList
[
listIndex
].
sensorWidth
missionItem
.
cameraSensorHeight
.
rawValue
=
_vehicleCameraList
[
listIndex
].
sensorHeight
missionItem
.
cameraResolutionWidth
.
rawValue
=
_vehicleCameraList
[
listIndex
].
imageWidth
missionItem
.
cameraResolutionHeight
.
rawValue
=
_vehicleCameraList
[
listIndex
].
imageHeight
missionItem
.
cameraFocalLength
.
rawValue
=
_vehicleCameraList
[
listIndex
].
focalLength
missionItem
.
cameraOrientationLandscape
.
rawValue
=
_vehicleCameraList
[
listIndex
].
landscape
?
1
:
0
missionItem
.
cameraOrientationFixed
=
_vehicleCameraList
[
listIndex
].
fixedOrientation
_noCameraValueRecalc
=
false
recalcFromCameraValues
()
}
}
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
missionItem
.
manualGrid
.
value
==
true
FactCheckBox
{
anchors.baseline
:
cameraTriggerDistanceField
.
baseline
text
:
qsTr
(
"
Trigger Distance
"
)
fact
:
missionItem
.
cameraTrigger
}
FactTextField
{
id
:
cameraTriggerDistanceField
Layout.fillWidth
:
true
fact
:
missionItem
.
cameraTriggerDistance
enabled
:
missionItem
.
cameraTrigger
.
value
}
}
FactCheckBox
{
text
:
qsTr
(
"
Hover and capture image
"
)
fact
:
missionItem
.
hoverAndCapture
}
}
// Camera based grid ui
...
...
@@ -343,7 +376,10 @@ Rectangle {
}
}
SectionHeader
{
text
:
qsTr
(
"
Grid
"
)
}
SectionHeader
{
id
:
gridHeader
text
:
qsTr
(
"
Grid
"
)
}
GridLayout
{
anchors.left
:
parent
.
left
...
...
@@ -351,6 +387,7 @@ Rectangle {
columnSpacing
:
_margin
rowSpacing
:
_margin
columns
:
2
visible
:
gridHeader
.
checked
QGCLabel
{
text
:
qsTr
(
"
Angle
"
)
}
FactTextField
{
...
...
@@ -403,13 +440,17 @@ Rectangle {
}
// Manual grid ui
SectionHeader
{
id
:
manualGridHeader
text
:
qsTr
(
"
Grid
"
)
visible
:
gridTypeCombo
.
currentIndex
==
_gridTypeManual
}
Column
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
visible
:
gridTypeCombo
.
currentIndex
==
_gridTypeManual
SectionHeader
{
text
:
qsTr
(
"
Grid
"
)
}
visible
:
manualGridHeader
.
visible
&&
manualGridHeader
.
checked
FactTextFieldGrid
{
anchors.left
:
parent
.
left
...
...
@@ -420,50 +461,21 @@ Rectangle {
factLabels
:
[
qsTr
(
"
Angle
"
),
qsTr
(
"
Spacing
"
),
qsTr
(
"
Altitude
"
),
qsTr
(
"
Turnaround dist
"
)]
}
Item
{
height
:
_margin
;
width
:
1
;
visible
:
!
ScreenTools
.
isTinyScreen
}
FactCheckBox
{
anchors.left
:
parent
.
left
text
:
qsTr
(
"
Relative altitude
"
)
fact
:
missionItem
.
gridAltitudeRelative
}
Item
{
height
:
_sectionSpacer
;
width
:
1
;
visible
:
!
ScreenTools
.
isTinyScreen
}
QGCLabel
{
text
:
qsTr
(
"
Camera
"
)
}
Rectangle
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
height
:
1
color
:
qgcPal
.
text
}
RowLayout
{
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margin
FactCheckBox
{
anchors.baseline
:
cameraTriggerDistanceField
.
baseline
text
:
qsTr
(
"
Trigger Distance
"
)
fact
:
missionItem
.
cameraTrigger
}
FactTextField
{
id
:
cameraTriggerDistanceField
Layout.fillWidth
:
true
fact
:
missionItem
.
cameraTriggerDistance
enabled
:
missionItem
.
cameraTrigger
.
value
}
}
}
SectionHeader
{
text
:
qsTr
(
"
Statistics
"
)
}
SectionHeader
{
id
:
statsHeader
text
:
qsTr
(
"
Statistics
"
)
}
Grid
{
columns
:
2
columnSpacing
:
ScreenTools
.
defaultFontPixelWidth
visible
:
statsHeader
.
checked
QGCLabel
{
text
:
qsTr
(
"
Survey area
"
)
}
QGCLabel
{
text
:
QGroundControl
.
squareMetersToAppSettingsAreaUnits
(
missionItem
.
coveredArea
).
toFixed
(
2
)
+
"
"
+
QGroundControl
.
appSettingsAreaUnitsString
}
...
...
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