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

Not receiving any callback for synchronized PointCloud2 and Robot EndpointState

asked 2018-02-14 23:41:39 -0500

ravijoshi gravatar image

I am trying to receive data from two different publishers as listed below-

  1. Message Type: baxter_core_msgs::EndpointState. Topic Name: /robot/limb/right/endpoint_state
  2. Message Type: sensor_msgs::PointCloud2. Topic Name: /kinect2/sd/points

Please see the code snippet below-

void DataCollector::callback(const baxter_core_msgs::EndpointStateConstPtr& ee_msg, const sensor_msgs::PointCloud2ConstPtr& pc_msg)
{
    std::cout << "Solve all of perception here" << std::endl;
}

DataCollector::DataCollector()
{
    ros::NodeHandle nh;
    message_filters::Subscriber<baxter_core_msgs::EndpointState> baxter_arm_sub(nh, "/robot/limb/right/endpoint_state", 1);
    message_filters::Subscriber<sensor_msgs::PointCloud2> point_cloud_sub(nh, "/kinect2/sd/points", 1);
    TimeSynchronizer<baxter_core_msgs::EndpointState, sensor_msgs::PointCloud2> sync(baxter_arm_sub, point_cloud_sub, 100);
    sync.registerCallback(boost::bind(&DataCollector::callback, this, _1, _2));
    ros::spin();
}

Unfortunately, there is no callback received. I dig into the problem and noticed that baxter_core_msgs::EndpointState message is being received in high frequency compared to sensor_msgs::PointCloud2.

Plese see below the screenshot of the output of rostopic echo /robot/limb/right/endpoint_state|grep secs and rostopic echo /kinect2/sd/points|grep secs in respective terminals taken at the same time-

image description

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2018-02-15 01:53:39 -0500

gvdhoorn gravatar image

updated 2018-02-15 01:55:59 -0500

See #q60903 and #q172676 for almost duplicates.

Summarising: TimeSynchronizer needs timestamps to match exactly. If you don't have that happening in your message stream, but still want callbacks for messages that are "close enough", then you should use the ApproximateTimePolicy.

edit flag offensive delete link more

Comments

Note also that if your Kinect2 is not connected to the Baxter PC, you might want to look into synchronising the clocks between all hosts in your ROS node graph. This will still not make TimeSynchronizer call your callbacks, but it will avoid problems later on (with TF fi).

gvdhoorn gravatar image gvdhoorn  ( 2018-02-15 01:56:53 -0500 )edit

Got it. Thank you very much.

ravijoshi gravatar image ravijoshi  ( 2018-02-15 02:48:21 -0500 )edit
1

If I may suggest: try to search for these kind of problems. It's not that we don't want to help, but getting answers on this forum takes time, so if you find it yourself, you save time.

Use Google (not the integrated search). I always do something like:

$search_term site:answers.ros.org
gvdhoorn gravatar image gvdhoorn  ( 2018-02-15 02:50:07 -0500 )edit

Thanks for telling the trick.I got it.

ravijoshi gravatar image ravijoshi  ( 2018-02-17 03:18:50 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-02-14 23:41:39 -0500

Seen: 172 times

Last updated: Feb 15 '18