diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp
index 3690d546795a13d9924e2dc83bd22d0cefbe4b5d..3494fa2ea0b38683e2d428de061900155e748976 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_);