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
9341d245
Commit
9341d245
authored
Jun 13, 2017
by
Don Gagne
Committed by
GitHub
Jun 13, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5289 from DonLakeFlyer/TakePhotoPlus
Camera Section: Add support for Take Photo
parents
04a290e8
9e94dae6
Changes
7
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
196 additions
and
62 deletions
+196
-62
CameraSection.FactMetaData.json
src/MissionManager/CameraSection.FactMetaData.json
+2
-2
CameraSection.cc
src/MissionManager/CameraSection.cc
+40
-16
CameraSection.h
src/MissionManager/CameraSection.h
+11
-3
CameraSectionTest.cc
src/MissionManager/CameraSectionTest.cc
+136
-39
CameraSectionTest.h
src/MissionManager/CameraSectionTest.h
+2
-0
SurveyMissionItem.cc
src/MissionManager/SurveyMissionItem.cc
+3
-2
SurveyMissionItemTest.cc
src/MissionManager/SurveyMissionItemTest.cc
+2
-0
No files found.
src/MissionManager/CameraSection.FactMetaData.json
View file @
9341d245
...
...
@@ -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),Stop taking photos,Start recording video,Stop recording video"
,
"enumValues"
:
"0,1,2,3,4,5"
,
"enumStrings"
:
"Continue current action,Take photo
,Take photo
s (time),Take photos (distance),Stop taking photos,Start recording video,Stop recording video"
,
"enumValues"
:
"0,
6,
1,2,3,4,5"
,
"defaultValue"
:
0
},
{
...
...
src/MissionManager/CameraSection.cc
View file @
9341d245
...
...
@@ -115,6 +115,19 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
{
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForSection
if
(
_specifyCameraMode
)
{
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
// camera id, all cameras
_cameraModeFact
.
rawValue
().
toDouble
(),
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
if
(
_specifyGimbal
)
{
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_DO_MOUNT_CONTROL
,
...
...
@@ -203,24 +216,26 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
false
,
// isCurrentItem
missionItemParent
);
break
;
case
TakePhoto
:
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_IMAGE_START_CAPTURE
,
MAV_FRAME_MISSION
,
0
,
// camera id = 0, all cameras
0
,
// Interval (none)
1
,
// Take 1 photo
-
1
,
// Max horizontal resolution
-
1
,
// Max vertical resolution
0
,
0
,
// param 6-7 not used
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
break
;
}
if
(
item
)
{
items
.
append
(
item
);
}
}
if
(
_specifyCameraMode
)
{
MissionItem
*
item
=
new
MissionItem
(
nextSequenceNumber
++
,
MAV_CMD_SET_CAMERA_MODE
,
MAV_FRAME_MISSION
,
0
,
// camera id, all cameras
_cameraModeFact
.
rawValue
().
toDouble
(),
NAN
,
NAN
,
NAN
,
NAN
,
NAN
,
// param 3-7 unused
true
,
// autoContinue
false
,
// isCurrentItem
missionItemParent
);
items
.
append
(
item
);
}
}
bool
CameraSection
::
scanForSection
(
QmlObjectListModel
*
visualItems
,
int
scanIndex
)
...
...
@@ -264,10 +279,19 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanInde
break
;
case
MAV_CMD_IMAGE_START_CAPTURE
:
if
(
!
foundCameraAction
&&
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
>=
1
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
-
1
&&
missionItem
.
param5
()
==
-
1
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
{
// This could possibly be TakePhotosIntervalTime or TakePhoto
if
(
!
foundCameraAction
&&
// TakePhotosIntervalTime matching
((
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
>=
1
&&
missionItem
.
param3
()
==
0
&&
missionItem
.
param4
()
==
-
1
&&
missionItem
.
param5
()
==
-
1
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)
||
// TakePhoto matching
(
missionItem
.
param1
()
==
0
&&
missionItem
.
param2
()
==
0
&&
missionItem
.
param3
()
==
1
&&
missionItem
.
param4
()
==
-
1
&&
missionItem
.
param5
()
==
-
1
&&
missionItem
.
param6
()
==
0
&&
missionItem
.
param7
()
==
0
)))
{
foundCameraAction
=
true
;
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param2
());
if
(
missionItem
.
param2
()
==
0
)
{
cameraAction
()
->
setRawValue
(
TakePhoto
);
}
else
{
cameraAction
()
->
setRawValue
(
TakePhotosIntervalTime
);
cameraPhotoIntervalTime
()
->
setRawValue
(
missionItem
.
param2
());
}
visualItems
->
removeAt
(
scanIndex
)
->
deleteLater
();
}
else
{
stopLooking
=
true
;
...
...
src/MissionManager/CameraSection.h
View file @
9341d245
...
...
@@ -21,17 +21,25 @@ class CameraSection : public Section
public:
CameraSection
(
Vehicle
*
vehicle
,
QObject
*
parent
=
NULL
);
// These nume values must match the json meta data
// These enum values must match the json meta data
enum
CameraAction
{
CameraActionNone
,
TakePhotosIntervalTime
,
TakePhotoIntervalDistance
,
StopTakingPhotos
,
TakeVideo
,
StopTakingVideo
};
StopTakingVideo
,
TakePhoto
};
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 @
9341d245
This diff is collapsed.
Click to expand it.
src/MissionManager/CameraSectionTest.h
View file @
9341d245
...
...
@@ -36,6 +36,7 @@ private slots:
void
_testScanForStopVideoSection
(
void
);
void
_testScanForStopImageSection
(
void
);
void
_testScanForCameraModeSection
(
void
);
void
_testScanForTakePhotoSection
(
void
);
void
_testScanForFullSection
(
void
);
private:
...
...
@@ -69,4 +70,5 @@ private:
SimpleMissionItem
*
_validStopTimeItem
;
SimpleMissionItem
*
_validCameraPhotoModeItem
;
SimpleMissionItem
*
_validCameraVideoModeItem
;
SimpleMissionItem
*
_validTakePhotoItem
;
};
src/MissionManager/SurveyMissionItem.cc
View file @
9341d245
...
...
@@ -108,9 +108,10 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
{
_editorQml
=
"qrc:/qml/SurveyItemEditor.qml"
;
// If the user hasn't changed turnaround from the default (which is a fixed wing default) and we are multi-rotor set the multi-rotor default.
// NULL check since object creation during unit testing passes NULL for vehicle
if
(
_vehicle
&&
_vehicle
->
multiRotor
())
{
_turnaroundDistFact
.
setRawValue
(
0
);
if
(
_vehicle
&&
_vehicle
->
multiRotor
()
&&
_turnaroundDistFact
.
rawValue
().
toDouble
()
==
_turnaroundDistFact
.
rawDefaultValue
().
toDouble
()
)
{
_turnaroundDistFact
.
setRawValue
(
5
);
}
connect
(
&
_gridSpacingFact
,
&
Fact
::
valueChanged
,
this
,
&
SurveyMissionItem
::
_generateGrid
);
...
...
src/MissionManager/SurveyMissionItemTest.cc
View file @
9341d245
...
...
@@ -33,6 +33,8 @@ void SurveyMissionItemTest::init(void)
_offlineVehicle
=
new
Vehicle
(
MAV_AUTOPILOT_PX4
,
MAV_TYPE_QUADROTOR
,
qgcApp
()
->
toolbox
()
->
firmwarePluginManager
(),
this
);
_surveyItem
=
new
SurveyMissionItem
(
_offlineVehicle
,
this
);
_surveyItem
->
setTurnaroundDist
(
0
);
// Unit test written for no turnaround distance
_surveyItem
->
setDirty
(
false
);
_mapPolygon
=
_surveyItem
->
mapPolygon
();
// It's important to check that the right signals are emitted at the right time since that drives ui change.
...
...
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