ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

how to synchronize two topics publishing PointCloud2 data

asked 2018-10-02 15:21:37 -0500

roskinetic gravatar image

updated 2018-10-02 21:53:48 -0500

Thomas D gravatar image

Hi, I am new to ROS and I am trying to do a simple example of Approximate Time Synchronization. I have following two nodes and each publishes a simple single PointCloud2 data (I am using the PointCloud2 data type because it has header of time stamp), and I have a node for time synchronization. I am following the ROS Tutorial for Approximate Time Policy. All nodes are compiled without any error but it seems that the callback function never get called. Please advise.

Thank you!

First node

int main (int argc, char **argv){

    ros::init(argc, argv, "talker");

    ros::NodeHandle n;

    ros::Publisher chatter_pub = n.advertise<sensor_msgs::PointCloud2>("chatter", 1000);

        ros::Rate loop_rate(10);

    int speed = 100;

        while (ros::ok()){

                sensor_msgs::PointCloud2 msg;

                msg.height = speed;

                chatter_pub.publish(msg);

                loop_rate.sleep();

        }

    return 0;

}

Second node is:

int main (int argc, char **argv){

    ros::init(argc, argv, "friend");

    ros::NodeHandle n;

    ros::Publisher chatterfriend_pub = n.advertise<sensor_msgs::PointCloud2>("chatter_friend", 1000);

        ros::Rate loop_rate(20);

    int speed = 500;

        while (ros::ok()){

                sensor_msgs::PointCloud2 msg;

                msg.height = speed;

                chatterfriend_pub.publish(msg);

                loop_rate.sleep();

        }

    return 0;

}

And my node for Time Synchronizer is

using namespace sensor_msgs;

using namespace message_filters;

ros::Publisher data1_pub;

ros::Publisher data2_pub;


void callback(const sensor_msgs::PointCloud2::ConstPtr& data1, const sensor_msgs::PointCloud2::ConstPtr& data2)
{

  ROS_INFO("Sync_Callback");

  data1_pub.publish(data1);

  data2_pub.publish(data2);

}

int main(int argc, char** argv)

{
  ros::init(argc, argv, "TimeSynchronizer");

  std::string data1_topic = "/chatter";

  std::string data2_topic = "/chatter_friend";


  ros::NodeHandle nh;

  message_filters::Subscriber<sensor_msgs::PointCloud2> data1_sub(nh, data1_topic, 100);

  message_filters::Subscriber<sensor_msgs::PointCloud2> data2_sub(nh, data2_topic, 100);

  data1_pub = nh.advertise<sensor_msgs::PointCloud2>("/synchronized" + data1_topic, 1000);

  data2_pub = nh.advertise<sensor_msgs::PointCloud2>("/synchronized" + data2_topic, 1000);

  typedef sync_policies::ApproximateTime<PointCloud2, PointCloud2> MySyncPolicy;

  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), data1_sub, data2_sub);

  sync.registerCallback(boost::bind(&callback, _1, _2));

  ros::spin();

  return 0;
}
edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-10-02 21:57:08 -0500

Thomas D gravatar image

I think the two nodes that publish are missing a ros::spinOnce() call in the main while loops. Therefore, the publishers never actually publish messages. You could check this by running rostopic hz chatter and rostopic hz chatter_friend to see what rate the messages are being published at.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-10-02 15:21:37 -0500

Seen: 782 times

Last updated: Oct 02 '18