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
5793c550
Commit
5793c550
authored
Oct 23, 2017
by
Gus Grubba
Committed by
GitHub
Oct 23, 2017
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #5777 from mavlink/cameraModes
Camera Modes
parents
dcb0f23e
bd61c5eb
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
111 additions
and
16 deletions
+111
-16
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+81
-10
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+30
-6
No files found.
src/Camera/QGCCameraControl.cc
View file @
5793c550
...
...
@@ -52,6 +52,10 @@ static const char* kValue = "value";
static
const
char
*
kVendor
=
"vendor"
;
static
const
char
*
kVersion
=
"version"
;
static
const
char
*
kPhotoMode
=
"PhotoMode"
;
static
const
char
*
kPhotoLapse
=
"PhotoLapse"
;
static
const
char
*
kPhotoLapseCount
=
"PhotoLapseCount"
;
//-----------------------------------------------------------------------------
static
bool
read_attribute
(
QDomNode
&
node
,
const
char
*
tagName
,
bool
&
target
)
...
...
@@ -123,6 +127,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
,
_storageTotal
(
0
)
,
_netManager
(
NULL
)
,
_cameraMode
(
CAM_MODE_UNDEFINED
)
,
_photoMode
(
PHOTO_CAPTURE_SINGLE
)
,
_photoLapse
(
1.0
)
,
_photoLapseCount
(
0
)
,
_video_status
(
VIDEO_CAPTURE_STATUS_UNDEFINED
)
,
_photo_status
(
PHOTO_CAPTURE_STATUS_UNDEFINED
)
,
_storageInfoRetries
(
0
)
...
...
@@ -145,6 +152,10 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
}
else
{
_initWhenReady
();
}
QSettings
settings
;
_photoMode
=
(
PhotoMode
)
settings
.
value
(
kPhotoMode
,
(
int
)
PHOTO_CAPTURE_SINGLE
).
toInt
();
_photoLapse
=
settings
.
value
(
kPhotoLapse
,
1.0
).
toDouble
();
_photoLapseCount
=
settings
.
value
(
kPhotoLapseCount
,
0
).
toInt
();
}
//-----------------------------------------------------------------------------
...
...
@@ -228,6 +239,36 @@ QGCCameraControl::setCameraMode(CameraMode mode)
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setPhotoMode
(
PhotoMode
mode
)
{
_photoMode
=
mode
;
QSettings
settings
;
settings
.
setValue
(
kPhotoMode
,
(
int
)
mode
);
emit
photoModeChanged
();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setPhotoLapse
(
qreal
interval
)
{
_photoLapse
=
interval
;
QSettings
settings
;
settings
.
setValue
(
kPhotoLapse
,
interval
);
emit
photoLapseChanged
();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
setPhotoLapseCount
(
int
count
)
{
_photoLapseCount
=
count
;
QSettings
settings
;
settings
.
setValue
(
kPhotoLapseCount
,
count
);
emit
photoLapseCountChanged
();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_setCameraMode
(
CameraMode
mode
)
...
...
@@ -240,7 +281,7 @@ QGCCameraControl::_setCameraMode(CameraMode mode)
void
QGCCameraControl
::
toggleMode
()
{
if
(
cameraMode
()
==
CAM_MODE_PHOTO
)
{
if
(
cameraMode
()
==
CAM_MODE_PHOTO
||
cameraMode
()
==
CAM_MODE_SURVEY
)
{
setVideoMode
();
}
else
if
(
cameraMode
()
==
CAM_MODE_VIDEO
)
{
setPhotoMode
();
...
...
@@ -269,12 +310,12 @@ QGCCameraControl::takePhoto()
}
if
(
capturesPhotos
())
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_IMAGE_START_CAPTURE
,
// Command id
false
,
// ShowError
0
,
// Reserved (Set to 0)
0
,
// Duration between two consecutive pictures (in seconds--ignored if single image)
1
);
// Number of images to capture total - 0 for unlimited capture
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_IMAGE_START_CAPTURE
,
// Command id
false
,
// ShowError
0
,
// Reserved (Set to 0)
_photoMode
==
PHOTO_CAPTURE_SINGLE
?
0
:
_photoLapse
,
// Duration between two consecutive pictures (in seconds--ignored if single image)
_photoMode
==
PHOTO_CAPTURE_SINGLE
?
1
:
_photoLapseCount
);
// Number of images to capture total - 0 for unlimited capture
_setPhotoStatus
(
PHOTO_CAPTURE_IN_PROGRESS
);
_captureInfoRetries
=
0
;
//-- Capture local image as well
...
...
@@ -287,6 +328,27 @@ QGCCameraControl::takePhoto()
return
false
;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
stopTakePhoto
()
{
qCDebug
(
CameraControlLog
)
<<
"stopTakePhoto()"
;
if
(
photoStatus
()
==
PHOTO_CAPTURE_IDLE
||
(
photoStatus
()
!=
PHOTO_CAPTURE_INTERVAL_IDLE
&&
photoStatus
()
!=
PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
))
{
return
false
;
}
if
(
capturesPhotos
())
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_IMAGE_STOP_CAPTURE
,
// Command id
false
,
// ShowError
0
);
// Reserved (Set to 0)
_setPhotoStatus
(
PHOTO_CAPTURE_IDLE
);
_captureInfoRetries
=
0
;
return
true
;
}
return
false
;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
startVideo
()
...
...
@@ -353,7 +415,7 @@ QGCCameraControl::setPhotoMode()
MAV_CMD_SET_CAMERA_MODE
,
// Command id
true
,
// ShowError
0
,
// Reserved (Set to 0)
CAM_MODE_PHOTO
);
// Camera mode (0: photo, 1: video)
CAM_MODE_PHOTO
);
// Camera mode (0: photo, 1: video)
_setCameraMode
(
CAM_MODE_PHOTO
);
}
}
...
...
@@ -452,6 +514,7 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
}
switch
(
command
)
{
case
MAV_CMD_IMAGE_START_CAPTURE
:
case
MAV_CMD_IMAGE_STOP_CAPTURE
:
if
(
++
_captureInfoRetries
<
5
)
{
_captureStatusTimer
.
start
(
1000
);
}
else
{
...
...
@@ -1172,10 +1235,18 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
//-- Keep asking for it once in a while when recording
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_captureStatusTimer
.
start
(
5000
);
//-- Same while image capture is busy
}
else
if
(
photoStatus
()
!=
PHOTO_CAPTURE_IDLE
)
{
//-- Same while
(single)
image capture is busy
}
else
if
(
photoStatus
()
!=
PHOTO_CAPTURE_IDLE
&&
photoMode
()
==
PHOTO_CAPTURE_SINGLE
)
{
_captureStatusTimer
.
start
(
1000
);
}
//-- Time Lapse
if
(
photoStatus
()
==
PHOTO_CAPTURE_INTERVAL_IDLE
||
photoStatus
()
==
PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
)
{
//-- Capture local image as well
QString
photoPath
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
savePath
()
->
rawValue
().
toString
()
+
QStringLiteral
(
"/Photo"
);
QDir
().
mkpath
(
photoPath
);
photoPath
+=
+
"/"
+
QDateTime
::
currentDateTime
().
toString
(
"yyyy-MM-dd_hh.mm.ss.zzz"
)
+
".jpg"
;
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
()
->
grabImage
(
photoPath
);
}
}
//-----------------------------------------------------------------------------
...
...
src/Camera/QGCCameraControl.h
View file @
5793c550
...
...
@@ -68,8 +68,9 @@ public:
//-- cam_mode
enum
CameraMode
{
CAM_MODE_UNDEFINED
=
-
1
,
CAM_MODE_PHOTO
=
0
,
CAM_MODE_VIDEO
=
1
,
CAM_MODE_PHOTO
=
0
,
CAM_MODE_VIDEO
=
1
,
CAM_MODE_SURVEY
=
2
,
};
//-- Video Capture Status
...
...
@@ -90,9 +91,16 @@ public:
PHOTO_CAPTURE_STATUS_UNDEFINED
=
255
};
//-- Photo Capture Modes
enum
PhotoMode
{
PHOTO_CAPTURE_SINGLE
=
0
,
PHOTO_CAPTURE_TIMELAPSE
,
};
Q_ENUMS
(
CameraMode
)
Q_ENUMS
(
VideoStatus
)
Q_ENUMS
(
PhotoStatus
)
Q_ENUMS
(
PhotoMode
)
Q_PROPERTY
(
int
version
READ
version
NOTIFY
infoChanged
)
Q_PROPERTY
(
QString
modelName
READ
modelName
NOTIFY
infoChanged
)
...
...
@@ -111,15 +119,19 @@ public:
Q_PROPERTY
(
QString
storageFreeStr
READ
storageFreeStr
NOTIFY
storageFreeChanged
)
Q_PROPERTY
(
quint32
storageTotal
READ
storageTotal
NOTIFY
storageTotalChanged
)
Q_PROPERTY
(
QStringList
activeSettings
READ
activeSettings
NOTIFY
activeSettingsChanged
)
Q_PROPERTY
(
VideoStatus
videoStatus
READ
videoStatus
NOTIFY
videoStatusChanged
)
Q_PROPERTY
(
PhotoStatus
photoStatus
READ
photoStatus
NOTIFY
photoStatusChanged
)
Q_PROPERTY
(
CameraMode
cameraMode
READ
cameraMode
WRITE
setCameraMode
NOTIFY
cameraModeChanged
)
Q_PROPERTY
(
QStringList
activeSettings
READ
activeSettings
NOTIFY
activeSettingsChanged
)
Q_PROPERTY
(
VideoStatus
videoStatus
READ
videoStatus
NOTIFY
videoStatusChanged
)
Q_PROPERTY
(
PhotoStatus
photoStatus
READ
photoStatus
NOTIFY
photoStatusChanged
)
Q_PROPERTY
(
CameraMode
cameraMode
READ
cameraMode
WRITE
setCameraMode
NOTIFY
cameraModeChanged
)
Q_PROPERTY
(
qreal
photoLapse
READ
photoLapse
WRITE
setPhotoLapse
NOTIFY
photoLapseChanged
)
Q_PROPERTY
(
int
photoLapseCount
READ
photoLapseCount
WRITE
setPhotoLapseCount
NOTIFY
photoLapseCountChanged
)
Q_PROPERTY
(
PhotoMode
photoMode
READ
photoMode
WRITE
setPhotoMode
NOTIFY
photoModeChanged
)
Q_INVOKABLE
virtual
void
setVideoMode
();
Q_INVOKABLE
virtual
void
setPhotoMode
();
Q_INVOKABLE
virtual
void
toggleMode
();
Q_INVOKABLE
virtual
bool
takePhoto
();
Q_INVOKABLE
virtual
bool
stopTakePhoto
();
Q_INVOKABLE
virtual
bool
startVideo
();
Q_INVOKABLE
virtual
bool
stopVideo
();
Q_INVOKABLE
virtual
bool
toggleVideo
();
...
...
@@ -143,6 +155,9 @@ public:
virtual
bool
isBasic
()
{
return
_settings
.
size
()
==
0
;
}
virtual
VideoStatus
videoStatus
();
virtual
PhotoStatus
photoStatus
();
virtual
PhotoMode
photoMode
()
{
return
_photoMode
;
}
virtual
qreal
photoLapse
()
{
return
_photoLapse
;
}
virtual
int
photoLapseCount
()
{
return
_photoLapseCount
;
}
virtual
CameraMode
cameraMode
()
{
return
_cameraMode
;
}
virtual
QStringList
activeSettings
();
virtual
quint32
storageFree
()
{
return
_storageFree
;
}
...
...
@@ -150,6 +165,9 @@ public:
virtual
quint32
storageTotal
()
{
return
_storageTotal
;
}
virtual
void
setCameraMode
(
CameraMode
mode
);
virtual
void
setPhotoMode
(
PhotoMode
mode
);
virtual
void
setPhotoLapse
(
qreal
interval
);
virtual
void
setPhotoLapseCount
(
int
count
);
virtual
void
handleSettings
(
const
mavlink_camera_settings_t
&
settings
);
virtual
void
handleCaptureStatus
(
const
mavlink_camera_capture_status_t
&
capStatus
);
...
...
@@ -168,6 +186,9 @@ signals:
void
infoChanged
();
void
videoStatusChanged
();
void
photoStatusChanged
();
void
photoModeChanged
();
void
photoLapseChanged
();
void
photoLapseCountChanged
();
void
cameraModeChanged
();
void
activeSettingsChanged
();
void
storageFreeChanged
();
...
...
@@ -225,6 +246,9 @@ protected:
QString
_vendor
;
QString
_cacheFile
;
CameraMode
_cameraMode
;
PhotoMode
_photoMode
;
qreal
_photoLapse
;
int
_photoLapseCount
;
VideoStatus
_video_status
;
PhotoStatus
_photo_status
;
QStringList
_activeSettings
;
...
...
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