diff --git a/libuvc_camera/src/camera_driver.cpp b/libuvc_camera/src/camera_driver.cpp
index 10cdd51986d919502607c106d949e7a8c3070994..1bb849160379ad203c48435eb2df9c7a8b901d66 100644
--- a/libuvc_camera/src/camera_driver.cpp
+++ b/libuvc_camera/src/camera_driver.cpp
@@ -159,6 +159,8 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
     return;
   }
 
+  ros::Time timestamp = ros::Time::now();
+
   sensor_msgs::Image::Ptr image(new sensor_msgs::Image());
   image->width = config_.width;
   image->height = config_.height;
@@ -174,6 +176,8 @@ void CameraDriver::ImageCallback(uvc_frame_t *frame) {
   std_msgs::Header::Ptr cinfoheader(new std_msgs::Header());
   imageheader->frame_id = config_.frame_id;
   cinfoheader->frame_id = config_.frame_id;
+  imageheader->stamp = timestamp;
+  cinfoheader->stamp = timestamp;
   image->header = *imageheader;
   cinfo->header = *cinfoheader;