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

Two Topics with Same Callback

asked 2017-01-14 15:23:24 -0500

updated 2017-01-14 15:28:42 -0500

Hi everyone,

I am subscribing to two different topics (each with different md5sums) using a single callback. I am using the message_filters class to achieve this. In my broadcaster, I am publishing a point cloud and an opencv image. I want to subscribe in a separate code. My callback signature looks like so:

 void callback(const sensor_msgs::ImageConstPtr& ensensoImage, const sensor_msgs::PointCloud2ConstPtr& ensensoCloud)
{
   cv::Mat ir; 
   PointCloudT cloud;
   getImage(ensensoImage, ir);
   getCloud(ensensoCloud, cloud);
   ROS_INFO_STREAM("cloud: " << cloud);

   std::lock_guard<std::mutex> lock(mutex);
   this->ir = ir;
   this->cloud = cloud;
   updateImage = true;
   updateCloud = true;

}

When I run my code, however, I get an std::terminate as follows:

user@user:~/catkin_ws$ rosrun ensenso ensenso_viewer terminate called after throwing an instance of 'ros::ConflictingSubscriptionException' what(): Tried to subscribe to a topic with the same name but different md5sum as a topic that was already subscribed [sensor_msgs/PointCloud2/1158d486dd51d683ce2f1be655c3c181 vs. sensor_msgs/Image/060021388200f6f0f447d0fcd9c64743] Aborted (core dumped)

Is it not possible to have a callback with different classes of a namespace or am I missing something?

For reference, the whole code is here.

I would appreciate any help. Thanks!

edit retag flag offensive close merge delete

Comments

Why do you even need to do this in 1 callback function? Why don't just use 2 callback functions, store the data and create another function using the data? I've never encountered this approach and according to the error you've got it's not maybe even supported.

l4ncelot gravatar image l4ncelot  ( 2017-01-14 17:15:00 -0500 )edit
1

Did you read that I was using message_filters? The parameters are templated and the user should be free to put their classes within the policies as they might deem fit. I want to receive two different topics in a particular time. An ordinary callback would not fit my purpose.

lakehanne gravatar image lakehanne  ( 2017-01-14 19:40:21 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2017-01-14 21:57:31 -0500

ahendrix gravatar image

What you're trying to do seems reasonable.

The error you have happens when you create two subscribers on the same topic name, with different message types and checksums.

From you description, it sounds like your data is on two separate topics, so I suspect there's a typo or mis-configuration in your code somewhere.

And indeed, here is looks like you create two topic names, but then use the same topic name when subscribing to both topics:

spinner(4), subNameCloud(basetopic + "/cloud"), subNameIr(basetopic + "/ir_image"), 
subImageIr(nh, subNameIr, 1), subCloud(nh, subNameIr, 1),

(note using subNameIr when creating both the Image and Cloud subscribers).

It looks like this should be:

spinner(4), subNameCloud(basetopic + "/cloud"), subNameIr(basetopic + "/ir_image"), 
subImageIr(nh, subNameIr, 1), subCloud(nh, subNameCloud, 1),
edit flag offensive delete link more

Comments

Touche! Awesome. Thank you! I spent almost 9 hours trying to figure out where the error laid in the code. After getting repeatedly frustrated, I decided to post a question on this site. Now thanks to your careful eye, I can go to bed happy. Thanks again!

lakehanne gravatar image lakehanne  ( 2017-01-14 22:25:45 -0500 )edit

If you feel @ahendrix has answered your question, could you please mark it as answered by ticking the checkmark to the left of it?

Thanks.

gvdhoorn gravatar image gvdhoorn  ( 2017-01-15 04:57:35 -0500 )edit

Done. Thanks!

lakehanne gravatar image lakehanne  ( 2017-01-15 09:12:17 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2017-01-14 15:23:24 -0500

Seen: 1,974 times

Last updated: Jan 14 '17