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
4b8147d3
Commit
4b8147d3
authored
Jul 07, 2017
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fix trigger start for images everywhere
parent
aca64fff
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
16 additions
and
15 deletions
+16
-15
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+16
-15
No files found.
src/MissionManager/SurveyMissionItem.cc
View file @
4b8147d3
...
...
@@ -1138,7 +1138,9 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
cameraTrigger
==
CameraTriggerOn
?
_triggerDistance
()
:
0
,
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 unused
0
,
// shutter integration (ignore)
cameraTrigger
==
CameraTriggerOn
?
1
:
0
,
// trigger immediately when starting
0
,
0
,
0
,
0
,
// param 4-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
...
...
@@ -1196,21 +1198,14 @@ bool SurveyMissionItem::_nextTransectCoord(const QList<QGeoCoordinate>& transect
/// @return false: Generation failed
bool
SurveyMissionItem
::
_appendMissionItemsWorker
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
,
int
&
seqNum
,
bool
hasRefly
,
bool
buildRefly
)
{
bool
firstWaypointTrigger
=
false
;
qCDebug
(
SurveyMissionItemLog
)
<<
"hasTurnaround:triggerCamera:hoverAndCapture:imagesEverywhere:hasRefly:buildRefly"
<<
_hasTurnaround
()
<<
_triggerCamera
()
<<
_hoverAndCaptureEnabled
()
<<
_imagesEverywhere
()
<<
hasRefly
<<
buildRefly
;
QList
<
QList
<
QGeoCoordinate
>>&
transectSegments
=
buildRefly
?
_reflyTransectSegments
:
_transectSegments
;
if
(
!
buildRefly
&&
_imagesEverywhere
())
{
// We are taking images in turnaround, so we start command once at beginning
MissionItem
*
item
=
new
MissionItem
(
seqNum
++
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
_triggerDistance
(),
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
firstWaypointTrigger
=
true
;
}
for
(
int
segmentIndex
=
0
;
segmentIndex
<
transectSegments
.
count
();
segmentIndex
++
)
{
...
...
@@ -1226,15 +1221,21 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
if
(
!
_nextTransectCoord
(
segment
,
pointIndex
++
,
coord
))
{
return
false
;
}
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
CameraTriggerNone
,
missionItemParent
);
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
firstWaypointTrigger
?
CameraTriggerOn
:
CameraTriggerNone
,
missionItemParent
);
firstWaypointTrigger
=
false
;
}
// Add polygon entry point
if
(
!
_nextTransectCoord
(
segment
,
pointIndex
++
,
coord
))
{
return
false
;
}
if
(
firstWaypointTrigger
)
{
cameraTrigger
=
CameraTriggerOn
;
}
else
{
cameraTrigger
=
_imagesEverywhere
()
||
!
_triggerCamera
()
?
CameraTriggerNone
:
(
_hoverAndCaptureEnabled
()
?
CameraTriggerHoverAndCapture
:
CameraTriggerOn
);
}
seqNum
=
_appendWaypointToMission
(
items
,
seqNum
,
coord
,
cameraTrigger
,
missionItemParent
);
firstWaypointTrigger
=
false
;
// Add internal hover and capture points
if
(
_hoverAndCaptureEnabled
())
{
...
...
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