diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp
index 0e4dc966bc3227f8cadc7f88a5c420e2d9566c62..5b6e6115f2cd84662e220794c9015c5c2ea80a7b 100644
--- a/libuvc_camera/src/camera_driver.cpp
+++ b/libuvc_camera/src/camera_driver.cpp
@@ -163,6 +163,9 @@ 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);
+  if ( timestamp == ros::Time(0) ) {
+    timestamp = ros::Time::now();
+  }
 
   boost::recursive_mutex::scoped_lock(mutex_);