Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
2f17ab70
Commit
2f17ab70
authored
Aug 28, 2017
by
Gus Grubba
Browse files
Handle capture status retries when capturing images.
Allow plugin to validate parameter setting.
parent
4bf28634
Changes
3
Hide whitespace changes
Inline
Side-by-side
src/Camera/QGCCameraControl.cc
View file @
2f17ab70
...
...
@@ -272,6 +272,7 @@ QGCCameraControl::takePhoto()
0
,
// Duration between two consecutive pictures (in seconds--ignored if single image)
1
);
// Number of images to capture total - 0 for unlimited capture
_setPhotoStatus
(
PHOTO_CAPTURE_IN_PROGRESS
);
_captureInfoRetries
=
0
;
//-- Capture local image as well
QString
photoPath
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
()
->
savePath
()
->
rawValue
().
toString
()
+
QStringLiteral
(
"/Photo"
);
QDir
().
mkpath
(
photoPath
);
...
...
@@ -384,6 +385,7 @@ QGCCameraControl::formatCard(int id)
void
QGCCameraControl
::
_requestCaptureStatus
()
{
qCDebug
(
CameraControlLog
)
<<
"_requestCaptureStatus()"
;
_vehicle
->
sendMavCommand
(
_compID
,
// target component
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
,
// command id
...
...
@@ -445,16 +447,23 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
qCDebug
(
CameraControlLog
)
<<
"Command failed for"
<<
command
;
}
switch
(
command
)
{
case
MAV_CMD_IMAGE_START_CAPTURE
:
if
(
++
_captureInfoRetries
<
5
)
{
_captureStatusTimer
.
start
(
1000
);
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Giving up requesting capture status"
;
}
break
;
case
MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS
:
if
(
++
_captureInfoRetries
<
3
)
{
_
requestC
aptureStatus
(
);
_
c
aptureStatus
Timer
.
start
(
500
);
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Giving up requesting capture status"
;
}
break
;
case
MAV_CMD_REQUEST_STORAGE_INFORMATION
:
if
(
++
_storageInfoRetries
<
3
)
{
_requestStorageInfo
(
);
QTimer
::
singleShot
(
500
,
this
,
&
QGCCameraControl
::
_requestStorageInfo
);
}
else
{
qCDebug
(
CameraControlLog
)
<<
"Giving up requesting storage status"
;
}
...
...
@@ -1349,3 +1358,12 @@ QGCCameraControl::incomingParameter(Fact* pFact, QVariant& newValue)
Q_UNUSED
(
newValue
);
return
true
;
}
//-----------------------------------------------------------------------------
bool
QGCCameraControl
::
validateParameter
(
Fact
*
pFact
,
QVariant
&
newValue
)
{
Q_UNUSED
(
pFact
);
Q_UNUSED
(
newValue
);
return
true
;
}
src/Camera/QGCCameraControl.h
View file @
2f17ab70
...
...
@@ -161,6 +161,8 @@ public:
virtual
void
factChanged
(
Fact
*
pFact
);
//-- Allow controller to modify or invalidate incoming parameter
virtual
bool
incomingParameter
(
Fact
*
pFact
,
QVariant
&
newValue
);
//-- Allow controller to modify or invalidate parameter change
virtual
bool
validateParameter
(
Fact
*
pFact
,
QVariant
&
newValue
);
signals:
void
infoChanged
();
...
...
src/Camera/QGCCameraIO.cc
View file @
2f17ab70
...
...
@@ -204,7 +204,9 @@ QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t& ack)
//-- If UI changed and value was not set, restore UI
QVariant
val
=
_valueFromMessage
(
ack
.
param_value
,
ack
.
param_type
);
if
(
_fact
->
rawValue
()
!=
val
)
{
_fact
->
_containerSetRawValue
(
val
);
if
(
_control
->
validateParameter
(
_fact
,
val
))
{
_fact
->
_containerSetRawValue
(
val
);
}
}
}
}
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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