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
73cfd557
Unverified
Commit
73cfd557
authored
Apr 06, 2018
by
Gus Grubba
Committed by
GitHub
Apr 06, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6308 from mavlink/videoUpdates
Set video capture status for missions
parents
9b9f4b7f
43228ad9
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
29 additions
and
35 deletions
+29
-35
MavCmdInfoCommon.json
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
+5
-0
CameraSection.cc
src/MissionManager/CameraSection.cc
+6
-6
CameraSection.h
src/MissionManager/CameraSection.h
+2
-0
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+9
-8
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+7
-21
No files found.
src/FirmwarePlugin/PX4/MavCmdInfoCommon.json
View file @
73cfd557
...
@@ -18,6 +18,11 @@
...
@@ -18,6 +18,11 @@
"id"
:
201
,
"id"
:
201
,
"comment"
:
"MAV_CMD_DO_SET_ROI"
,
"comment"
:
"MAV_CMD_DO_SET_ROI"
,
"paramRemove"
:
"1,2,3"
"paramRemove"
:
"1,2,3"
},
{
"id"
:
2500
,
"comment"
:
"MAV_CMD_VIDEO_START_CAPTURE"
,
"paramRemove"
:
"2"
}
}
]
]
}
}
src/MissionManager/CameraSection.cc
View file @
73cfd557
...
@@ -180,11 +180,11 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
...
@@ -180,11 +180,11 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item
=
new
MissionItem
(
nextSequenceNumber
++
,
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
0
,
// Reserved (Set to 0)
0
,
// Reserved (Set to 0)
0
,
// No CAMERA_CAPTURE_STATUS streaming
VIDEO_CAPTURE_STATUS_INTERVAL
,
// CAMERA_CAPTURE_STATUS (default to every 5 seconds)
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autoContinue
true
,
// autoContinue
false
,
// isCurrentItem
false
,
// isCurrentItem
missionItemParent
);
missionItemParent
);
break
;
break
;
...
@@ -360,7 +360,7 @@ bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanInde
...
@@ -360,7 +360,7 @@ bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanInde
if
(
item
)
{
if
(
item
)
{
MissionItem
&
missionItem
=
item
->
missionItem
();
MissionItem
&
missionItem
=
item
->
missionItem
();
if
((
MAV_CMD
)
item
->
command
()
==
MAV_CMD_VIDEO_START_CAPTURE
)
{
if
((
MAV_CMD
)
item
->
command
()
==
MAV_CMD_VIDEO_START_CAPTURE
)
{
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
)
{
if
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
VIDEO_CAPTURE_STATUS_INTERVAL
)
{
cameraAction
()
->
setRawValue
(
TakeVideo
);
cameraAction
()
->
setRawValue
(
TakeVideo
);
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
return
true
;
return
true
;
...
...
src/MissionManager/CameraSection.h
View file @
73cfd557
...
@@ -14,6 +14,8 @@
...
@@ -14,6 +14,8 @@
#include "MissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "Fact.h"
#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds
class
CameraSection
:
public
Section
class
CameraSection
:
public
Section
{
{
Q_OBJECT
Q_OBJECT
...
...
src/MissionManager/CameraSectionTest.cc
View file @
73cfd557
...
@@ -70,7 +70,7 @@ void CameraSectionTest::init(void)
...
@@ -70,7 +70,7 @@ void CameraSectionTest::init(void)
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_CMD_VIDEO_START_CAPTURE
,
MAV_FRAME_MISSION
,
MAV_FRAME_MISSION
,
0
,
// Reserved (Set to 0)
0
,
// Reserved (Set to 0)
0
,
// No CAMERA_CAPTURE_STATUS streaming
VIDEO_CAPTURE_STATUS_INTERVAL
,
// CAMERA_CAPTURE_STATUS (default to every 5 seconds)
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
true
,
// autocontinue
false
),
// isCurrentItem
false
),
// isCurrentItem
...
@@ -896,13 +896,6 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
...
@@ -896,13 +896,6 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
visualItems
.
clear
();
visualItems
.
clear
();
invalidSimpleItem
.
missionItem
()
=
_validStartVideoItem
->
missionItem
();
invalidSimpleItem
.
missionItem
().
setParam2
(
10
);
// must be 0
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
visualItems
.
count
(),
1
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
visualItems
.
clear
();
}
}
void
CameraSectionTest
::
_testScanForStopVideoSection
(
void
)
void
CameraSectionTest
::
_testScanForStopVideoSection
(
void
)
...
@@ -938,6 +931,14 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
...
@@ -938,6 +931,14 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
QCOMPARE
(
visualItems
.
count
(),
1
);
QCOMPARE
(
visualItems
.
count
(),
1
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
visualItems
.
clear
();
visualItems
.
clear
();
invalidSimpleItem
.
missionItem
()
=
_validStartVideoItem
->
missionItem
();
invalidSimpleItem
.
missionItem
().
setParam2
(
VIDEO_CAPTURE_STATUS_INTERVAL
+
1
);
// must be VIDEO_CAPTURE_STATUS_INTERVAL
visualItems
.
append
(
&
invalidSimpleItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
false
);
QCOMPARE
(
visualItems
.
count
(),
1
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
false
);
visualItems
.
clear
();
}
}
void
CameraSectionTest
::
_testScanForStopImageSection
(
void
)
void
CameraSectionTest
::
_testScanForStopImageSection
(
void
)
...
...
src/MissionManager/MavCmdInfoCommon.json
View file @
73cfd557
...
@@ -1005,11 +1005,6 @@
...
@@ -1005,11 +1005,6 @@
"friendlyName"
:
"Start image capture"
,
"friendlyName"
:
"Start image capture"
,
"description"
:
"Start taking one or more photos."
,
"description"
:
"Start taking one or more photos."
,
"category"
:
"Camera"
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Reserved"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"param2"
:
{
"label"
:
"Interval"
,
"label"
:
"Interval"
,
"default"
:
0
,
"default"
:
0
,
...
@@ -1027,12 +1022,7 @@
...
@@ -1027,12 +1022,7 @@
"rawName"
:
"MAV_CMD_IMAGE_STOP_CAPTURE"
,
"rawName"
:
"MAV_CMD_IMAGE_STOP_CAPTURE"
,
"friendlyName"
:
"Stop image capture"
,
"friendlyName"
:
"Stop image capture"
,
"description"
:
"Stop taking photos."
,
"description"
:
"Stop taking photos."
,
"category"
:
"Camera"
,
"category"
:
"Camera"
"param1"
:
{
"label"
:
"Reserved"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
},
{
"id"
:
2003
,
"rawName"
:
"MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName"
:
"Trigger control"
},
{
"id"
:
2003
,
"rawName"
:
"MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName"
:
"Trigger control"
},
{
{
...
@@ -1041,10 +1031,11 @@
...
@@ -1041,10 +1031,11 @@
"friendlyName"
:
"Start video capture"
,
"friendlyName"
:
"Start video capture"
,
"description"
:
"Start video capture."
,
"description"
:
"Start video capture."
,
"category"
:
"Camera"
,
"category"
:
"Camera"
,
"param1"
:
{
"param2"
:
{
"label"
:
"Reserved"
,
"label"
:
"Status Frequency"
,
"default"
:
0
,
"default"
:
0.2
,
"decimalPlaces"
:
0
"units"
:
"Hz"
,
"decimalPlaces"
:
2
}
}
},
},
{
{
...
@@ -1052,12 +1043,7 @@
...
@@ -1052,12 +1043,7 @@
"rawName"
:
"MAV_CMD_VIDEO_STOP_CAPTURE"
,
"rawName"
:
"MAV_CMD_VIDEO_STOP_CAPTURE"
,
"friendlyName"
:
"Stop video capture"
,
"friendlyName"
:
"Stop video capture"
,
"description"
:
"Stop video capture."
,
"description"
:
"Stop video capture."
,
"category"
:
"Camera"
,
"category"
:
"Camera"
"param1"
:
{
"label"
:
"Reserved"
,
"default"
:
0
,
"decimalPlaces"
:
0
}
},
},
{
"id"
:
2800
,
"rawName"
:
"MAV_CMD_PANORAMA_CREATE", "friendlyName"
:
"Create panorama"
},
{
"id"
:
2800
,
"rawName"
:
"MAV_CMD_PANORAMA_CREATE", "friendlyName"
:
"Create panorama"
},
{
{
...
...
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