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
80f39ce1
Commit
80f39ce1
authored
Mar 23, 2017
by
DonLakeFlyer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Add support for stop camera actions
parent
98b317d3
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
81 additions
and
7 deletions
+81
-7
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+2
-2
CameraSection.cc
src/MissionManager/CameraSection.cc
+62
-3
CameraSection.h
src/MissionManager/CameraSection.h
+4
-1
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+13
-1
No files found.
src/MissionManager/CameraSection.FactMetaData.json
View file @
80f39ce1
...
...
@@ -3,8 +3,8 @@
"name"
:
"CameraAction"
,
"shortDescription"
:
"Specify whether the camera should take photos or video"
,
"type"
:
"uint32"
,
"enumStrings"
:
"Continue current action,Take photos (time),Take photos (distance),
Take
video"
,
"enumValues"
:
"0,1,2,3"
,
"enumStrings"
:
"Continue current action,Take photos (time),Take photos (distance),
Stop taking photos,Start recording video,Stop recording
video"
,
"enumValues"
:
"0,1,2,3
,4,5
"
,
"defaultValue"
:
0
},
{
...
...
src/MissionManager/CameraSection.cc
View file @
80f39ce1
...
...
@@ -150,6 +150,37 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss
false
,
// isCurrentItem
missionItemParent
);
break
;
case
StopTakingVideo
:
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_VIDEO_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
// Camera ID
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
break
;
case
StopTakingPhotos
:
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_DO_SET_CAM_TRIGG_DIST
,
MAV_FRAME_MISSION
,
0
,
// Trigger distance = 0 means stop
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_IMAGE_STOP_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
// camera id
0
,
0
,
0
,
0
,
0
,
0
,
// param 2-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
break
;
}
if
(
item
)
{
items
.
append
(
item
);
...
...
@@ -204,14 +235,32 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
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
)
{
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
if
(
missionItem
.
param1
()
==
0
&&
scanIndex
<
visualItems
->
count
()
-
1
)
{
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
)
{
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
StopTakingPhotos
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
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
();
}
else
{
stopLooking
=
true
;
break
;
}
stopLooking
=
true
;
break
;
case
MAV_CMD_VIDEO_START_CAPTURE
:
...
...
@@ -224,6 +273,16 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
}
break
;
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
0
&&
missionItem
.
param5
()
==
0
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
StopTakingVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
else
{
stopLooking
=
true
;
}
break
;
default:
stopLooking
=
true
;
break
;
...
...
src/MissionManager/CameraSection.h
View file @
80f39ce1
...
...
@@ -23,11 +23,14 @@ class CameraSection : public QObject
public:
CameraSection
(
QObject
*
parent
=
NULL
);
// These nume values must match the json meta data
enum
CameraAction
{
CameraActionNone
,
TakePhotosIntervalTime
,
TakePhotoIntervalDistance
,
TakeVideo
StopTakingPhotos
,
TakeVideo
,
StopTakingVideo
};
Q_ENUMS
(
CameraAction
)
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
80f39ce1
...
...
@@ -991,7 +991,7 @@
"id"
:
2500
,
"rawName"
:
"MAV_CMD_VIDEO_START_CAPTURE"
,
"friendlyName"
:
"Start video capture"
,
"description"
:
"Start
taking video
."
,
"description"
:
"Start
video capture
."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Camera id"
,
...
...
@@ -1009,6 +1009,18 @@
"decimalPlaces"
:
0
}
},
{
"id"
:
2501
,
"rawName"
:
"MAV_CMD_VIDEO_STOP_CAPTURE"
,
"friendlyName"
:
"Stop video capture"
,
"description"
:
"Stop video capture."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Camera id"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
{
"id"
:
2800
,
"rawName"
:
"MAV_CMD_PANORAMA_CREATE", "friendlyName"
:
"Create panorama"
},
{
"id"
:
3000
,
...
...
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