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
0446c70d
Commit
0446c70d
authored
Aug 16, 2017
by
Gus Grubba
Committed by
GitHub
Aug 16, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5580 from DonLakeFlyer/SurveyMode
CAMERA_MODE_IMAGE_SURVEY support
parents
f10ac35f
e1fb25c6
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
48 additions
and
36 deletions
+48
-36
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+2
-2
CameraSection.cc
src/MissionManager/CameraSection.cc
+1
-1
CameraSection.h
src/MissionManager/CameraSection.h
+0
-6
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+40
-18
CameraSectionTest.h
src/MissionManager/CameraSectionTest.h
+1
-0
MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoCommon.json
+3
-8
MissionController.cc
src/MissionManager/MissionController.cc
+1
-1
No files found.
src/MissionManager/CameraSection.FactMetaData.json
View file @
0446c70d
...
...
@@ -49,8 +49,8 @@
"name"
:
"CameraMode"
,
"shortDescription"
:
"Specify whether the camera should switch to photo or video mode"
,
"type"
:
"uint32"
,
"enumStrings"
:
"Take photos,Record video"
,
"enumValues"
:
"0,1"
,
"enumStrings"
:
"Take photos,Record video
,Survey photo mode
"
,
"enumValues"
:
"0,1
,2
"
,
"defaultValue"
:
0
}
]
src/MissionManager/CameraSection.cc
View file @
0446c70d
...
...
@@ -392,7 +392,7 @@ bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scan
MissionItem
&
missionItem
=
item
->
missionItem
();
if
((
MAV_CMD
)
item
->
command
()
==
MAV_CMD_SET_CAMERA_MODE
)
{
// We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
if
(
missionItem
.
param1
()
==
0
&&
(
missionItem
.
param2
()
==
0
||
missionItem
.
param2
()
==
1
)
&&
qIsNaN
(
missionItem
.
param3
()))
{
if
(
missionItem
.
param1
()
==
0
&&
(
missionItem
.
param2
()
==
CAMERA_MODE_IMAGE
||
missionItem
.
param2
()
==
CAMERA_MODE_VIDEO
||
missionItem
.
param2
()
==
CAMERA_MODE_IMAGE_SURVEY
)
&&
qIsNaN
(
missionItem
.
param3
()))
{
setSpecifyCameraMode
(
true
);
cameraMode
()
->
setRawValue
(
missionItem
.
param2
());
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
...
...
src/MissionManager/CameraSection.h
View file @
0446c70d
...
...
@@ -34,12 +34,6 @@ public:
};
Q_ENUMS
(
CameraAction
)
enum
CameraMode
{
CameraModePhoto
,
CameraModeVideo
};
Q_ENUMS
(
CameraMode
)
Q_PROPERTY
(
bool
specifyGimbal
READ
specifyGimbal
WRITE
setSpecifyGimbal
NOTIFY
specifyGimbalChanged
)
Q_PROPERTY
(
Fact
*
gimbalPitch
READ
gimbalPitch
CONSTANT
)
Q_PROPERTY
(
Fact
*
gimbalYaw
READ
gimbalYaw
CONSTANT
)
...
...
src/MissionManager/CameraSectionTest.cc
View file @
0446c70d
...
...
@@ -13,18 +13,19 @@
#include "MissionCommandUIInfo.h"
CameraSectionTest
::
CameraSectionTest
(
void
)
:
_spyCamera
(
NULL
)
,
_spySection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_validGimbalItem
(
NULL
)
,
_validDistanceItem
(
NULL
)
,
_validTimeItem
(
NULL
)
,
_validStartVideoItem
(
NULL
)
,
_validStopVideoItem
(
NULL
)
,
_validStopDistanceItem
(
NULL
)
,
_validStopTimeItem
(
NULL
)
,
_validCameraPhotoModeItem
(
NULL
)
,
_validCameraVideoModeItem
(
NULL
)
:
_spyCamera
(
NULL
)
,
_spySection
(
NULL
)
,
_cameraSection
(
NULL
)
,
_validGimbalItem
(
NULL
)
,
_validDistanceItem
(
NULL
)
,
_validTimeItem
(
NULL
)
,
_validStartVideoItem
(
NULL
)
,
_validStopVideoItem
(
NULL
)
,
_validStopDistanceItem
(
NULL
)
,
_validStopTimeItem
(
NULL
)
,
_validCameraPhotoModeItem
(
NULL
)
,
_validCameraVideoModeItem
(
NULL
)
,
_validCameraSurveyPhotoModeItem
(
NULL
)
{
}
...
...
@@ -83,7 +84,7 @@ void CameraSectionTest::init(void)
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
// Reserved (Set to 0)
C
ameraSection
::
CameraModePhoto
,
C
AMERA_MODE_IMAGE
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
false
),
// isCurrentItem
...
...
@@ -93,11 +94,21 @@ void CameraSectionTest::init(void)
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
// Reserved (Set to 0)
C
ameraSection
::
CameraModeVideo
,
C
AMERA_MODE_VIDEO
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
false
),
// isCurrentItem
this
);
_validCameraSurveyPhotoModeItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
MissionItem
(
0
,
// sequence number
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
// Reserved (Set to 0)
CAMERA_MODE_IMAGE_SURVEY
,
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 reserved
true
,
// autocontinue
false
),
// isCurrentItem
this
);
_validTakePhotoItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
MissionItem
(
0
,
MAV_CMD_IMAGE_START_CAPTURE
,
...
...
@@ -125,6 +136,7 @@ void CameraSectionTest::cleanup(void)
delete
_validTakePhotoItem
;
delete
_validCameraPhotoModeItem
;
delete
_validCameraVideoModeItem
;
delete
_validCameraSurveyPhotoModeItem
;
SectionTest
::
cleanup
();
}
...
...
@@ -453,7 +465,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
// Test specifyCameraMode
_cameraSection
->
setSpecifyCameraMode
(
true
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
ameraSection
::
CameraModePhoto
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
AMERA_MODE_IMAGE
);
_cameraSection
->
appendSectionItems
(
rgMissionItems
,
this
,
seqNum
);
QCOMPARE
(
rgMissionItems
.
count
(),
1
);
QCOMPARE
(
seqNum
,
1
);
...
...
@@ -463,7 +475,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
seqNum
=
0
;
_cameraSection
->
setSpecifyCameraMode
(
true
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
ameraSection
::
CameraModeVideo
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
AMERA_MODE_VIDEO
);
_cameraSection
->
appendSectionItems
(
rgMissionItems
,
this
,
seqNum
);
QCOMPARE
(
rgMissionItems
.
count
(),
1
);
QCOMPARE
(
seqNum
,
1
);
...
...
@@ -472,6 +484,16 @@ void CameraSectionTest::_testAppendSectionItems(void)
rgMissionItems
.
clear
();
seqNum
=
0
;
_cameraSection
->
setSpecifyCameraMode
(
true
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
CAMERA_MODE_IMAGE_SURVEY
);
_cameraSection
->
appendSectionItems
(
rgMissionItems
,
this
,
seqNum
);
QCOMPARE
(
rgMissionItems
.
count
(),
1
);
QCOMPARE
(
seqNum
,
1
);
_missionItemsEqual
(
*
rgMissionItems
[
0
],
_validCameraSurveyPhotoModeItem
->
missionItem
());
_cameraSection
->
setSpecifyCameraMode
(
false
);
rgMissionItems
.
clear
();
seqNum
=
0
;
// Test camera actions
_cameraSection
->
cameraAction
()
->
setRawValue
(
CameraSection
::
TakePhoto
);
...
...
@@ -539,7 +561,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
_cameraSection
->
cameraAction
()
->
setRawValue
(
CameraSection
::
TakePhotosIntervalTime
);
_cameraSection
->
cameraPhotoIntervalTime
()
->
setRawValue
(
_validTimeItem
->
missionItem
().
param2
());
_cameraSection
->
setSpecifyCameraMode
(
true
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
ameraSection
::
CameraModePhoto
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
AMERA_MODE_IMAGE
);
_cameraSection
->
appendSectionItems
(
rgMissionItems
,
this
,
seqNum
);
QCOMPARE
(
rgMissionItems
.
count
(),
3
);
QCOMPARE
(
seqNum
,
3
);
...
...
@@ -995,7 +1017,7 @@ void CameraSectionTest::_resetSection(void)
_cameraSection
->
cameraPhotoIntervalTime
()
->
setRawValue
(
0
);
_cameraSection
->
cameraPhotoIntervalDistance
()
->
setRawValue
(
0
);
_cameraSection
->
cameraAction
()
->
setRawValue
(
CameraSection
::
CameraActionNone
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
ameraSection
::
CameraModePhoto
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
C
AMERA_MODE_IMAGE
);
_cameraSection
->
setSpecifyCameraMode
(
false
);
}
...
...
src/MissionManager/CameraSectionTest.h
View file @
0446c70d
...
...
@@ -72,5 +72,6 @@ private:
SimpleMissionItem
*
_validStopTimeItem
;
SimpleMissionItem
*
_validCameraPhotoModeItem
;
SimpleMissionItem
*
_validCameraVideoModeItem
;
SimpleMissionItem
*
_validCameraSurveyPhotoModeItem
;
SimpleMissionItem
*
_validTakePhotoItem
;
};
src/MissionManager/MavCmdInfoCommon.json
View file @
0446c70d
...
...
@@ -971,17 +971,12 @@
"id"
:
530
,
"rawName"
:
"MAV_CMD_SET_CAMERA_MODE"
,
"friendlyName"
:
"Set camera modes"
,
"description"
:
"Set camera photo, video
, audio
modes."
,
"description"
:
"Set camera photo, video modes."
,
"category"
:
"Camera"
,
"param1"
:
{
"label"
:
"Reserved"
,
"default"
:
0
,
"decimalPlaces"
:
0
},
"param2"
:
{
"label"
:
"Mode"
,
"enumStrings"
:
"Take photos,Record video"
,
"enumValues"
:
"0,1"
,
"enumStrings"
:
"Take photos,Record video
,Survey photo mode
"
,
"enumValues"
:
"0,1
,2
"
,
"default"
:
0
}
},
...
...
src/MissionManager/MissionController.cc
View file @
0446c70d
...
...
@@ -327,7 +327,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
// Set camera to photo mode (leave alone if user already specified)
if
(
cameraSection
->
cameraModeSupported
()
&&
!
cameraSection
->
specifyCameraMode
())
{
cameraSection
->
setSpecifyCameraMode
(
true
);
cameraSection
->
cameraMode
()
->
setRawValue
(
0
);
cameraSection
->
cameraMode
()
->
setRawValue
(
CAMERA_MODE_IMAGE_SURVEY
);
}
// Point gimbal straight down
if
(
_controllerVehicle
->
firmwarePlugin
()
->
hasGimbal
(
_controllerVehicle
,
rollSupported
,
pitchSupported
,
yawSupported
)
&&
pitchSupported
)
{
...
...
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