Synchronization of RGB and depth topics in ASUS Xtion

asked 2020-10-23 02:46:34 -0500

thanasis_t gravatar image

updated 2022-05-23 09:19:52 -0500

lucasw gravatar image

I am checking whether the /camera/rgb/image_raw and the /camera/depth/image topics of the ASUS Xtion camera are synchronized. For that purpose, I have a simple script with two different subscriptions in the topics and each time I print the difference of the timestamps. The code is shown below.

#include <ros/ros.h>
#include <sensor_msgs/Image.h>

long double rgb_time, depth_time;


void callback_rgb(const sensor_msgs::ImagePtr& rgb){
    rgb_time = rgb->header.stamp.toSec();
    ROS_INFO("Difference between rgb and depth: %Lf", abs(rgb_time-depth_time));
}

void callback_depth(const sensor_msgs::ImagePtr& depth){
    depth_time = depth->header.stamp.toSec();
}


int main(int argc, char** argv){
    ros::init(argc, argv, "queue_points");
    ros::NodeHandle nh;

    ros::Subscriber sub = nh.subscribe("/camera/rgb/image_raw", 100, callback_rgb);
    ros::Subscriber sub2 = nh.subscribe("/camera/depth/image", 100, callback_depth);

    ros::spin();
}

The problem is that the log shows that the timestamp difference gradually increases from 0 to ~0.033 and then it resets to 0. I have checked using rostopic hz that both topics are being published at ~30Hz. I know that the good practice when data fusion is of concern is to use Time Synchronizer. However, shouldn't this approach show if the messages are synchronized? My question is whether this behavior in the timestamps is what actually happens or whether it is misleading.

I am using Ubuntu 18.04, ROS Melodic and the camera drive is the ros_astra_camera. Thank you a lot in advance and let me know if any more information is necessary.

edit retag flag offensive close merge delete

Comments

How do you ensure you are comparing the stamps of the correct pair of messages?

gvdhoorn gravatar image gvdhoorn  ( 2020-10-23 05:06:34 -0500 )edit

Theoretically, I am comparing the stamps of the latest messages from each topic, no?

thanasis_t gravatar image thanasis_t  ( 2020-10-23 05:20:45 -0500 )edit

Theoretically? Maybe. In practice: only one way to know, and that would be to check.

gvdhoorn gravatar image gvdhoorn  ( 2020-10-23 05:36:10 -0500 )edit

The way to check is through the Time Synchronizer? Or is there another way?

thanasis_t gravatar image thanasis_t  ( 2020-10-23 05:52:31 -0500 )edit

UPDATE: I used an ApproximateTimeSynchronizer to ensure that I am comparing the correct messages. The result is still the same.

thanasis_t gravatar image thanasis_t  ( 2020-10-23 06:30:11 -0500 )edit