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
696cf7c8
Commit
696cf7c8
authored
Aug 09, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Allow derived classes to process and validate incoming parameters.
Retry requests for storage and capture info.
parent
2a777cc8
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
53 additions
and
5 deletions
+53
-5
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+43
-4
QGCCameraControl.h
src/Camera/QGCCameraControl.h
+6
-0
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+4
-1
No files found.
src/Camera/QGCCameraControl.cc
View file @
696cf7c8
...
...
@@ -119,6 +119,8 @@ QGCCameraControl::QGCCameraControl(const mavlink_camera_information_t *info, Veh
,
_netManager
(
NULL
)
,
_cameraMode
(
CAM_MODE_UNDEFINED
)
,
_video_status
(
VIDEO_CAPTURE_STATUS_UNDEFINED
)
,
_storageInfoRetries
(
0
)
,
_captureInfoRetries
(
0
)
{
QQmlEngine
::
setObjectOwnership
(
this
,
QQmlEngine
::
CppOwnership
);
memcpy
(
&
_info
,
info
,
sizeof
(
mavlink_camera_information_t
));
...
...
@@ -414,12 +416,40 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
case
MAV_CMD_VIDEO_STOP_CAPTURE
:
_setVideoStatus
(
VIDEO_CAPTURE_STATUS_STOPPED
);
break
;
case
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
:
_captureInfoRetries
=
0
;
break
;
case
MAV_CMD_REQUEST_STORAGE_INFORMATION
:
_storageInfoRetries
=
0
;
break
;
}
}
else
{
if
(
noReponseFromVehicle
)
{
qCDebug
(
CameraControlLog
)
<<
"No response for"
<<
command
;
if
(
noReponseFromVehicle
||
result
==
MAV_RESULT_TEMPORARILY_REJECTED
||
result
==
MAV_RESULT_FAILED
)
{
if
(
noReponseFromVehicle
)
{
qCDebug
(
CameraControlLog
)
<<
"No response for"
<<
command
;
}
else
if
(
result
==
MAV_RESULT_TEMPORARILY_REJECTED
)
{
qCDebug
(
CameraControlLog
)
<<
"Command temporarily rejected for"
<<
command
;
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Command failed for"
<<
command
;
}
switch
(
command
)
{
case
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
:
if
(
++
_captureInfoRetries
<
3
)
{
_requestCaptureStatus
();
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Giving up requesting capture status"
;
}
break
;
case
MAV_CMD_REQUEST_STORAGE_INFORMATION
:
if
(
++
_storageInfoRetries
<
3
)
{
_requestStorageInfo
();
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Giving up requesting storage status"
;
}
break
;
}
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Bad response for"
<<
command
;
qCDebug
(
CameraControlLog
)
<<
"Bad response for"
<<
command
<<
result
;
}
}
}
...
...
@@ -951,7 +981,7 @@ QGCCameraControl::_updateRanges(Fact* pFact)
}
//-- Parameter update requests
if
(
_requestUpdates
.
contains
(
pFact
->
name
()))
{
_requestAllParameters
(
);
QTimer
::
singleShot
(
250
,
this
,
&
QGCCameraControl
::
_requestAllParameters
);
}
//-- Update UI (Asynchronous state where values come back after a while)
if
(
_updates
.
size
())
{
...
...
@@ -1260,3 +1290,12 @@ QGCCameraControl::_paramDone()
//-- All parameters loaded (or timed out)
emit
parametersReady
();
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
incomingParameter
(
Fact
*
pFact
,
QVariant
&
newValue
)
{
Q_UNUSED
(
pFact
);
Q_UNUSED
(
newValue
);
return
true
;
}
src/Camera/QGCCameraControl.h
View file @
696cf7c8
...
...
@@ -142,7 +142,11 @@ public:
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
);
//-- Notify controller a parameter has changed
virtual
void
factChanged
(
Fact
*
pFact
);
//-- Allow controller to modify or invalidate incoming parameter
virtual
bool
incomingParameter
(
Fact
*
pFact
,
QVariant
&
newValue
);
signals:
void
infoChanged
();
...
...
@@ -213,6 +217,8 @@ protected:
QMap
<
QString
,
QVariantList
>
_originalOptValues
;
QMap
<
QString
,
QGCCameraParamIO
*>
_paramIO
;
QVector
<
Fact
*>
_updates
;
int
_storageInfoRetries
;
int
_captureInfoRetries
;
//-- Parameters that require a full update
QStringList
_requestUpdates
;
};
src/Camera/QGCCameraIO.cc
View file @
696cf7c8
...
...
@@ -211,7 +211,10 @@ void
QGCCameraParamIO
::
handleParamValue
(
const
mavlink_param_ext_value_t
&
value
)
{
_paramRequestTimer
.
stop
();
_fact
->
_containerSetRawValue
(
_valueFromMessage
(
value
.
param_value
,
value
.
param_type
));
QVariant
newValue
=
_valueFromMessage
(
value
.
param_value
,
value
.
param_type
);
if
(
_control
->
incomingParameter
(
_fact
,
newValue
))
{
_fact
->
_containerSetRawValue
(
newValue
);
}
_paramRequestReceived
=
true
;
if
(
!
_done
)
{
_done
=
true
;
...
...
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