diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp index 7fa5aeec2c205cdb07f88c179b010ad22214111c..34024f197ba15c2eaabf428653ba64d8951fd290 100644 --- a/libuvc_camera/src/camera_driver.cpp +++ b/libuvc_camera/src/camera_driver.cpp @@ -162,7 +162,7 @@ void CameraDriver::ReconfigureCallback(UVCCameraConfig &new_config, uint32_t lev } void CameraDriver::ImageCallback(uvc_frame_t *frame) { - ros::Time timestamp = ros::Time(frame->capture_time.tv_sec, frame->capture_time.tv_usec); + ros::Time timestamp = ros::Time::now(); boost::recursive_mutex::scoped_lock(mutex_);