@@ -35,7 +35,8 @@ class NodeletCamera: public nodelet::Nodelet
3535{
3636public:
3737 NodeletCamera () :
38- cameraStarted_ (false )
38+ cameraStarted_ (false ),
39+ intialize_time_base_ (false )
3940 {
4041 // Types for depth stream
4142 format_[rs::stream::depth] = rs::format::z16; // libRS type
@@ -209,11 +210,6 @@ class NodeletCamera: public nodelet::Nodelet
209210 info_publisher_[rs::stream::fisheye] =
210211 node_handle.advertise < sensor_msgs::CameraInfo >(" camera/fisheye/camera_info" , 1 );
211212
212- // HW timestamp version of image publishers, for realsense_ros_slam package
213- image_publishers_hw_timestamp_[rs::stream::color] = node_handle.advertise <sensor_msgs::Image>(" /camera/color/image_raw_hw_timestamp" , 1 );
214- image_publishers_hw_timestamp_[rs::stream::depth] = node_handle.advertise <sensor_msgs::Image>(" /camera/depth/image_raw_hw_timestamp" , 1 );
215- image_publishers_hw_timestamp_[rs::stream::fisheye] = node_handle.advertise <sensor_msgs::Image>(" /camera/fisheye/image_raw_hw_timestamp" , 1 );
216-
217213 imu_publishers_[RS_EVENT_IMU_GYRO] = node_handle.advertise < sensor_msgs::Imu >(" camera/gyro/sample" , 100 );
218214 imu_publishers_[RS_EVENT_IMU_ACCEL] = node_handle.advertise < sensor_msgs::Imu >(" camera/accel/sample" , 100 );
219215
@@ -240,14 +236,33 @@ class NodeletCamera: public nodelet::Nodelet
240236 stream_callback_per_stream[stream] = [this ,stream](rs::frame frame)
241237 {
242238 image_[stream].data = (unsigned char *) frame.get_data ();
243- ros::Time t = ros::Time::now ();
239+
240+ if ((true == isZR300_) && (rs::timestamp_domain::microcontroller != frame.get_frame_timestamp_domain ()))
241+ {
242+ ROS_ERROR_STREAM (" error: Junk time stamp in stream:" << (int )(stream) <<
243+ " \t with frame counter:" << frame.get_frame_number ());
244+ return ;
245+ }
246+
247+ // We compute a ROS timestamp which is based on an initial ROS time at point of first frame,
248+ // and the incremental timestamp from the camera.
249+ if (false == intialize_time_base_)
250+ {
251+ intialize_time_base_ = true ;
252+ ros_time_base_ = ros::Time::now ();
253+ camera_time_base_ = frame.get_timestamp ();
254+ }
255+ double elapsed_camera_ms = (/* ms*/ frame.get_timestamp () - /* ms*/ camera_time_base_) / /* ms to seconds*/ 1000 ;
256+ ros::Time t (ros_time_base_.toSec () + elapsed_camera_ms);
244257
258+ // If this stream is associated with depth and we have at least one point cloud subscriber,
259+ // service it here.
245260 if ((stream == rs::stream::depth) && (0 != pointcloud_publisher_.getNumSubscribers ()))
246261 publishPCTopic (t);
247262
248- seq_[stream] += 1 ;
249- if ((0 != image_publishers_ [stream].getNumSubscribers ()) ||
250- (0 != image_publishers_hw_timestamp_ [stream].getNumSubscribers ()))
263+ seq_[stream] += 1 ;
264+ if ((0 != info_publisher_ [stream].getNumSubscribers ()) ||
265+ (0 != image_publishers_ [stream].getNumSubscribers ()))
251266 {
252267 sensor_msgs::ImagePtr img;
253268 img = cv_bridge::CvImage (std_msgs::Header (), encoding_[stream], image_[stream]).toImageMsg ();
@@ -259,28 +274,8 @@ class NodeletCamera: public nodelet::Nodelet
259274 img->header .stamp = t;
260275 img->header .seq = seq_[stream];
261276
262- // ROS Timestamp
263- if (0 != image_publishers_[stream].getNumSubscribers ())
264- image_publishers_[stream].publish (img);
265-
266- // Camera HW Timestamp for realsense_ros_slam
267- if (0 != image_publishers_hw_timestamp_[stream].getNumSubscribers ())
268- {
269- if (rs::timestamp_domain::microcontroller != frame.get_frame_timestamp_domain ())
270- {
271- ROS_ERROR_STREAM (" error: Junk time stamp in stream:" << (int )(stream) <<
272- " \t with frame counter:" << frame.get_frame_number ());
273- }
274- else
275- {
276- img->header .stamp = ros::Time (frame.get_timestamp ());
277- image_publishers_hw_timestamp_[stream].publish (img);
278- }
279- }
280- }
281-
282- if (0 != image_publishers_[stream].getNumSubscribers ())
283- {
277+ image_publishers_[stream].publish (img);
278+
284279 camera_info_[stream].header .stamp = t;
285280 camera_info_[stream].header .seq = seq_[stream];
286281 info_publisher_[stream].publish (camera_info_[stream]);
@@ -307,6 +302,7 @@ class NodeletCamera: public nodelet::Nodelet
307302 {
308303 // Needed to align image timestamps to common clock-domain with the motion events
309304 device_->set_option (rs::option::fisheye_strobe, 1 );
305+
310306 // This option causes the fisheye image to be aquired in-sync with the depth image.
311307 device_->set_option (rs::option::fisheye_external_trigger, 1 );
312308 device_->set_option (rs::option::fisheye_color_auto_exposure, 1 );
@@ -328,8 +324,12 @@ class NodeletCamera: public nodelet::Nodelet
328324 if ( 0 == imu_publishers_[motionType].getNumSubscribers ())
329325 return ;
330326
327+ if (false == intialize_time_base_)
328+ return ;
329+ double elapsed_camera_ms = (/* ms*/ entry.timestamp_data .timestamp - /* ms*/ camera_time_base_) / /* ms to seconds*/ 1000 ;
330+ ros::Time t (ros_time_base_.toSec () + elapsed_camera_ms);
331+
331332 sensor_msgs::Imu imu_msg = sensor_msgs::Imu ();
332- imu_msg.header .stamp = ros::Time::now ();
333333 imu_msg.header .frame_id = optical_imu_id_[motionType];
334334 imu_msg.orientation .x = 0.0 ;
335335 imu_msg.orientation .y = 0.0 ;
@@ -350,7 +350,7 @@ class NodeletCamera: public nodelet::Nodelet
350350 }
351351 seq_motion[motionType] += 1 ;
352352 imu_msg.header .seq = seq_motion[motionType];
353- imu_msg.header .stamp = ros::Time (entry. timestamp_data . timestamp ) ;
353+ imu_msg.header .stamp = t ;
354354 imu_publishers_[motionType].publish (imu_msg);
355355 };
356356
@@ -703,7 +703,6 @@ class NodeletCamera: public nodelet::Nodelet
703703
704704 // R200 and ZR300 types
705705 std::map<rs::stream, image_transport::Publisher> image_publishers_;
706- std::map<rs::stream, ros::Publisher> image_publishers_hw_timestamp_;
707706 std::map<rs::stream, int > image_format_;
708707 std::map<rs::stream, rs::format> format_;
709708 std::map<rs::stream, ros::Publisher> info_publisher_;
@@ -718,6 +717,9 @@ class NodeletCamera: public nodelet::Nodelet
718717 std::map<rs::stream, std::function<void (rs::frame)>> stream_callback_per_stream;
719718 std::map<rs::stream, sensor_msgs::CameraInfo> camera_info_;
720719 ros::Publisher pointcloud_publisher_;
720+ bool intialize_time_base_;
721+ double camera_time_base_;
722+ ros::Time ros_time_base_;
721723
722724 // ZR300 specific types
723725 bool isZR300_ = false ;
0 commit comments