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
2995ae9f
Commit
2995ae9f
authored
Jul 20, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Broadcast camera parameter loading done.
parent
2eeee80e
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
31 additions
and
2 deletions
+31
-2
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+17
-2
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+3
-0
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+9
-0
QGCCameraIO.h
src/Camera/QGCCameraIO.h
+2
-0
No files found.
src/Camera/QGCCameraControl.cc
View file @
2995ae9f
...
...
@@ -117,9 +117,9 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
{
memcpy
(
&
_info
,
&
info
,
sizeof
(
mavlink_camera_information_t
));
connect
(
this
,
&
QGCCameraControl
::
dataReady
,
this
,
&
QGCCameraControl
::
_dataReady
);
if
(
_info
.
cam_definition_uri
[
0
])
{
const
char
*
url
=
(
const
char
*
)
info
->
cam_definition_uri
;
if
(
url
[
0
]
!=
0
)
{
//-- Process camera definition file
const
char
*
url
=
(
const
char
*
)
info
->
cam_definition_uri
;
_httpRequest
(
url
);
}
else
{
_initWhenReady
();
...
...
@@ -1114,6 +1114,21 @@ QGCCameraControl::_dataReady(QByteArray data)
if
(
data
.
size
())
{
qCDebug
(
CameraControlLog
)
<<
"Parsing camera definition"
;
_loadCameraDefinitionFile
(
data
);
}
else
{
qCDebug
(
CameraControlLog
)
<<
"No camera definition"
;
}
_initWhenReady
();
}
//-----------------------------------------------------------------------------
void
QGCCameraControl
::
_paramDone
()
{
foreach
(
QString
param
,
_paramIO
.
keys
())
{
if
(
!
_paramIO
[
param
]
->
paramDone
())
{
return
;
}
}
//-- All parameters loaded (or timed out)
paramLoadCompleted
();
}
src/Camera/QGCCameraControl.h
View file @
2995ae9f
...
...
@@ -60,6 +60,7 @@ public:
class
QGCCameraControl
:
public
FactGroup
{
Q_OBJECT
friend
class
QGCCameraParamIO
;
public:
QGCCameraControl
(
const
mavlink_camera_information_t
*
info
,
Vehicle
*
vehicle
,
int
compID
,
QObject
*
parent
=
NULL
);
virtual
~
QGCCameraControl
();
...
...
@@ -142,6 +143,7 @@ public:
virtual
void
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
);
virtual
void
handleStorageInfo
(
const
mavlink_storage_information_t
&
st
);
virtual
void
factChanged
(
Fact
*
pFact
);
virtual
void
paramLoadCompleted
()
{;}
signals:
void
infoChanged
();
...
...
@@ -165,6 +167,7 @@ private slots:
void
_downloadFinished
();
void
_mavCommandResult
(
int
vehicleId
,
int
component
,
int
command
,
int
result
,
bool
noReponseFromVehicle
);
void
_dataReady
(
QByteArray
data
);
void
_paramDone
();
private:
bool
_handleLocalization
(
QByteArray
&
bytes
);
...
...
src/Camera/QGCCameraIO.cc
View file @
2995ae9f
...
...
@@ -19,6 +19,7 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
,
_vehicle
(
vehicle
)
,
_sentRetries
(
0
)
,
_requestRetries
(
0
)
,
_done
(
false
)
{
_paramWriteTimer
.
setSingleShot
(
true
);
_paramWriteTimer
.
setInterval
(
3000
);
...
...
@@ -177,6 +178,10 @@ QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
_paramRequestTimer
.
stop
();
_fact
->
_containerSetRawValue
(
_valueFromMessage
(
value
.
param_value
,
value
.
param_type
));
_paramRequestReceived
=
true
;
if
(
!
_done
)
{
_done
=
true
;
_control
->
_paramDone
();
}
qCDebug
(
CameraIOLog
)
<<
QString
(
"handleParamValue() %1 %2"
).
arg
(
_fact
->
name
()).
arg
(
_fact
->
rawValueString
());
}
...
...
@@ -224,6 +229,10 @@ QGCCameraParamIO::_paramRequestTimeout()
{
if
(
++
_requestRetries
>
3
)
{
qCWarning
(
CameraIOLog
)
<<
"No response for param request:"
<<
_fact
->
name
();
if
(
!
_done
)
{
_done
=
true
;
_control
->
_paramDone
();
}
}
else
{
//-- Request it again
qCDebug
(
CameraIOLog
)
<<
"Param request retry:"
<<
_fact
->
name
();
...
...
src/Camera/QGCCameraIO.h
View file @
2995ae9f
...
...
@@ -24,6 +24,7 @@ public:
void
handleParamAck
(
const
mavlink_param_ext_ack_t
&
ack
);
void
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
);
void
setParamRequest
();
bool
paramDone
()
{
return
_done
;
}
private
slots
:
void
_factChanged
(
QVariant
value
);
...
...
@@ -46,5 +47,6 @@ private:
mavlink_message_t
_msg
;
QTimer
_paramWriteTimer
;
QTimer
_paramRequestTimer
;
bool
_done
;
};
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