From 78e93b99f16ee3ffe89eff76235fd531099b7918 Mon Sep 17 00:00:00 2001
From: Furushchev <furushchev@jsk.imi.i.u-tokyo.ac.jp>
Date: Sun, 4 Oct 2015 23:17:25 +0900
Subject: [PATCH] [libuvc_camera/src/camera_driver.cpp] use frame's capture
 time for timestamp of ros message instead of callback time

---
 libuvc_camera/src/camera_driver.cpp | 3 +--
 1 file changed, 1 insertion(+), 2 deletions(-)

diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp
index 3690d54..3494fa2 100644
--- a/libuvc_camera/src/camera_driver.cpp
+++ b/libuvc_camera/src/camera_driver.cpp
@@ -157,8 +157,7 @@ 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();
+  ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec);
 
   boost::recursive_mutex::scoped_lock(mutex_);
 
-- 
GitLab