Skip to content
GitLab
Menu
Projects
Groups
Snippets
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
mobile_robotics
ADC
external
libuvc_ros
Commits
c0714417
Commit
c0714417
authored
Sep 25, 2013
by
Ken Tossell
Browse files
Fixed image and cinfo headers' frame + timestamp (from fuerte branch).
parent
928a5c3e
Changes
1
Hide whitespace changes
Inline
Side-by-side
libuvc_camera/src/camera_driver.cpp
View file @
c0714417
...
...
@@ -146,6 +146,9 @@ void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t lev
}
void
CameraDriver
::
ImageCallback
(
uvc_frame_t
*
frame
)
{
// TODO: Switch to {frame}'s timestamp once that becomes reliable.
ros
::
Time
timestamp
=
ros
::
Time
::
now
();
boost
::
recursive_mutex
::
scoped_lock
(
mutex_
);
assert
(
state_
==
kRunning
);
...
...
@@ -169,6 +172,11 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
sensor_msgs
::
CameraInfo
::
ConstPtr
cinfo
(
new
sensor_msgs
::
CameraInfo
(
cinfo_manager_
.
getCameraInfo
()));
image
->
header
.
frame_id
=
config_
.
frame_id
;
image
->
header
.
stamp
=
timestamp
;
cinfo
->
header
.
frame_id
=
config_
.
frame_id
;
cinfo
->
header
.
stamp
=
timestamp
;
cam_pub_
.
publish
(
image
,
cinfo
);
if
(
config_changed_
)
{
...
...
Write
Preview
Supports
Markdown
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