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
6580a544
Unverified
Commit
6580a544
authored
Jan 21, 2019
by
Gus Grubba
Committed by
GitHub
Jan 21, 2019
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #7178 from mavlink/handleCameraInfo
Prevent testing nullified camera info request
parents
0102d7bd
c226e432
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
19 additions
and
16 deletions
+19
-16
QGCCameraManager.cc
src/Camera/QGCCameraManager.cc
+19
-16
No files found.
src/Camera/QGCCameraManager.cc
View file @
6580a544
...
...
@@ -110,29 +110,32 @@ QGCCameraManager::_handleHeartbeat(const mavlink_message_t &message)
if
(
_vehicleReadyState
&&
_vehicle
->
id
()
==
message
.
sysid
&&
_vehicle
->
defaultComponentId
()
!=
message
.
compid
)
{
//-- First time hearing from this one?
if
(
!
_cameraInfoRequest
.
contains
(
message
.
compid
))
{
qCDebug
(
CameraManagerLog
)
<<
"Hearbeat from "
<<
message
.
compid
;
CameraStruct
*
pInfo
=
new
CameraStruct
(
this
);
pInfo
->
lastHeartbeat
.
start
();
_cameraInfoRequest
[
message
.
compid
]
=
pInfo
;
//-- Request camera info
_requestCameraInfo
(
message
.
compid
);
}
else
{
//-- Check if we have indeed received the camera info
if
(
_cameraInfoRequest
[
message
.
compid
]
->
infoReceived
)
{
//-- We have it. Just update the heartbeat timeout
_cameraInfoRequest
[
message
.
compid
]
->
lastHeartbeat
.
start
();
}
else
{
//-- Try again. Maybe.
if
(
_cameraInfoRequest
[
message
.
compid
]
->
lastHeartbeat
.
elapsed
()
>
2000
)
{
if
(
_cameraInfoRequest
[
message
.
compid
]
->
tryCount
>
3
)
{
if
(
!
_cameraInfoRequest
[
message
.
compid
]
->
gaveUp
)
{
_cameraInfoRequest
[
message
.
compid
]
->
gaveUp
=
true
;
qWarning
()
<<
"Giving up requesting camera info from"
<<
_vehicle
->
id
()
<<
message
.
compid
;
if
(
_cameraInfoRequest
[
message
.
compid
])
{
//-- Check if we have indeed received the camera info
if
(
_cameraInfoRequest
[
message
.
compid
]
->
infoReceived
)
{
//-- We have it. Just update the heartbeat timeout
_cameraInfoRequest
[
message
.
compid
]
->
lastHeartbeat
.
start
();
}
else
{
//-- Try again. Maybe.
if
(
_cameraInfoRequest
[
message
.
compid
]
->
lastHeartbeat
.
elapsed
()
>
2000
)
{
if
(
_cameraInfoRequest
[
message
.
compid
]
->
tryCount
>
3
)
{
if
(
!
_cameraInfoRequest
[
message
.
compid
]
->
gaveUp
)
{
_cameraInfoRequest
[
message
.
compid
]
->
gaveUp
=
true
;
qWarning
()
<<
"Giving up requesting camera info from"
<<
_vehicle
->
id
()
<<
message
.
compid
;
}
}
else
{
_cameraInfoRequest
[
message
.
compid
]
->
tryCount
++
;
//-- Request camera info. Again. It could be something other than a camera, in which
// case, we won't ever receive it.
_requestCameraInfo
(
message
.
compid
);
}
}
else
{
_cameraInfoRequest
[
message
.
compid
]
->
tryCount
++
;
//-- Request camera info. Again. It could be something other than a camera, in which
// case, we won't ever receive it.
_requestCameraInfo
(
message
.
compid
);
}
}
}
...
...
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