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
a9621d2b
Commit
a9621d2b
authored
Jul 18, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Handle Facts
Handle initial storage Handle image/video capture and storage.
parent
4362d4e5
Changes
8
Hide whitespace changes
Inline
Side-by-side
Showing
8 changed files
with
445 additions
and
116 deletions
+445
-116
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+292
-46
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+75
-36
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+13
-4
QGCCameraIO.h
src/Camera/QGCCameraIO.h
+1
-0
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+48
-16
QGCCameraManager.h
src/Camera/QGCCameraManager.h
+9
-7
Fact.cc
src/FactSystem/Fact.cc
+3
-5
Fact.h
src/FactSystem/Fact.h
+4
-2
No files found.
src/Camera/QGCCameraControl.cc
View file @
a9621d2b
...
@@ -7,6 +7,10 @@
...
@@ -7,6 +7,10 @@
#include "QGCCameraControl.h"
#include "QGCCameraControl.h"
#include "QGCCameraIO.h"
#include "QGCCameraIO.h"
#include "SettingsManager.h"
#include "VideoManager.h"
#include "QGCMapEngine.h"
#include <QDomDocument>
#include <QDomDocument>
#include <QDomNodeList>
#include <QDomNodeList>
...
@@ -105,22 +109,20 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
...
@@ -105,22 +109,20 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
,
_vehicle
(
vehicle
)
,
_vehicle
(
vehicle
)
,
_compID
(
compID
)
,
_compID
(
compID
)
,
_version
(
0
)
,
_version
(
0
)
,
_storageFree
(
0
)
,
_storageTotal
(
0
)
,
_netManager
(
NULL
)
,
_cameraMode
(
CAMERA_MODE_UNDEFINED
)
,
_cameraMode
(
CAMERA_MODE_UNDEFINED
)
,
_video_status
(
VIDEO_CAPTURE_STATUS_UNDEFINED
)
{
{
memcpy
(
&
_info
,
&
info
,
sizeof
(
mavlink_camera_information_t
));
memcpy
(
&
_info
,
&
info
,
sizeof
(
mavlink_camera_information_t
));
if
(
1
/*!_info.definition_uri[0]*/
)
{
connect
(
this
,
&
QGCCameraControl
::
dataReady
,
this
,
&
QGCCameraControl
::
_dataReady
);
//-- Process camera definition file
if
(
1
/*_info.cam_definition_uri[0]*/
)
{
_loadCameraDefinitionFile
(
"/Users/gus/github/Yuneec/camera_repeater/yuneec_udp/def_files/e90.xml"
);
//-- Process camera definition file
}
_httpRequest
(
"http://www.grubba.com/e90.xml"
);
if
(
isBasic
())
{
_requestCameraSettings
();
}
else
{
}
else
{
_requestAllParameters
();
_initWhenReady
();
QTimer
::
singleShot
(
2000
,
this
,
&
QGCCameraControl
::
_requestCameraSettings
);
}
}
emit
infoChanged
();
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -132,6 +134,34 @@ QGCCameraControl::~QGCCameraControl()
...
@@ -132,6 +134,34 @@ QGCCameraControl::~QGCCameraControl()
delete
_paramIO
[
paramName
];
delete
_paramIO
[
paramName
];
}
}
}
}
if
(
_netManager
)
{
delete
_netManager
;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_initWhenReady
()
{
qCDebug
(
CameraControlLog
)
<<
"_initWhenReady()"
;
if
(
isBasic
())
{
qCDebug
(
CameraControlLog
)
<<
"Basic, MAVLink only messages."
;
_requestCameraSettings
();
}
else
{
_requestAllParameters
();
//-- Give some time to load the parameters before going after the camera settings
QTimer
::
singleShot
(
2000
,
this
,
&
QGCCameraControl
::
_requestCameraSettings
);
}
connect
(
_vehicle
,
&
Vehicle
::
mavCommandResult
,
this
,
&
QGCCameraControl
::
_mavCommandResult
);
connect
(
&
_captureStatusTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraControl
::
_requestCaptureStatus
);
_captureStatusTimer
.
setSingleShot
(
true
);
QTimer
::
singleShot
(
2500
,
this
,
&
QGCCameraControl
::
_requestStorageInfo
);
_captureStatusTimer
.
start
(
2750
);
emit
infoChanged
();
if
(
_netManager
)
{
delete
_netManager
;
_netManager
=
NULL
;
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -146,6 +176,20 @@ QGCCameraControl::firmwareVersion()
...
@@ -146,6 +176,20 @@ QGCCameraControl::firmwareVersion()
return
ver
;
return
ver
;
}
}
//-----------------------------------------------------------------------------
QGCCameraControl
::
VideoStatus
QGCCameraControl
::
videoStatus
()
{
return
_video_status
;
}
//-----------------------------------------------------------------------------
QString
QGCCameraControl
::
storageFreeStr
()
{
return
QGCMapEngine
::
bigSizeToString
((
quint64
)
_storageFree
*
1024
);
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraControl
::
setCameraMode
(
CameraMode
mode
)
QGCCameraControl
::
setCameraMode
(
CameraMode
mode
)
...
@@ -159,6 +203,12 @@ QGCCameraControl::setCameraMode(CameraMode mode)
...
@@ -159,6 +203,12 @@ QGCCameraControl::setCameraMode(CameraMode mode)
qCDebug
(
CameraControlLog
)
<<
"setCameraMode() Invalid mode:"
<<
mode
;
qCDebug
(
CameraControlLog
)
<<
"setCameraMode() Invalid mode:"
<<
mode
;
return
;
return
;
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_setCameraMode
(
CameraMode
mode
)
{
_cameraMode
=
mode
;
_cameraMode
=
mode
;
emit
cameraModeChanged
();
emit
cameraModeChanged
();
}
}
...
@@ -175,31 +225,85 @@ QGCCameraControl::toggleMode()
...
@@ -175,31 +225,85 @@ QGCCameraControl::toggleMode()
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
bool
QGCCameraControl
::
t
akePhot
o
()
QGCCameraControl
::
t
oggleVide
o
()
{
{
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
return
stopVideo
();
}
else
{
return
startVideo
();
}
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
takePhoto
()
{
qCDebug
(
CameraControlLog
)
<<
"takePhoto()"
;
//-- Check if camera can capture photos or if it can capture it while in Video Mode
if
(
!
capturesPhotos
()
||
(
cameraMode
()
==
CAMERA_MODE_VIDEO
&&
!
photosInVideoMode
()))
{
return
false
;
}
if
(
capturesPhotos
())
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_IMAGE_START_CAPTURE
,
// Command id
false
,
// ShowError
0
,
// Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
0
,
// Duration between two consecutive pictures (in seconds--ignored if single image)
1
);
// Number of images to capture total - 0 for unlimited capture
//-- 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
);
return
true
;
}
return
false
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
bool
QGCCameraControl
::
startVideo
()
QGCCameraControl
::
startVideo
()
{
{
qCDebug
(
CameraControlLog
)
<<
"startVideo()"
;
//-- Check if camera can capture videos or if it can capture it while in Photo Mode
if
(
!
capturesVideo
()
||
(
cameraMode
()
==
CAMERA_MODE_PHOTO
&&
!
videoInPhotoMode
()))
{
return
false
;
}
if
(
videoStatus
()
!=
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_VIDEO_START_CAPTURE
,
// Command id
true
,
// ShowError
0
,
// Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
0
);
// CAMERA_CAPTURE_STATUS Frequency
return
true
;
}
return
false
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
bool
QGCCameraControl
::
stopVideo
()
QGCCameraControl
::
stopVideo
()
{
{
qCDebug
(
CameraControlLog
)
<<
"stopVideo()"
;
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_vehicle
->
sendMavCommand
(
MAV_COMP_ID_CAMERA
,
// Target component
MAV_CMD_VIDEO_STOP_CAPTURE
,
// Command id
true
,
// ShowError
0
);
// Camera ID (0 for all cameras), 1 for first, 2 for second, etc.
return
true
;
}
return
false
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraControl
::
setVideoMode
()
QGCCameraControl
::
setVideoMode
()
{
{
if
(
_vehicle
&&
_cameraMode
!=
CAMERA_MODE_VIDEO
)
{
if
(
hasModes
()
&&
_cameraMode
!=
CAMERA_MODE_VIDEO
)
{
qCDebug
(
CameraControlLog
)
<<
"setVideoMode()"
;
qCDebug
(
CameraControlLog
)
<<
"setVideoMode()"
;
//-- Use basic MAVLink message
//-- Use basic MAVLink message
_vehicle
->
sendMavCommand
(
_vehicle
->
sendMavCommand
(
...
@@ -208,8 +312,7 @@ QGCCameraControl::setVideoMode()
...
@@ -208,8 +312,7 @@ QGCCameraControl::setVideoMode()
true
,
// ShowError
true
,
// ShowError
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
CAMERA_MODE_VIDEO
);
// Camera mode (0: photo, 1: video)
CAMERA_MODE_VIDEO
);
// Camera mode (0: photo, 1: video)
_cameraMode
=
CAMERA_MODE_VIDEO
;
_setCameraMode
(
CAMERA_MODE_VIDEO
);
emit
cameraModeChanged
();
}
}
}
}
...
@@ -217,7 +320,7 @@ QGCCameraControl::setVideoMode()
...
@@ -217,7 +320,7 @@ QGCCameraControl::setVideoMode()
void
void
QGCCameraControl
::
setPhotoMode
()
QGCCameraControl
::
setPhotoMode
()
{
{
if
(
_vehicle
&&
_cameraMode
!=
CAMERA_MODE_PHOTO
)
{
if
(
hasModes
()
&&
_cameraMode
!=
CAMERA_MODE_PHOTO
)
{
qCDebug
(
CameraControlLog
)
<<
"setPhotoMode()"
;
qCDebug
(
CameraControlLog
)
<<
"setPhotoMode()"
;
//-- Use basic MAVLink message
//-- Use basic MAVLink message
_vehicle
->
sendMavCommand
(
_vehicle
->
sendMavCommand
(
...
@@ -226,8 +329,7 @@ QGCCameraControl::setPhotoMode()
...
@@ -226,8 +329,7 @@ QGCCameraControl::setPhotoMode()
true
,
// ShowError
true
,
// ShowError
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
CAMERA_MODE_PHOTO
);
// Camera mode (0: photo, 1: video)
CAMERA_MODE_PHOTO
);
// Camera mode (0: photo, 1: video)
_cameraMode
=
CAMERA_MODE_PHOTO
;
_setCameraMode
(
CAMERA_MODE_PHOTO
);
emit
cameraModeChanged
();
}
}
}
}
...
@@ -236,15 +338,12 @@ void
...
@@ -236,15 +338,12 @@ void
QGCCameraControl
::
resetSettings
()
QGCCameraControl
::
resetSettings
()
{
{
qCDebug
(
CameraControlLog
)
<<
"resetSettings()"
;
qCDebug
(
CameraControlLog
)
<<
"resetSettings()"
;
if
(
_vehicle
)
{
_vehicle
->
sendMavCommand
(
//-- Use basic MAVLink message
_compID
,
// Target component
_vehicle
->
sendMavCommand
(
MAV_CMD_RESET_CAMERA_SETTINGS
,
// Command id
_compID
,
// Target component
true
,
// ShowError
MAV_CMD_RESET_CAMERA_SETTINGS
,
// Command id
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
true
,
// ShowError
1
);
// Do Reset
0
,
// Camera ID (0 for all, 1 for first, 2 for second, etc.) ==> TODO: Remove
1
);
// Do Reset
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -262,6 +361,18 @@ QGCCameraControl::formatCard(int id)
...
@@ -262,6 +361,18 @@ QGCCameraControl::formatCard(int id)
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_requestCaptureStatus
()
{
_vehicle
->
sendMavCommand
(
_compID
,
// target component
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
,
// command id
false
,
// showError
0
,
// Storage ID ("All" for now)
1
);
// Do Request
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraControl
::
factChanged
(
Fact
*
pFact
)
QGCCameraControl
::
factChanged
(
Fact
*
pFact
)
...
@@ -271,16 +382,48 @@ QGCCameraControl::factChanged(Fact* pFact)
...
@@ -271,16 +382,48 @@ QGCCameraControl::factChanged(Fact* pFact)
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
bool
void
QGCCameraControl
::
_
loadCameraDefinitionFile
(
const
QString
&
fi
le
)
QGCCameraControl
::
_
mavCommandResult
(
int
vehicleId
,
int
component
,
int
command
,
int
result
,
bool
noReponseFromVehic
le
)
{
{
QFile
xmlFile
(
file
);
//-- Is this ours?
if
(
!
xmlFile
.
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
if
(
_vehicle
->
id
()
!=
vehicleId
||
compID
()
!=
component
)
{
qWarning
()
<<
"Unable to open camera definition file"
<<
file
<<
xmlFile
.
errorString
();
return
;
return
false
;
}
if
(
!
noReponseFromVehicle
&&
result
==
MAV_RESULT_ACCEPTED
)
{
switch
(
command
)
{
case
MAV_CMD_RESET_CAMERA_SETTINGS
:
if
(
isBasic
())
{
_requestCameraSettings
();
}
else
{
_requestAllParameters
();
QTimer
::
singleShot
(
2000
,
this
,
&
QGCCameraControl
::
_requestCameraSettings
);
}
break
;
case
MAV_CMD_VIDEO_START_CAPTURE
:
_setVideoStatus
(
VIDEO_CAPTURE_STATUS_RUNNING
);
_captureStatusTimer
.
start
(
1000
);
break
;
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
_setVideoStatus
(
VIDEO_CAPTURE_STATUS_STOPPED
);
break
;
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_setVideoStatus
(
VideoStatus
status
)
{
if
(
_video_status
!=
status
)
{
_video_status
=
status
;
emit
videoStatusChanged
();
}
}
QByteArray
bytes
=
xmlFile
.
readAll
();
}
xmlFile
.
close
();
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
_loadCameraDefinitionFile
(
QByteArray
&
bytes
)
{
//-- Handle localization
//-- Handle localization
if
(
!
_handleLocalization
(
bytes
))
{
if
(
!
_handleLocalization
(
bytes
))
{
return
false
;
return
false
;
...
@@ -296,13 +439,13 @@ QGCCameraControl::_loadCameraDefinitionFile(const QString& file)
...
@@ -296,13 +439,13 @@ QGCCameraControl::_loadCameraDefinitionFile(const QString& file)
//-- Load camera constants
//-- Load camera constants
QDomNodeList
defElements
=
doc
.
elementsByTagName
(
kDefnition
);
QDomNodeList
defElements
=
doc
.
elementsByTagName
(
kDefnition
);
if
(
!
defElements
.
size
()
||
!
_loadConstants
(
defElements
))
{
if
(
!
defElements
.
size
()
||
!
_loadConstants
(
defElements
))
{
qWarning
()
<<
"Unable to load camera constants from camera definition
file"
<<
file
;
qWarning
()
<<
"Unable to load camera constants from camera definition
"
;
return
false
;
return
false
;
}
}
//-- Load camera parameters
//-- Load camera parameters
QDomNodeList
paramElements
=
doc
.
elementsByTagName
(
kParameters
);
QDomNodeList
paramElements
=
doc
.
elementsByTagName
(
kParameters
);
if
(
!
paramElements
.
size
()
||
!
_loadSettings
(
paramElements
))
{
if
(
!
paramElements
.
size
()
||
!
_loadSettings
(
paramElements
))
{
qWarning
()
<<
"Unable to load camera parameters from camera definition
file"
<<
file
;
qWarning
()
<<
"Unable to load camera parameters from camera definition
"
;
return
false
;
return
false
;
}
}
return
true
;
return
true
;
...
@@ -427,7 +570,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
...
@@ -427,7 +570,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
pFact
->
setMetaData
(
metaData
);
pFact
->
setMetaData
(
metaData
);
pFact
->
setRawValue
(
metaData
->
rawDefaultValue
(),
true
);
pFact
->
_containerSetRawValue
(
metaData
->
rawDefaultValue
()
);
QGCCameraParamIO
*
pIO
=
new
QGCCameraParamIO
(
this
,
pFact
,
_vehicle
);
QGCCameraParamIO
*
pIO
=
new
QGCCameraParamIO
(
this
,
pFact
,
_vehicle
);
_paramIO
[
factName
]
=
pIO
;
_paramIO
[
factName
]
=
pIO
;
_addFact
(
pFact
,
factName
);
_addFact
(
pFact
,
factName
);
...
@@ -737,13 +880,62 @@ QGCCameraControl::_requestCameraSettings()
...
@@ -737,13 +880,62 @@ QGCCameraControl::_requestCameraSettings()
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_requestStorageInfo
()
{
qCDebug
(
CameraControlLog
)
<<
"_requestStorageInfo()"
;
if
(
_vehicle
)
{
_vehicle
->
sendMavCommand
(
_compID
,
// Target component
MAV_CMD_REQUEST_STORAGE_INFORMATION
,
// command id
false
,
// showError
0
,
// Storage ID (0 for all, 1 for first, 2 for second, etc.)
1
);
// Do Request
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraControl
::
handleSettings
(
const
mavlink_camera_settings_t
&
settings
)
QGCCameraControl
::
handleSettings
(
const
mavlink_camera_settings_t
&
settings
)
{
{
_cameraMode
=
(
CameraMode
)
settings
.
mode_id
;
qCDebug
(
CameraControlLog
)
<<
"handleSettings() Mode:"
<<
settings
.
mode_id
;
emit
cameraModeChanged
();
_setCameraMode
((
CameraMode
)
settings
.
mode_id
);
qCDebug
(
CameraControlLog
)
<<
"handleSettings() Mode:"
<<
_cameraMode
;
}
//-----------------------------------------------------------------------------
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
;
}
//-- Always emit this
emit
storageTotalChanged
();
if
(
_storageFree
!=
st
.
available_capacity
)
{
_storageFree
=
st
.
available_capacity
;
emit
storageFreeChanged
();
}
}
//-----------------------------------------------------------------------------
void
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
;
emit
storageFreeChanged
();
}
//-- Video Capture Status
_setVideoStatus
((
VideoStatus
)
cap
.
video_status
);
//-- Keep asking for it once in a while when recording
if
(
videoStatus
()
==
VIDEO_CAPTURE_STATUS_RUNNING
)
{
_captureStatusTimer
.
start
(
5000
);
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -864,3 +1056,57 @@ QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMe
...
@@ -864,3 +1056,57 @@ QGCCameraControl::_loadNameValue(QDomNode option, const QString factName, FactMe
}
}
return
true
;
return
true
;
}
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_httpRequest
(
const
QString
&
url
)
{
qCDebug
(
CameraControlLog
)
<<
"Request camera definition:"
<<
url
;
if
(
!
_netManager
)
{
_netManager
=
new
QNetworkAccessManager
(
this
);
}
QNetworkProxy
savedProxy
=
_netManager
->
proxy
();
QNetworkProxy
tempProxy
;
tempProxy
.
setType
(
QNetworkProxy
::
DefaultProxy
);
_netManager
->
setProxy
(
tempProxy
);
QNetworkRequest
request
(
url
);
request
.
setAttribute
(
QNetworkRequest
::
FollowRedirectsAttribute
,
true
);
QSslConfiguration
conf
=
request
.
sslConfiguration
();
conf
.
setPeerVerifyMode
(
QSslSocket
::
VerifyNone
);
request
.
setSslConfiguration
(
conf
);
QNetworkReply
*
reply
=
_netManager
->
get
(
request
);
connect
(
reply
,
&
QNetworkReply
::
finished
,
this
,
&
QGCCameraControl
::
_downloadFinished
);
_netManager
->
setProxy
(
savedProxy
);
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_downloadFinished
()
{
QNetworkReply
*
reply
=
qobject_cast
<
QNetworkReply
*>
(
sender
());
if
(
!
reply
)
{
return
;
}
int
err
=
reply
->
error
();
int
http_code
=
reply
->
attribute
(
QNetworkRequest
::
HttpStatusCodeAttribute
).
toInt
();
QByteArray
data
=
reply
->
readAll
();
if
(
err
==
QNetworkReply
::
NoError
&&
http_code
==
200
)
{
data
.
append
(
"
\n
"
);
}
else
{
data
.
clear
();
qWarning
()
<<
QString
(
"Camera Definition download error: %1 status: %2"
).
arg
(
reply
->
errorString
(),
reply
->
attribute
(
QNetworkRequest
::
HttpStatusCodeAttribute
).
toString
());
}
emit
dataReady
(
data
);
//reply->deleteLater();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_dataReady
(
QByteArray
data
)
{
if
(
data
.
size
())
{
qCDebug
(
CameraControlLog
)
<<
"Parsing camera definition"
;
_loadCameraDefinitionFile
(
data
);
}
_initWhenReady
();
}
src/Camera/QGCCameraControl.h
View file @
a9621d2b
...
@@ -62,7 +62,7 @@ class QGCCameraControl : public FactGroup
...
@@ -62,7 +62,7 @@ class QGCCameraControl : public FactGroup
Q_OBJECT
Q_OBJECT
public:
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
=
NULL
);
~
QGCCameraControl
();
virtual
~
QGCCameraControl
();
//-- cam_mode
//-- cam_mode
enum
CameraMode
{
enum
CameraMode
{
...
@@ -71,7 +71,15 @@ public:
...
@@ -71,7 +71,15 @@ public:
CAMERA_MODE_VIDEO
=
1
,
CAMERA_MODE_VIDEO
=
1
,
};
};
//-- Video Capture Status
enum
VideoStatus
{
VIDEO_CAPTURE_STATUS_STOPPED
=
0
,
VIDEO_CAPTURE_STATUS_RUNNING
,
VIDEO_CAPTURE_STATUS_UNDEFINED
};
Q_ENUMS
(
CameraMode
)
Q_ENUMS
(
CameraMode
)
Q_ENUMS
(
VideoStatus
)
Q_PROPERTY
(
int
version
READ
version
NOTIFY
infoChanged
)
Q_PROPERTY
(
int
version
READ
version
NOTIFY
infoChanged
)
Q_PROPERTY
(
QString
modelName
READ
modelName
NOTIFY
infoChanged
)
Q_PROPERTY
(
QString
modelName
READ
modelName
NOTIFY
infoChanged
)
...
@@ -86,57 +94,82 @@ public:
...
@@ -86,57 +94,82 @@ public:
Q_PROPERTY
(
bool
photosInVideoMode
READ
photosInVideoMode
NOTIFY
infoChanged
)
Q_PROPERTY
(
bool
photosInVideoMode
READ
photosInVideoMode
NOTIFY
infoChanged
)
Q_PROPERTY
(
bool
videoInPhotoMode
READ
videoInPhotoMode
NOTIFY
infoChanged
)
Q_PROPERTY
(
bool
videoInPhotoMode
READ
videoInPhotoMode
NOTIFY
infoChanged
)
Q_PROPERTY
(
bool
isBasic
READ
isBasic
NOTIFY
infoChanged
)
Q_PROPERTY
(
bool
isBasic
READ
isBasic
NOTIFY
infoChanged
)
Q_PROPERTY
(
quint32
storageFree
READ
storageFree
NOTIFY
storageFreeChanged
)
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
(
QStringList
activeSettings
READ
activeSettings
NOTIFY
activeSettingsChanged
)
Q_PROPERTY
(
VideoStatus
videoStatus
READ
videoStatus
NOTIFY
videoStatusChanged
)
Q_PROPERTY
(
CameraMode
cameraMode
READ
cameraMode
WRITE
setCameraMode
NOTIFY
cameraModeChanged
)
Q_PROPERTY
(
CameraMode
cameraMode
READ
cameraMode
WRITE
setCameraMode
NOTIFY
cameraModeChanged
)
Q_INVOKABLE
void
setVideoMode
();
Q_INVOKABLE
virtual
void
setVideoMode
();
Q_INVOKABLE
void
setPhotoMode
();
Q_INVOKABLE
virtual
void
setPhotoMode
();
Q_INVOKABLE
void
toggleMode
();
Q_INVOKABLE
virtual
void
toggleMode
();
Q_INVOKABLE
void
takePhoto
();
Q_INVOKABLE
virtual
bool
takePhoto
();
Q_INVOKABLE
void
startVideo
();
Q_INVOKABLE
virtual
bool
startVideo
();
Q_INVOKABLE
void
stopVideo
();
Q_INVOKABLE
virtual
bool
stopVideo
();
Q_INVOKABLE
void
resetSettings
();
Q_INVOKABLE
virtual
bool
toggleVideo
();
Q_INVOKABLE
void
formatCard
(
int
id
=
1
);
Q_INVOKABLE
virtual
void
resetSettings
();
Q_INVOKABLE
virtual
void
formatCard
(
int
id
=
1
);
int
version
()
{
return
_version
;
}
QString
modelName
()
{
return
_modelName
;
}
virtual
int
version
()
{
return
_version
;
}
QString
vendor
()
{
return
_vendor
;
}
virtual
QString
modelName
()
{
return
_modelName
;
}
QString
firmwareVersion
();
virtual
QString
vendor
()
{
return
_vendor
;
}
qreal
focalLength
()
{
return
(
qreal
)
_info
.
focal_length
;
}
virtual
QString
firmwareVersion
();
QSizeF
sensorSize
()
{
return
QSizeF
(
_info
.
sensor_size_h
,
_info
.
sensor_size_v
);
}
virtual
qreal
focalLength
()
{
return
(
qreal
)
_info
.
focal_length
;
}
QSize
resolution
()
{
return
QSize
(
_info
.
resolution_h
,
_info
.
resolution_v
);
}
virtual
QSizeF
sensorSize
()
{
return
QSizeF
(
_info
.
sensor_size_h
,
_info
.
sensor_size_v
);
}
bool
capturesVideo
()
{
return
true
/*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_VIDEO*/
;
}
virtual
QSize
resolution
()
{
return
QSize
(
_info
.
resolution_h
,
_info
.
resolution_v
);
}
bool
capturesPhotos
()
{
return
true
/*_info.flags & CAMERA_CAP_FLAGS_CAPTURE_PHOTO*/
;
}
virtual
bool
capturesVideo
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAPTURE_VIDEO
;
}
bool
hasModes
()
{
return
true
/*_info.flags & CAMERA_CAP_FLAGS_HAS_MODES*/
;
}
virtual
bool
capturesPhotos
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAPTURE_IMAGE
;
}
bool
photosInVideoMode
()
{
return
true
/*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_PHOTO_IN_VIDEO_MODE*/
;
}
virtual
bool
hasModes
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_HAS_MODES
;
}
bool
videoInPhotoMode
()
{
return
false
/*_info.flags & CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_PHOTO_MODE*/
;
}
virtual
bool
photosInVideoMode
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE
;
}
virtual
bool
videoInPhotoMode
()
{
return
_info
.
flags
&
CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE
;
}
int
compID
()
{
return
_compID
;
}
bool
isBasic
()
{
return
_settings
.
size
()
==
0
;
}
virtual
int
compID
()
{
return
_compID
;
}
CameraMode
cameraMode
()
{
return
_cameraMode
;
}
virtual
bool
isBasic
()
{
return
_settings
.
size
()
==
0
;
}
QStringList
activeSettings
()
{
return
_activeSettings
;
}
virtual
VideoStatus
videoStatus
();
virtual
CameraMode
cameraMode
()
{
return
_cameraMode
;
}
void
setCameraMode
(
CameraMode
mode
);
virtual
QStringList
activeSettings
()
{
return
_activeSettings
;
}
virtual
quint32
storageFree
()
{
return
_storageFree
;
}
void
handleSettings
(
const
mavlink_camera_settings_t
&
settings
);
virtual
QString
storageFreeStr
();
void
handleParamAck
(
const
mavlink_param_ext_ack_t
&
ack
);
virtual
quint32
storageTotal
()
{
return
_storageTotal
;
}
void
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
);
void
factChanged
(
Fact
*
pFact
);
virtual
void
setCameraMode
(
CameraMode
mode
);
virtual
void
handleSettings
(
const
mavlink_camera_settings_t
&
settings
);
virtual
void
handleCaptureStatus
(
const
mavlink_camera_capture_status_t
&
capStatus
);
virtual
void
handleParamAck
(
const
mavlink_param_ext_ack_t
&
ack
);
virtual
void
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
);
virtual
void
handleStorageInfo
(
const
mavlink_storage_information_t
&
st
);
virtual
void
factChanged
(
Fact
*
pFact
);
signals:
signals:
void
infoChanged
();
void
infoChanged
();
void
videoStatusChanged
();
void
cameraModeChanged
();
void
cameraModeChanged
();
void
activeSettingsChanged
();
void
activeSettingsChanged
();
void
storageFreeChanged
();
void
storageTotalChanged
();
void
dataReady
(
QByteArray
data
);
protected:
virtual
void
_setVideoStatus
(
VideoStatus
status
);
virtual
void
_setCameraMode
(
CameraMode
mode
);
private
slots
:
private
slots
:
void
_initWhenReady
();
void
_requestCameraSettings
();
void
_requestCameraSettings
();
void
_requestAllParameters
();
void
_requestAllParameters
();
void
_requestCaptureStatus
();
void
_requestStorageInfo
();
void
_downloadFinished
();
void
_mavCommandResult
(
int
vehicleId
,
int
component
,
int
command
,
int
result
,
bool
noReponseFromVehicle
);
void
_dataReady
(
QByteArray
data
);
private:
private:
bool
_handleLocalization
(
QByteArray
&
bytes
);
bool
_handleLocalization
(
QByteArray
&
bytes
);
bool
_replaceLocaleStrings
(
const
QDomNode
node
,
QByteArray
&
bytes
);
bool
_replaceLocaleStrings
(
const
QDomNode
node
,
QByteArray
&
bytes
);
bool
_loadCameraDefinitionFile
(
const
QString
&
file
);
bool
_loadCameraDefinitionFile
(
QByteArray
&
bytes
);
bool
_loadConstants
(
const
QDomNodeList
nodeList
);
bool
_loadConstants
(
const
QDomNodeList
nodeList
);
bool
_loadSettings
(
const
QDomNodeList
nodeList
);
bool
_loadSettings
(
const
QDomNodeList
nodeList
);
void
_processRanges
();
void
_processRanges
();
...
@@ -146,20 +179,26 @@ private:
...
@@ -146,20 +179,26 @@ private:
bool
_loadRanges
(
QDomNode
option
,
const
QString
factName
,
QString
paramValue
);
bool
_loadRanges
(
QDomNode
option
,
const
QString
factName
,
QString
paramValue
);
void
_updateActiveList
();
void
_updateActiveList
();
void
_updateRanges
(
Fact
*
pFact
);
void
_updateRanges
(
Fact
*
pFact
);
void
_httpRequest
(
const
QString
&
url
);
QStringList
_loadExclusions
(
QDomNode
option
);
QStringList
_loadExclusions
(
QDomNode
option
);
QString
_getParamName
(
const
char
*
param_id
);
QString
_getParamName
(
const
char
*
param_id
);
pr
ivate
:
pr
otected
:
Vehicle
*
_vehicle
;
Vehicle
*
_vehicle
;
int
_compID
;
int
_compID
;
mavlink_camera_information_t
_info
;
mavlink_camera_information_t
_info
;
int
_version
;
int
_version
;
uint32_t
_storageFree
;
uint32_t
_storageTotal
;
QNetworkAccessManager
*
_netManager
;
QString
_modelName
;
QString
_modelName
;
QString
_vendor
;
QString
_vendor
;
CameraMode
_cameraMode
;
CameraMode
_cameraMode
;
VideoStatus
_video_status
;
QStringList
_activeSettings
;
QStringList
_activeSettings
;
QStringList
_settings
;
QStringList
_settings
;
QTimer
_captureStatusTimer
;
QList
<
QGCCameraOptionExclusion
*>
_valueExclusions
;
QList
<
QGCCameraOptionExclusion
*>
_valueExclusions
;
QList
<
QGCCameraOptionRange
*>
_optionRanges
;
QList
<
QGCCameraOptionRange
*>
_optionRanges
;
QMap
<
QString
,
QStringList
>
_originalOptNames
;
QMap
<
QString
,
QStringList
>
_originalOptNames
;
...
...
src/Camera/QGCCameraIO.cc
View file @
a9621d2b
...
@@ -27,6 +27,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
...
@@ -27,6 +27,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
connect
(
&
_paramWriteTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramWriteTimeout
);
connect
(
&
_paramWriteTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramWriteTimeout
);
connect
(
&
_paramRequestTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramRequestTimeout
);
connect
(
&
_paramRequestTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramRequestTimeout
);
connect
(
_fact
,
&
Fact
::
rawValueChanged
,
this
,
&
QGCCameraParamIO
::
_factChanged
);
connect
(
_fact
,
&
Fact
::
rawValueChanged
,
this
,
&
QGCCameraParamIO
::
_factChanged
);
connect
(
_fact
,
&
Fact
::
_containerRawValueChanged
,
this
,
&
QGCCameraParamIO
::
_containerRawValueChanged
);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -43,12 +44,20 @@ void
...
@@ -43,12 +44,20 @@ void
QGCCameraParamIO
::
_factChanged
(
QVariant
value
)
QGCCameraParamIO
::
_factChanged
(
QVariant
value
)
{
{
Q_UNUSED
(
value
);
Q_UNUSED
(
value
);
qCDebug
(
CameraIOLog
)
<<
"Fact"
<<
_fact
->
name
()
<<
"changed"
;
qCDebug
(
CameraIOLog
)
<<
"UI Fact"
<<
_fact
->
name
()
<<
"changed"
;
_sendParameter
();
//-- TODO: Do we really want to update the UI now or only when we receive the ACK?
//-- TODO: Do we really want to update the UI now or only when we receive the ACK?
_control
->
factChanged
(
_fact
);
_control
->
factChanged
(
_fact
);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraParamIO
::
_containerRawValueChanged
(
const
QVariant
value
)
{
Q_UNUSED
(
value
);
qCDebug
(
CameraIOLog
)
<<
"Send Fact"
<<
_fact
->
name
()
<<
"changed"
;
_sendParameter
();
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraParamIO
::
_sendParameter
()
QGCCameraParamIO
::
_sendParameter
()
...
@@ -146,7 +155,7 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
...
@@ -146,7 +155,7 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
{
{
_paramWriteTimer
.
stop
();
_paramWriteTimer
.
stop
();
if
(
ack
.
param_result
==
PARAM_ACK_ACCEPTED
)
{
if
(
ack
.
param_result
==
PARAM_ACK_ACCEPTED
)
{
_fact
->
setRawValue
(
_valueFromMessage
(
ack
.
param_value
,
ack
.
param_type
),
true
);
_fact
->
_containerSetRawValue
(
_valueFromMessage
(
ack
.
param_value
,
ack
.
param_type
)
);
}
}
if
(
ack
.
param_result
==
PARAM_ACK_IN_PROGRESS
)
{
if
(
ack
.
param_result
==
PARAM_ACK_IN_PROGRESS
)
{
//-- Wait a bit longer for this one
//-- Wait a bit longer for this one
...
@@ -166,7 +175,7 @@ void
...
@@ -166,7 +175,7 @@ void
QGCCameraParamIO
::
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
)
QGCCameraParamIO
::
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
)
{
{
_paramRequestTimer
.
stop
();
_paramRequestTimer
.
stop
();
_fact
->
setRawValue
(
_valueFromMessage
(
value
.
param_value
,
value
.
param_type
),
true
);
_fact
->
_containerSetRawValue
(
_valueFromMessage
(
value
.
param_value
,
value
.
param_type
)
);
_paramRequestReceived
=
true
;
_paramRequestReceived
=
true
;
qCDebug
(
CameraIOLog
)
<<
QString
(
"handleParamValue() %1 %2"
).
arg
(
_fact
->
name
()).
arg
(
_fact
->
rawValueString
());
qCDebug
(
CameraIOLog
)
<<
QString
(
"handleParamValue() %1 %2"
).
arg
(
_fact
->
name
()).
arg
(
_fact
->
rawValueString
());
}
}
...
...
src/Camera/QGCCameraIO.h
View file @
a9621d2b
...
@@ -27,6 +27,7 @@ public:
...
@@ -27,6 +27,7 @@ public:
private
slots
:
private
slots
:
void
_factChanged
(
QVariant
value
);
void
_factChanged
(
QVariant
value
);
void
_containerRawValueChanged
(
const
QVariant
value
);
void
_paramWriteTimeout
();
void
_paramWriteTimeout
();
void
_paramRequestTimeout
();
void
_paramRequestTimeout
();
...
...
src/Camera/QGCCameraManager.cc
View file @
a9621d2b
...
@@ -50,22 +50,30 @@ QGCCameraManager::_vehicleReady(bool ready)
...
@@ -50,22 +50,30 @@ QGCCameraManager::_vehicleReady(bool ready)
void
void
QGCCameraManager
::
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
)
QGCCameraManager
::
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
)
{
{
switch
(
message
.
msgid
)
{
if
(
message
.
sysid
==
_vehicle
->
id
())
{
case
MAVLINK_MSG_ID_HEARTBEAT
:
switch
(
message
.
msgid
)
{
_handleHeartbeat
(
message
);
case
MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS
:
break
;
_handleCaptureStatus
(
message
);
case
MAVLINK_MSG_ID_CAMERA_INFORMATION
:
break
;
_handleCameraInfo
(
message
);
case
MAVLINK_MSG_ID_STORAGE_INFORMATION
:
break
;
_handleStorageInfo
(
message
);
case
MAVLINK_MSG_ID_CAMERA_SETTINGS
:
break
;
_handleCameraSettings
(
message
);
case
MAVLINK_MSG_ID_HEARTBEAT
:
break
;
_handleHeartbeat
(
message
);
case
MAVLINK_MSG_ID_PARAM_EXT_ACK
:
break
;
_handleParamAck
(
message
);
case
MAVLINK_MSG_ID_CAMERA_INFORMATION
:
break
;
_handleCameraInfo
(
message
);
case
MAVLINK_MSG_ID_PARAM_EXT_VALUE
:
break
;
_handleParamValue
(
message
);
case
MAVLINK_MSG_ID_CAMERA_SETTINGS
:
break
;
_handleCameraSettings
(
message
);
break
;
case
MAVLINK_MSG_ID_PARAM_EXT_ACK
:
_handleParamAck
(
message
);
break
;
case
MAVLINK_MSG_ID_PARAM_EXT_VALUE
:
_handleParamValue
(
message
);
break
;
}
}
}
}
}
...
@@ -120,6 +128,30 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
...
@@ -120,6 +128,30 @@ QGCCameraManager::_handleCameraInfo(const mavlink_message_t& message)
}
}
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_handleCaptureStatus
(
const
mavlink_message_t
&
message
)
{
QGCCameraControl
*
pCamera
=
_findCamera
(
message
.
compid
);
if
(
pCamera
)
{
mavlink_camera_capture_status_t
cap
;
mavlink_msg_camera_capture_status_decode
(
&
message
,
&
cap
);
pCamera
->
handleCaptureStatus
(
cap
);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager
::
_handleStorageInfo
(
const
mavlink_message_t
&
message
)
{
QGCCameraControl
*
pCamera
=
_findCamera
(
message
.
compid
);
if
(
pCamera
)
{
mavlink_storage_information_t
st
;
mavlink_msg_storage_information_decode
(
&
message
,
&
st
);
pCamera
->
handleStorageInfo
(
st
);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
QGCCameraManager
::
_handleCameraSettings
(
const
mavlink_message_t
&
message
)
QGCCameraManager
::
_handleCameraSettings
(
const
mavlink_message_t
&
message
)
...
...
src/Camera/QGCCameraManager.h
View file @
a9621d2b
...
@@ -23,7 +23,7 @@ class QGCCameraManager : public QObject
...
@@ -23,7 +23,7 @@ class QGCCameraManager : public QObject
Q_OBJECT
Q_OBJECT
public:
public:
QGCCameraManager
(
Vehicle
*
vehicle
);
QGCCameraManager
(
Vehicle
*
vehicle
);
~
QGCCameraManager
();
virtual
~
QGCCameraManager
();
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
cameras
READ
cameras
NOTIFY
camerasChanged
)
Q_PROPERTY
(
QString
controllerSource
READ
controllerSource
NOTIFY
controllerSourceChanged
)
Q_PROPERTY
(
QString
controllerSource
READ
controllerSource
NOTIFY
controllerSourceChanged
)
...
@@ -33,24 +33,26 @@ public:
...
@@ -33,24 +33,26 @@ public:
//-- Camera controller source (QML)
//-- Camera controller source (QML)
virtual
QString
controllerSource
();
virtual
QString
controllerSource
();
private
slots
:
void
_vehicleReady
(
bool
ready
);
void
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
);
signals:
signals:
void
camerasChanged
();
void
camerasChanged
();
void
controllerSourceChanged
();
void
controllerSourceChanged
();
private:
protected
slots
:
void
_vehicleReady
(
bool
ready
);
void
_mavlinkMessageReceived
(
const
mavlink_message_t
&
message
);
protected:
QGCCameraControl
*
_findCamera
(
int
id
);
QGCCameraControl
*
_findCamera
(
int
id
);
void
_requestCameraInfo
(
int
compID
);
void
_requestCameraInfo
(
int
compID
);
void
_handleHeartbeat
(
const
mavlink_message_t
&
message
);
void
_handleHeartbeat
(
const
mavlink_message_t
&
message
);
void
_handleCameraInfo
(
const
mavlink_message_t
&
message
);
void
_handleCameraInfo
(
const
mavlink_message_t
&
message
);
void
_handleStorageInfo
(
const
mavlink_message_t
&
message
);
void
_handleCameraSettings
(
const
mavlink_message_t
&
message
);
void
_handleCameraSettings
(
const
mavlink_message_t
&
message
);
void
_handleParamAck
(
const
mavlink_message_t
&
message
);
void
_handleParamAck
(
const
mavlink_message_t
&
message
);
void
_handleParamValue
(
const
mavlink_message_t
&
message
);
void
_handleParamValue
(
const
mavlink_message_t
&
message
);
void
_handleCaptureStatus
(
const
mavlink_message_t
&
message
);
pr
ivate
:
pr
otected
:
Vehicle
*
_vehicle
;
Vehicle
*
_vehicle
;
bool
_vehicleReadyState
;
bool
_vehicleReadyState
;
int
_cameraCount
;
int
_cameraCount
;
...
...
src/FactSystem/Fact.cc
View file @
a9621d2b
...
@@ -92,7 +92,7 @@ void Fact::forceSetRawValue(const QVariant& value)
...
@@ -92,7 +92,7 @@ void Fact::forceSetRawValue(const QVariant& value)
}
}
}
}
void
Fact
::
setRawValue
(
const
QVariant
&
value
,
bool
skipSignal
)
void
Fact
::
setRawValue
(
const
QVariant
&
value
)
{
{
if
(
_metaData
)
{
if
(
_metaData
)
{
QVariant
typedValue
;
QVariant
typedValue
;
...
@@ -102,10 +102,8 @@ void Fact::setRawValue(const QVariant& value, bool skipSignal)
...
@@ -102,10 +102,8 @@ void Fact::setRawValue(const QVariant& value, bool skipSignal)
if
(
typedValue
!=
_rawValue
)
{
if
(
typedValue
!=
_rawValue
)
{
_rawValue
.
setValue
(
typedValue
);
_rawValue
.
setValue
(
typedValue
);
_sendValueChangedSignal
(
cookedValue
());
_sendValueChangedSignal
(
cookedValue
());
if
(
!
skipSignal
)
{
emit
_containerRawValueChanged
(
rawValue
());
emit
_containerRawValueChanged
(
rawValue
());
emit
rawValueChanged
(
_rawValue
);
emit
rawValueChanged
(
_rawValue
);
}
}
}
}
}
}
else
{
}
else
{
...
...
src/FactSystem/Fact.h
View file @
a9621d2b
...
@@ -112,7 +112,7 @@ public:
...
@@ -112,7 +112,7 @@ public:
/// Returns the values as a string with full 18 digit precision if float/double.
/// Returns the values as a string with full 18 digit precision if float/double.
QString
rawValueStringFullPrecision
(
void
)
const
;
QString
rawValueStringFullPrecision
(
void
)
const
;
void
setRawValue
(
const
QVariant
&
value
,
bool
skipSignal
=
false
);
void
setRawValue
(
const
QVariant
&
value
);
void
setCookedValue
(
const
QVariant
&
value
);
void
setCookedValue
(
const
QVariant
&
value
);
void
setEnumIndex
(
int
index
);
void
setEnumIndex
(
int
index
);
void
setEnumStringValue
(
const
QString
&
value
);
void
setEnumStringValue
(
const
QString
&
value
);
...
@@ -135,6 +135,8 @@ public:
...
@@ -135,6 +135,8 @@ public:
void
setMetaData
(
FactMetaData
*
metaData
);
void
setMetaData
(
FactMetaData
*
metaData
);
FactMetaData
*
metaData
()
{
return
_metaData
;
}
FactMetaData
*
metaData
()
{
return
_metaData
;
}
//-- Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
void
_containerSetRawValue
(
const
QVariant
&
value
);
void
_containerSetRawValue
(
const
QVariant
&
value
);
/// Generally you should not change the name of a fact. But if you know what you are doing, you can.
/// Generally you should not change the name of a fact. But if you know what you are doing, you can.
...
@@ -161,7 +163,7 @@ signals:
...
@@ -161,7 +163,7 @@ signals:
/// Signalled when property has been changed by a call to the property write accessor
/// Signalled when property has been changed by a call to the property write accessor
///
///
/// This signal is meant for use by Fact container implementations.
/// This signal is meant for use by Fact container implementations.
Used to send changed values to vehicle.
void
_containerRawValueChanged
(
const
QVariant
&
value
);
void
_containerRawValueChanged
(
const
QVariant
&
value
);
protected:
protected:
...
...
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