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
673ee0f5
Commit
673ee0f5
authored
Jun 19, 2017
by
Don Gagne
Committed by
GitHub
Jun 19, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5310 from DonLakeFlyer/CameraSectionFixes
CameraSection: Scanning fixes plus unit test
parents
e9896fec
c999a76c
Changes
4
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
280 additions
and
127 deletions
+280
-127
CameraSection.cc
src/MissionManager/CameraSection.cc
+172
-103
CameraSection.h
src/MissionManager/CameraSection.h
+9
-0
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+96
-23
CameraSectionTest.h
src/MissionManager/CameraSectionTest.h
+3
-1
No files found.
src/MissionManager/CameraSection.cc
View file @
673ee0f5
This diff is collapsed.
Click to expand it.
src/MissionManager/CameraSection.h
View file @
673ee0f5
...
...
@@ -90,6 +90,15 @@ private slots:
void
_cameraActionChanged
(
void
);
private:
bool
_scanGimbal
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakePhoto
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakePhotosIntervalTime
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanStopTakingPhotos
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTriggerDistance
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanTakeVideo
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanStopTakingVideo
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_scanSetCameraMode
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
);
bool
_available
;
bool
_settingsSpecified
;
bool
_specifyGimbal
;
...
...
src/MissionManager/CameraSectionTest.cc
View file @
673ee0f5
...
...
@@ -8,6 +8,9 @@
****************************************************************************/
#include "CameraSectionTest.h"
#include "QGCApplication.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
CameraSectionTest
::
CameraSectionTest
(
void
)
:
_spyCamera
(
NULL
)
...
...
@@ -20,6 +23,8 @@ CameraSectionTest::CameraSectionTest(void)
,
_validStopVideoItem
(
NULL
)
,
_validStopDistanceItem
(
NULL
)
,
_validStopTimeItem
(
NULL
)
,
_validCameraPhotoModeItem
(
NULL
)
,
_validCameraVideoModeItem
(
NULL
)
{
}
...
...
@@ -116,6 +121,8 @@ void CameraSectionTest::cleanup(void)
delete
_validStopDistanceItem
;
delete
_validStopTimeItem
;
delete
_validTakePhotoItem
;
delete
_validCameraPhotoModeItem
;
delete
_validCameraVideoModeItem
;
SectionTest
::
cleanup
();
}
...
...
@@ -567,7 +574,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems
.
clear
();
scanIndex
=
0
;
/*
/*
MAV_CMD_DO_MOUNT_CONTROL
Mission Param #1 pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode.
Mission Param #2 roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode.
...
...
@@ -662,7 +669,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
visualItems
.
clear
();
scanIndex
=
0
;
/*
/*
MAV_CMD_SET_CAMERA_MODE
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Camera mode (0: photo mode, 1: video mode)
...
...
@@ -691,7 +698,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
_commonScanTest
(
_cameraSection
);
/*
/*
MAV_CMD_IMAGE_START_CAPTURE WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds)
...
...
@@ -762,7 +769,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
_commonScanTest
(
_cameraSection
);
/*
/*
MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set CAM_TRIGG_DIST for this flight
Mission Param #1 Camera trigger distance (meters)
Mission Param #2 Empty
...
...
@@ -852,7 +859,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
_commonScanTest
(
_cameraSection
);
/*
/*
MAV_CMD_VIDEO_START_CAPTURE WIP: Starts video capture (recording)
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Frames per second, set to -1 for highest framerate possible.
...
...
@@ -939,7 +946,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
_commonScanTest
(
_cameraSection
);
/*
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1 WIP: Camera ID
*/
...
...
@@ -1057,7 +1064,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
_commonScanTest
(
_cameraSection
);
/*
/*
MAV_CMD_IMAGE_START_CAPTURE Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds)
...
...
@@ -1118,8 +1125,42 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
visualItems
.
clear
();
}
void
CameraSectionTest
::
_
testScanForFullSection
(
void
)
void
CameraSectionTest
::
_
validateItemScan
(
SimpleMissionItem
*
validItem
)
{
QVERIFY
(
_cameraSection
->
settingsSpecified
());
if
(
validItem
==
_validGimbalItem
)
{
QCOMPARE
(
_cameraSection
->
specifyGimbal
(),
true
);
QCOMPARE
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
(),
validItem
->
missionItem
().
param1
());
QCOMPARE
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
(),
validItem
->
missionItem
().
param3
());
}
else
if
(
validItem
==
_validDistanceItem
)
{
QCOMPARE
(
_cameraSection
->
cameraAction
()
->
rawValue
().
toInt
(),
(
int
)
CameraSection
::
TakePhotoIntervalDistance
);
QCOMPARE
(
_cameraSection
->
cameraPhotoIntervalDistance
()
->
rawValue
().
toInt
(),
(
int
)
_validDistanceItem
->
missionItem
().
param1
());
}
else
if
(
validItem
==
_validTimeItem
)
{
}
else
if
(
validItem
==
_validStartVideoItem
)
{
}
else
if
(
validItem
==
_validStopVideoItem
)
{
}
else
if
(
validItem
==
_validTakePhotoItem
)
{
}
else
if
(
validItem
==
_validCameraPhotoModeItem
)
{
}
else
if
(
validItem
==
_validCameraVideoModeItem
)
{
}
}
void
CameraSectionTest
::
_resetSection
(
void
)
{
_cameraSection
->
gimbalYaw
()
->
setRawValue
(
0
);
_cameraSection
->
gimbalPitch
()
->
setRawValue
(
0
);
_cameraSection
->
setSpecifyGimbal
(
false
);
_cameraSection
->
cameraPhotoIntervalTime
()
->
setRawValue
(
0
);
_cameraSection
->
cameraPhotoIntervalDistance
()
->
setRawValue
(
0
);
_cameraSection
->
cameraAction
()
->
setRawValue
(
CameraSection
::
CameraActionNone
);
_cameraSection
->
cameraMode
()
->
setRawValue
(
CameraSection
::
CameraModePhoto
);
_cameraSection
->
setSpecifyCameraMode
(
false
);
}
/// Test that we can scan the commands associated with the camera section in various orders/combinations.
void
CameraSectionTest
::
_testScanForMultipleItems
(
void
)
{
MissionCommandTree
*
commandTree
=
qgcApp
()
->
toolbox
()
->
missionCommandTree
();
QCOMPARE
(
_cameraSection
->
available
(),
true
);
int
scanIndex
=
0
;
...
...
@@ -1127,19 +1168,51 @@ void CameraSectionTest::_testScanForFullSection(void)
_commonScanTest
(
_cameraSection
);
SimpleMissionItem
*
newValidGimbalItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
SimpleMissionItem
*
newValidDistanceItem
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
newValidGimbalItem
->
missionItem
()
=
_validGimbalItem
->
missionItem
();
newValidDistanceItem
->
missionItem
()
=
_validDistanceItem
->
missionItem
();
visualItems
.
append
(
newValidGimbalItem
);
visualItems
.
append
(
newValidDistanceItem
);
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
QCOMPARE
(
visualItems
.
count
(),
0
);
QCOMPARE
(
_cameraSection
->
settingsSpecified
(),
true
);
QCOMPARE
(
_cameraSection
->
specifyGimbal
(),
true
);
QCOMPARE
(
_cameraSection
->
cameraAction
()
->
rawValue
().
toInt
(),
(
int
)
CameraSection
::
TakePhotoIntervalDistance
);
QCOMPARE
(
_cameraSection
->
cameraPhotoIntervalDistance
()
->
rawValue
().
toInt
(),
(
int
)
_validDistanceItem
->
missionItem
().
param1
());
QCOMPARE
(
_cameraSection
->
gimbalPitch
()
->
rawValue
().
toDouble
(),
_validGimbalItem
->
missionItem
().
param1
());
QCOMPARE
(
_cameraSection
->
gimbalYaw
()
->
rawValue
().
toDouble
(),
_validGimbalItem
->
missionItem
().
param3
());
visualItems
.
clear
();
QList
<
SimpleMissionItem
*>
rgCameraItems
;
rgCameraItems
<<
_validGimbalItem
<<
_validCameraPhotoModeItem
<<
_validCameraVideoModeItem
;
QList
<
SimpleMissionItem
*>
rgActionItems
;
rgActionItems
<<
_validDistanceItem
<<
_validTimeItem
<<
_validStartVideoItem
<<
_validStopVideoItem
<<
_validTakePhotoItem
;
// Camera action followed by gimbal/mode
foreach
(
SimpleMissionItem
*
actionItem
,
rgActionItems
)
{
foreach
(
SimpleMissionItem
*
cameraItem
,
rgCameraItems
)
{
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
item1
->
missionItem
()
=
actionItem
->
missionItem
();
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
item2
->
missionItem
()
=
cameraItem
->
missionItem
();
visualItems
.
append
(
item1
);
visualItems
.
append
(
item2
);
qDebug
()
<<
commandTree
->
getUIInfo
(
_offlineVehicle
,
(
MAV_CMD
)
item1
->
command
())
->
rawName
()
<<
commandTree
->
getUIInfo
(
_offlineVehicle
,
(
MAV_CMD
)
item2
->
command
())
->
rawName
();;
scanIndex
=
0
;
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
_validateItemScan
(
cameraItem
);
_resetSection
();
visualItems
.
clearAndDeleteContents
();
}
}
// Gimbal/Mode followed by camera action
foreach
(
SimpleMissionItem
*
actionItem
,
rgCameraItems
)
{
foreach
(
SimpleMissionItem
*
cameraItem
,
rgActionItems
)
{
SimpleMissionItem
*
item1
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
item1
->
missionItem
()
=
actionItem
->
missionItem
();
SimpleMissionItem
*
item2
=
new
SimpleMissionItem
(
_offlineVehicle
,
this
);
item2
->
missionItem
()
=
cameraItem
->
missionItem
();
visualItems
.
append
(
item1
);
visualItems
.
append
(
item2
);
qDebug
()
<<
commandTree
->
getUIInfo
(
_offlineVehicle
,
(
MAV_CMD
)
item1
->
command
())
->
rawName
()
<<
commandTree
->
getUIInfo
(
_offlineVehicle
,
(
MAV_CMD
)
item2
->
command
())
->
rawName
();;
scanIndex
=
0
;
QCOMPARE
(
_cameraSection
->
scanForSection
(
&
visualItems
,
scanIndex
),
true
);
_validateItemScan
(
cameraItem
);
_resetSection
();
visualItems
.
clearAndDeleteContents
();
}
}
}
src/MissionManager/CameraSectionTest.h
View file @
673ee0f5
...
...
@@ -37,10 +37,12 @@ private slots:
void
_testScanForStopImageSection
(
void
);
void
_testScanForCameraModeSection
(
void
);
void
_testScanForTakePhotoSection
(
void
);
void
_testScanFor
FullSection
(
void
);
void
_testScanFor
MultipleItems
(
void
);
private:
void
_createSpy
(
CameraSection
*
cameraSection
,
MultiSignalSpy
**
cameraSpy
);
void
_validateItemScan
(
SimpleMissionItem
*
validItem
);
void
_resetSection
(
void
);
enum
{
specifyGimbalChangedIndex
=
0
,
...
...
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