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
997793a6
Unverified
Commit
997793a6
authored
Mar 27, 2019
by
Gus Grubba
Committed by
GitHub
Mar 27, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7325 from mavlink/videoReceiver
Make sure video streaming is running before accessing it.
parents
47d1f9f9
976d14bd
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
22 additions
and
13 deletions
+22
-13
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+15
-8
Vehicle.cc
src/Vehicle/Vehicle.cc
+7
-5
No files found.
src/Camera/QGCCameraControl.cc
View file @
997793a6
...
...
@@ -364,10 +364,12 @@ QGCCameraControl::takePhoto()
_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
);
photoPath
+=
+
"/"
+
QDateTime
::
currentDateTime
().
toString
(
"yyyy-MM-dd_hh.mm.ss.zzz"
)
+
".jpg"
;
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
()
->
grabImage
(
photoPath
);
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
())
{
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
;
}
}
...
...
@@ -667,6 +669,9 @@ QGCCameraControl::_mavCommandResult(int vehicleId, int component, int command, i
case
MAV_CMD_REQUEST_STORAGE_INFORMATION
:
_storageInfoRetries
=
0
;
break
;
case
MAV_CMD_IMAGE_START_CAPTURE
:
_captureStatusTimer
.
start
(
1000
);
break
;
}
}
else
{
if
(
noReponseFromVehicle
||
result
==
MAV_RESULT_TEMPORARILY_REJECTED
||
result
==
MAV_RESULT_FAILED
)
{
...
...
@@ -1471,10 +1476,12 @@ QGCCameraControl::handleCaptureStatus(const mavlink_camera_capture_status_t& cap
//-- Time Lapse
if
(
photoStatus
()
==
PHOTO_CAPTURE_INTERVAL_IDLE
||
photoStatus
()
==
PHOTO_CAPTURE_INTERVAL_IN_PROGRESS
)
{
//-- 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
);
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
())
{
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
);
}
}
}
...
...
src/Vehicle/Vehicle.cc
View file @
997793a6
...
...
@@ -1640,9 +1640,11 @@ void Vehicle::_updateArmed(bool armed)
}
else
{
_mapTrajectoryStop
();
// Also handle Video Streaming
if
(
_settingsManager
->
videoSettings
()
->
disableWhenDisarmed
()
->
rawValue
().
toBool
())
{
_settingsManager
->
videoSettings
()
->
streamEnabled
()
->
setRawValue
(
false
);
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
()
->
stop
();
if
(
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
())
{
if
(
_settingsManager
->
videoSettings
()
->
disableWhenDisarmed
()
->
rawValue
().
toBool
())
{
_settingsManager
->
videoSettings
()
->
streamEnabled
()
->
setRawValue
(
false
);
qgcApp
()
->
toolbox
()
->
videoManager
()
->
videoReceiver
()
->
stop
();
}
}
}
}
...
...
@@ -1654,8 +1656,8 @@ void Vehicle::_handlePing(LinkInterface* link, mavlink_message_t& message)
mavlink_message_t
msg
;
mavlink_msg_ping_decode
(
&
message
,
&
ping
);
mavlink_msg_ping_pack_chan
(
_mavlink
->
getSystemId
(
),
_mavlink
->
getComponentId
(
),
mavlink_msg_ping_pack_chan
(
static_cast
<
uint8_t
>
(
_mavlink
->
getSystemId
()
),
static_cast
<
uint8_t
>
(
_mavlink
->
getComponentId
()
),
priorityLink
()
->
mavlinkChannel
(),
&
msg
,
ping
.
time_usec
,
...
...
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