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
c2879665
Commit
c2879665
authored
Dec 10, 2018
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Deal with c++ warnings
parent
2f982bbe
Changes
2
Show whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
58 additions
and
49 deletions
+58
-49
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+53
-29
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+5
-20
No files found.
src/Camera/QGCCameraControl.cc
View file @
c2879665
...
...
@@ -58,6 +58,27 @@ static const char* kPhotoMode = "PhotoMode";
static
const
char
*
kPhotoLapse
=
"PhotoLapse"
;
static
const
char
*
kPhotoLapseCount
=
"PhotoLapseCount"
;
//-----------------------------------------------------------------------------
QGCCameraOptionExclusion
::
QGCCameraOptionExclusion
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QStringList
exclusions_
)
:
QObject
(
parent
)
,
param
(
param_
)
,
value
(
value_
)
,
exclusions
(
exclusions_
)
{
}
//-----------------------------------------------------------------------------
QGCCameraOptionRange
::
QGCCameraOptionRange
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QString
targetParam_
,
QString
condition_
,
QStringList
optNames_
,
QStringList
optValues_
)
:
QObject
(
parent
)
,
param
(
param_
)
,
value
(
value_
)
,
targetParam
(
targetParam_
)
,
condition
(
condition_
)
,
optNames
(
optNames_
)
,
optValues
(
optValues_
)
{
}
//-----------------------------------------------------------------------------
static
bool
read_attribute
(
QDomNode
&
node
,
const
char
*
tagName
,
bool
&
target
)
...
...
@@ -127,7 +148,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
,
_cached
(
false
)
,
_storageFree
(
0
)
,
_storageTotal
(
0
)
,
_netManager
(
NULL
)
,
_netManager
(
nullptr
)
,
_cameraMode
(
CAM_MODE_UNDEFINED
)
,
_photoMode
(
PHOTO_CAPTURE_SINGLE
)
,
_photoLapse
(
1.0
)
...
...
@@ -140,9 +161,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
memcpy
(
&
_info
,
info
,
sizeof
(
mavlink_camera_information_t
));
connect
(
this
,
&
QGCCameraControl
::
dataReady
,
this
,
&
QGCCameraControl
::
_dataReady
);
_vendor
=
QString
(
(
const
char
*
)(
void
*
)
&
info
->
vendor_name
[
0
]
);
_modelName
=
QString
(
(
const
char
*
)(
void
*
)
&
info
->
model_name
[
0
]
);
int
ver
=
(
int
)
_info
.
cam_definition_version
;
_vendor
=
QString
(
reinterpret_cast
<
const
char
*>
(
info
->
vendor_name
)
);
_modelName
=
QString
(
reinterpret_cast
<
const
char
*>
(
info
->
model_name
)
);
int
ver
=
static_cast
<
int
>
(
_info
.
cam_definition_version
)
;
_cacheFile
.
sprintf
(
"%s/%s_%s_%03d.xml"
,
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
parameterSavePath
().
toStdString
().
c_str
(),
_vendor
.
toStdString
().
c_str
(),
...
...
@@ -155,7 +176,7 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
_initWhenReady
();
}
QSettings
settings
;
_photoMode
=
(
PhotoMode
)
settings
.
value
(
kPhotoMode
,
(
int
)
PHOTO_CAPTURE_SINGLE
).
toInt
(
);
_photoMode
=
static_cast
<
PhotoMode
>
(
settings
.
value
(
kPhotoMode
,
static_cast
<
int
>
(
PHOTO_CAPTURE_SINGLE
)).
toInt
()
);
_photoLapse
=
settings
.
value
(
kPhotoLapse
,
1.0
).
toDouble
();
_photoLapseCount
=
settings
.
value
(
kPhotoLapseCount
,
0
).
toInt
();
}
...
...
@@ -189,7 +210,7 @@ QGCCameraControl::_initWhenReady()
emit
infoChanged
();
if
(
_netManager
)
{
delete
_netManager
;
_netManager
=
NULL
;
_netManager
=
nullptr
;
}
}
...
...
@@ -223,7 +244,7 @@ QGCCameraControl::photoStatus()
QString
QGCCameraControl
::
storageFreeStr
()
{
return
QGCMapEngine
::
bigSizeToString
(
(
quint64
)
_storageFree
*
1024
*
1024
);
return
QGCMapEngine
::
bigSizeToString
(
static_cast
<
quint64
>
(
_storageFree
*
1024
*
1024
)
);
}
//-----------------------------------------------------------------------------
...
...
@@ -247,7 +268,7 @@ QGCCameraControl::setPhotoMode(PhotoMode mode)
{
_photoMode
=
mode
;
QSettings
settings
;
settings
.
setValue
(
kPhotoMode
,
(
int
)
mode
);
settings
.
setValue
(
kPhotoMode
,
static_cast
<
int
>
(
mode
)
);
emit
photoModeChanged
();
}
...
...
@@ -316,7 +337,7 @@ QGCCameraControl::takePhoto()
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)
static_cast
<
float
>
(
_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
;
...
...
@@ -944,12 +965,12 @@ QGCCameraControl::_requestAllParameters()
MAVLinkProtocol
*
mavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
mavlink_message_t
msg
;
mavlink_msg_param_ext_request_list_pack_chan
(
mavlink
->
getSystemId
(
),
mavlink
->
getComponentId
(
),
static_cast
<
uint8_t
>
(
mavlink
->
getSystemId
()
),
static_cast
<
uint8_t
>
(
mavlink
->
getComponentId
()
),
_vehicle
->
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
_vehicle
->
id
(
),
compID
(
));
static_cast
<
uint8_t
>
(
_vehicle
->
id
()
),
static_cast
<
uint8_t
>
(
compID
()
));
_vehicle
->
sendMessageOnLink
(
_vehicle
->
priorityLink
(),
msg
);
qCDebug
(
CameraControlLogVerbose
)
<<
"Request all parameters"
;
}
...
...
@@ -1223,7 +1244,7 @@ void
QGCCameraControl
::
handleSettings
(
const
mavlink_camera_settings_t
&
settings
)
{
qCDebug
(
CameraControlLog
)
<<
"handleSettings() Mode:"
<<
settings
.
mode_id
;
_setCameraMode
(
(
CameraMode
)
settings
.
mode_id
);
_setCameraMode
(
static_cast
<
CameraMode
>
(
settings
.
mode_id
)
);
}
//-----------------------------------------------------------------------------
...
...
@@ -1231,13 +1252,15 @@ void
QGCCameraControl
::
handleStorageInfo
(
const
mavlink_storage_information_t
&
st
)
{
qCDebug
(
CameraControlLog
)
<<
"_handleStorageInfo:"
<<
st
.
available_capacity
<<
st
.
status
<<
st
.
storage_count
<<
st
.
storage_id
<<
st
.
total_capacity
<<
st
.
used_capacity
;
if
(
_storageTotal
!=
st
.
total_capacity
)
{
_storageTotal
=
st
.
total_capacity
;
uint32_t
t
=
static_cast
<
uint32_t
>
(
st
.
total_capacity
);
if
(
_storageTotal
!=
t
)
{
_storageTotal
=
t
;
}
//-- Always emit this
emit
storageTotalChanged
();
if
(
_storageFree
!=
st
.
available_capacity
)
{
_storageFree
=
st
.
available_capacity
;
uint32_t
a
=
static_cast
<
uint32_t
>
(
st
.
available_capacity
);
if
(
_storageFree
!=
a
)
{
_storageFree
=
a
;
emit
storageFreeChanged
();
}
}
...
...
@@ -1249,15 +1272,16 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
//-- This is a response to MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
qCDebug
(
CameraControlLog
)
<<
"handleCaptureStatus:"
<<
cap
.
available_capacity
<<
cap
.
image_interval
<<
cap
.
image_status
<<
cap
.
recording_time_ms
<<
cap
.
video_status
;
//-- Disk Free Space
if
(
_storageFree
!=
cap
.
available_capacity
)
{
_storageFree
=
cap
.
available_capacity
;
uint32_t
a
=
static_cast
<
uint32_t
>
(
cap
.
available_capacity
);
if
(
_storageFree
!=
a
)
{
_storageFree
=
a
;
emit
storageFreeChanged
();
}
//-- Video/Image Capture Status
uint8_t
vs
=
cap
.
video_status
<
(
uint8_t
)
VIDEO_CAPTURE_STATUS_LAST
?
cap
.
video_status
:
(
uint8_t
)
VIDEO_CAPTURE_STATUS_UNDEFINED
;
uint8_t
ps
=
cap
.
image_status
<
(
uint8_t
)
PHOTO_CAPTURE_LAST
?
cap
.
image_status
:
(
uint8_t
)
PHOTO_CAPTURE_STATUS_UNDEFINED
;
_setVideoStatus
(
(
VideoStatus
)
vs
);
_setPhotoStatus
(
(
PhotoStatus
)
ps
);
uint8_t
vs
=
cap
.
video_status
<
static_cast
<
uint8_t
>
(
VIDEO_CAPTURE_STATUS_LAST
)
?
cap
.
video_status
:
static_cast
<
uint8_t
>
(
VIDEO_CAPTURE_STATUS_UNDEFINED
)
;
uint8_t
ps
=
cap
.
image_status
<
static_cast
<
uint8_t
>
(
PHOTO_CAPTURE_LAST
)
?
cap
.
image_status
:
static_cast
<
uint8_t
>
(
PHOTO_CAPTURE_STATUS_UNDEFINED
)
;
_setVideoStatus
(
static_cast
<
VideoStatus
>
(
vs
)
);
_setPhotoStatus
(
static_cast
<
PhotoStatus
>
(
ps
)
);
//-- Keep asking for it once in a while when recording
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_captureStatusTimer
.
start
(
5000
);
...
...
src/Camera/QGCCameraControl.h
View file @
c2879665
...
...
@@ -21,13 +21,7 @@ Q_DECLARE_LOGGING_CATEGORY(CameraControlLogVerbose)
class
QGCCameraOptionExclusion
:
public
QObject
{
public:
QGCCameraOptionExclusion
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QStringList
exclusions_
)
:
QObject
(
parent
)
,
param
(
param_
)
,
value
(
value_
)
,
exclusions
(
exclusions_
)
{
}
QGCCameraOptionExclusion
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QStringList
exclusions_
);
QString
param
;
QString
value
;
QStringList
exclusions
;
...
...
@@ -37,16 +31,7 @@ public:
class
QGCCameraOptionRange
:
public
QObject
{
public:
QGCCameraOptionRange
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QString
targetParam_
,
QString
condition_
,
QStringList
optNames_
,
QStringList
optValues_
)
:
QObject
(
parent
)
,
param
(
param_
)
,
value
(
value_
)
,
targetParam
(
targetParam_
)
,
condition
(
condition_
)
,
optNames
(
optNames_
)
,
optValues
(
optValues_
)
{
}
QGCCameraOptionRange
(
QObject
*
parent
,
QString
param_
,
QString
value_
,
QString
targetParam_
,
QString
condition_
,
QStringList
optNames_
,
QStringList
optValues_
);
QString
param
;
QString
value
;
QString
targetParam
;
...
...
@@ -62,7 +47,7 @@ class QGCCameraControl : public FactGroup
Q_OBJECT
friend
class
QGCCameraParamIO
;
public:
QGCCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
=
NULL
);
QGCCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
=
nullptr
);
virtual
~
QGCCameraControl
();
//-- cam_mode
...
...
@@ -142,8 +127,8 @@ public:
virtual
QString
modelName
()
{
return
_modelName
;
}
virtual
QString
vendor
()
{
return
_vendor
;
}
virtual
QString
firmwareVersion
();
virtual
qreal
focalLength
()
{
return
(
qreal
)
_info
.
focal_length
;
}
virtual
QSizeF
sensorSize
()
{
return
QSizeF
(
_info
.
sensor_size_h
,
_info
.
sensor_size_v
);
}
virtual
qreal
focalLength
()
{
return
static_cast
<
qreal
>
(
_info
.
focal_length
)
;
}
virtual
QSizeF
sensorSize
()
{
return
QSizeF
(
static_cast
<
qreal
>
(
_info
.
sensor_size_h
),
static_cast
<
qreal
>
(
_info
.
sensor_size_v
)
);
}
virtual
QSize
resolution
()
{
return
QSize
(
_info
.
resolution_h
,
_info
.
resolution_v
);
}
virtual
bool
capturesVideo
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAPTURE_VIDEO
;
}
virtual
bool
capturesPhotos
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAPTURE_IMAGE
;
}
...
...
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