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
5bdc29c8
Unverified
Commit
5bdc29c8
authored
Jun 08, 2018
by
Gus Grubba
Committed by
GitHub
Jun 08, 2018
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #6186 from mavlink/multiCamera
Ignoring Jenkins (Linux)
parents
6cfb0544
b97fbe87
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
63 additions
and
14 deletions
+63
-14
v2.0
libs/mavlink/include/mavlink/v2.0
+1
-1
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+5
-5
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+13
-0
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+15
-3
CameraPageWidget.qml
src/FlightMap/Widgets/CameraPageWidget.qml
+22
-4
QmlObjectListModel.cc
src/QmlControls/QmlObjectListModel.cc
+7
-1
No files found.
v2.0
@
033fa8e7
Subproject commit
653ac745a57794a38c831f1ff296066a2e09c09b
Subproject commit
033fa8e7a4a75a0c3f17cea57e3be8966e05f770
src/Camera/QGCCameraControl.cc
View file @
5bdc29c8
...
...
@@ -311,7 +311,7 @@ QGCCameraControl::takePhoto()
}
if
(
capturesPhotos
())
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
_compID
,
// Target component
MAV_CMD_IMAGE_START_CAPTURE
,
// Command id
false
,
// ShowError
0
,
// Reserved (Set to 0)
...
...
@@ -339,7 +339,7 @@ QGCCameraControl::stopTakePhoto()
}
if
(
capturesPhotos
())
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
_compID
,
// Target component
MAV_CMD_IMAGE_STOP_CAPTURE
,
// Command id
false
,
// ShowError
0
);
// Reserved (Set to 0)
...
...
@@ -361,7 +361,7 @@ QGCCameraControl::startVideo()
}
if
(
videoStatus
()
!=
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
_compID
,
// Target component
MAV_CMD_VIDEO_START_CAPTURE
,
// Command id
true
,
// ShowError
0
,
// Reserved (Set to 0)
...
...
@@ -378,7 +378,7 @@ QGCCameraControl::stopVideo()
qCDebug
(
CameraControlLog
)
<<
"stopVideo()"
;
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
_compID
,
// Target component
MAV_CMD_VIDEO_STOP_CAPTURE
,
// Command id
true
,
// ShowError
0
);
// Reserved (Set to 0)
...
...
@@ -399,7 +399,7 @@ QGCCameraControl::setVideoMode()
MAV_CMD_SET_CAMERA_MODE
,
// Command id
true
,
// ShowError
0
,
// Reserved (Set to 0)
CAM_MODE_VIDEO
);
// Camera mode (0: photo, 1: video)
CAM_MODE_VIDEO
);
// Camera mode (0: photo, 1: video)
_setCameraMode
(
CAM_MODE_VIDEO
);
}
}
...
...
src/Camera/QGCCameraManager.cc
View file @
5bdc29c8
...
...
@@ -15,6 +15,7 @@ QGCCameraManager::QGCCameraManager(Vehicle *vehicle)
:
_vehicle
(
vehicle
)
,
_vehicleReadyState
(
false
)
,
_currentTask
(
0
)
,
_currentCamera
(
0
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
qCDebug
(
CameraManagerLog
)
<<
"QGCCameraManager Created"
;
...
...
@@ -27,6 +28,16 @@ QGCCameraManager::~QGCCameraManager()
{
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
setCurrentCamera
(
int
sel
)
{
if
(
sel
!=
_currentCamera
&&
sel
>=
0
&&
sel
<
_cameras
.
count
())
{
_currentCamera
=
sel
;
emit
currentCameraChanged
();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_vehicleReady
(
bool
ready
)
...
...
@@ -121,7 +132,9 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
if
(
pCamera
)
{
QQmlEngine
::
setObjectOwnership
(
pCamera
,
QQmlEngine
::
CppOwnership
);
_cameras
.
append
(
pCamera
);
_cameraLabels
<<
pCamera
->
modelName
();
emit
camerasChanged
();
emit
cameraLabelsChanged
();
}
}
}
...
...
src/Camera/QGCCameraManager.h
View file @
5bdc29c8
...
...
@@ -25,13 +25,23 @@ public:
QGCCameraManager
(
Vehicle
*
vehicle
);
virtual
~
QGCCameraManager
();
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QStringList
cameraLabels
READ
cameraLabels
NOTIFY
cameraLabelsChanged
)
Q_PROPERTY
(
int
currentCamera
READ
currentCamera
WRITE
setCurrentCamera
NOTIFY
currentCameraChanged
)
//-- Return a list of cameras provided by this vehicle
virtual
QmlObjectListModel
*
cameras
()
{
return
&
_cameras
;
}
virtual
QmlObjectListModel
*
cameras
()
{
return
&
_cameras
;
}
//-- Camera names to show the user (for selection)
virtual
QStringList
cameraLabels
()
{
return
_cameraLabels
;
}
//-- Current selected camera
virtual
int
currentCamera
()
{
return
_currentCamera
;
}
//-- Set current camera
virtual
void
setCurrentCamera
(
int
sel
);
signals:
void
camerasChanged
();
void
camerasChanged
();
void
cameraLabelsChanged
();
void
currentCameraChanged
();
protected
slots
:
virtual
void
_vehicleReady
(
bool
ready
);
...
...
@@ -53,5 +63,7 @@ protected:
bool
_vehicleReadyState
;
int
_currentTask
;
QmlObjectListModel
_cameras
;
QStringList
_cameraLabels
;
QMap
<
int
,
bool
>
_cameraInfoRequested
;
int
_currentCamera
;
};
src/FlightMap/Widgets/CameraPageWidget.qml
View file @
5bdc29c8
...
...
@@ -33,10 +33,10 @@ Column {
property
var
_activeVehicle
:
QGroundControl
.
multiVehicleManager
.
activeVehicle
property
var
_dynamicCameras
:
_activeVehicle
?
_activeVehicle
.
dynamicCameras
:
null
property
bool
_isCamera
:
_dynamicCameras
?
_dynamicCameras
.
cameras
.
count
>
0
:
false
property
var
_camera
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
0
)
:
null
// Single camera support for the time being
property
bool
_cameraModeUndefined
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
0
).
cameraMode
===
QGCCameraControl
.
CAMERA_MODE_UNDEFINED
:
true
property
bool
_cameraVideoMode
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
0
).
cameraMode
===
1
:
false
property
bool
_cameraPhotoMode
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
0
).
cameraMode
===
0
:
false
property
var
_camera
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
)
:
null
property
bool
_cameraModeUndefined
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
).
cameraMode
===
QGCCameraControl
.
CAMERA_MODE_UNDEFINED
:
true
property
bool
_cameraVideoMode
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
).
cameraMode
===
1
:
false
property
bool
_cameraPhotoMode
:
_isCamera
?
_dynamicCameras
.
cameras
.
get
(
_curCameraIndex
).
cameraMode
===
0
:
false
property
bool
_cameraPhotoIdle
:
_isCamera
&&
_camera
.
photoStatus
===
QGCCameraControl
.
PHOTO_CAPTURE_IDLE
property
bool
_cameraElapsedMode
:
_isCamera
&&
_camera
.
cameraMode
===
QGCCameraControl
.
CAM_MODE_PHOTO
&&
_camera
.
photoMode
===
QGCCameraControl
.
PHOTO_CAPTURE_TIMELAPSE
property
real
_spacers
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
...
...
@@ -46,6 +46,7 @@ Column {
property
bool
_hasModes
:
_isCamera
&&
_camera
&&
_camera
.
hasModes
property
bool
_videoRecording
:
_camera
&&
_camera
.
videoStatus
===
QGCCameraControl
.
VIDEO_CAPTURE_STATUS_RUNNING
property
bool
_noStorage
:
_camera
&&
_camera
.
storageTotal
===
0
property
int
_curCameraIndex
:
_dynamicCameras
?
_dynamicCameras
.
currentCamera
:
0
function
showSettings
()
{
qgcView
.
showDialog
(
cameraSettings
,
_cameraVideoMode
?
qsTr
(
"
Video Settings
"
)
:
qsTr
(
"
Camera Settings
"
),
70
,
StandardButton
.
Ok
)
...
...
@@ -202,6 +203,23 @@ Column {
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
spacing
:
_margins
Row
{
visible
:
_isCamera
spacing
:
ScreenTools
.
defaultFontPixelWidth
anchors.horizontalCenter
:
parent
.
horizontalCenter
QGCLabel
{
text
:
qsTr
(
"
Camera Selector:
"
)
width
:
_labelFieldWidth
anchors.verticalCenter
:
parent
.
verticalCenter
}
QGCComboBox
{
id
:
cameraSelector
model
:
_isCamera
?
_dynamicCameras
.
cameraLabels
:
[]
width
:
_editFieldWidth
onActivated
:
_dynamicCameras
.
currentCamera
=
index
currentIndex
:
_dynamicCameras
.
currentCamera
}
}
//-------------------------------------------
//-- Camera Settings
Repeater
{
...
...
src/QmlControls/QmlObjectListModel.cc
View file @
5bdc29c8
...
...
@@ -45,7 +45,7 @@ QVariant QmlObjectListModel::data(const QModelIndex &index, int role) const
return
QVariant
();
}
if
(
index
.
row
()
>=
_objectList
.
count
())
{
if
(
index
.
row
()
<
0
||
index
.
row
()
>=
_objectList
.
count
())
{
return
QVariant
();
}
...
...
@@ -118,11 +118,17 @@ bool QmlObjectListModel::removeRows(int position, int rows, const QModelIndex& p
QObject
*
QmlObjectListModel
::
operator
[](
int
index
)
{
if
(
index
<
0
||
index
>=
_objectList
.
count
())
{
return
NULL
;
}
return
_objectList
[
index
];
}
const
QObject
*
QmlObjectListModel
::
operator
[](
int
index
)
const
{
if
(
index
<
0
||
index
>=
_objectList
.
count
())
{
return
NULL
;
}
return
_objectList
[
index
];
}
...
...
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