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

Synchronisation with Subscribers

asked 2016-03-01 04:19:33 -0600

Jägermeister gravatar image

updated 2016-03-01 09:02:38 -0600

I would like to have two subscribers in one file. Two subscribers are supposed to subscribe to two different topics, get their respective data and process them. In order to get this working, I need to solve the synchronization issue. I've already look here but it wasn't very helping, since his way of subscribing is not how I do.

Here is my code:

  ros::init(argc, argv, "radarSubscriber");
  ros::NodeHandle n("~");

  // subscribe to the multibeam
  ros::Subscriber sub = n.subscribe("/multibeam", 500, multibeamCallback);
  // subscribe to image_processor
  ros::Subscriber sub = n.subscribe("/processor", 500, processorCallback);

  // part I took from the link ------------------------------------------------------------------
  typedef sync_policies::ApproximateTime<Image, Image> MySyncPolicy;
  // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image1_sub, image2_sub);
  sync.registerCallback(boost::bind(&callback, _1, _2));
  //  -------------------------------------------------------------------------------------------

What should come there instead of image, image is what I need to know. He was trying to synchronize two cameras, therefore image image works for him. What is it going to be there for me? Should I put the data types of mine (the ones that I subscribe to and get via callback) ?

Thanks in advance.

EDIT:

So after figuring out that the regular subscribers won't work, I used the message filters. However the problem persists. Here is the code that I try to compile:

// subscribe to two topics, one for radar beams, one for frame sectors
  message_filters::Subscriber<sensor_msgs::LaserScan> subMultibeam(n, "multibeam", 1);
  message_filters::Subscriber<std_msgs::Int32MultiArray> subProcessor(n, "imgProcessor", 1);

  // synchronize the callback through approximate time approach
  typedef sync_policies::ApproximateTime<sensor_msgs::LaserScan, std_msgs::Int32MultiArray> MySyncPolicy;
  Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), subMultibeam, subProcessor);
  sync.registerCallback(boost::bind(&callback, _1, _2));

and here is a small piece of the error message that I am getting (the whole message is enormously big and I can't paste it here):

/opt/ros/hydro/include/message_filters/sync_policies/approximate_time.h: In member function ‘void message_filters::sync_policies::ApproximateTime<M0, M1, M2, M3, M4, M5, M6, M7, M8>::checkInterMessageBound() [with int i = 1, M0 = sensor_msgs::LaserScan_<std::allocator<void> >, M1 = std_msgs::Int32MultiArray_<std::allocator<void> >, M2 = message_filters::NullType, M3 = message_filters::NullType, M4 = message_filters::NullType, M5 = message_filters::NullType, M6 = message_filters::NullType, M7 = message_filters::NullType, M8 = message_filters::NullType]’:

/opt/ros/hydro/include/message_filters/sync_policies/approximate_time.h:218:7:   instantiated from ‘void message_filters::sync_policies::ApproximateTime<M0, M1, M2, M3, M4, M5, M6, M7, M8>::add(const typename boost::mpl::at_c<typename message_filters::PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>::Events, i>::type&) [with int i = 1, M0 = sensor_msgs::LaserScan_<std::allocator<void> >, M1 = std_msgs::Int32MultiArray_<std::allocator<void> >, M2 = message_filters::NullType, M3 = message_filters::NullType, M4 = message_filters::NullType, M5 = message_filters::NullType, M6 = message_filters::NullType, M7 = message_filters::NullType, M8 = message_filters::NullType, typename boost::mpl::at_c<typename message_filters::PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8>::Events, i>::type = ros::MessageEvent<const std_msgs::Int32MultiArray_<std::allocator<void> > >]’

/opt/ros/hydro/include/message_filters/synchronizer.h:160:5:   instantiated from ‘message_filters::Synchronizer<Policy>::Synchronizer(const Policy&, F0&, F1&) [with F0 = message_filters::Subscriber ...
(more)
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
1

answered 2016-03-01 04:50:09 -0600

mgruhler gravatar image

updated 2016-03-01 09:12:10 -0600

You need to add the types that you are receiving in your subscribers. Check what you have in your multibeamCallback and processorCallback.

Also, you have two subscribers with the name sub. You need to pass the subscribers to the synchronizer, they should have different names. (As this is actually a redeclaration in your code, I'm guessing the way you have it will not compile anyways...)


Edit

Whoops. This will not work with regular Subscribers. According to the wiki, you need to add respective message_filters::Subscribers, which definitely makes more sense here...

You synchonize, i.e. you only have one callback taking all messages, instead of multiple callbacks. So you need to follow the example you linked...


Edit2

To synchronize, your message need to have a std_msgs/Header. This actually contains the TimeStamp. Without, those obviously cannot be synchronized.

Thus, Int32MultiArray is actually of the wrong message type... (Didn't think of this before...)

edit flag offensive delete link more

Comments

You are right about the variable name sub, thanks, I fixed it.

So, I have const sensor_msgs::LaserScan::ConstPtr& and const std_msgs::Int64MultiArray& in these callbacks, respectively. This means I should feed these two in ApproximateTime, I guess.

Jägermeister gravatar image Jägermeister  ( 2016-03-01 04:52:58 -0600 )edit
1

not the ConstPtrs, but the type, i.e. sensor_msgs::Laserscan and std_msgs::Int64MultiArray, I guess...

mgruhler gravatar image mgruhler  ( 2016-03-01 05:31:55 -0600 )edit

There seems to be an error at

typedef sync_policies::ApproximateTime<sensor_msgs::LaserScan, std_msgs::Int32MultiArray> MySyncPolicy;

Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), subMultibeam, subProcessor);

as it does not compile when I include the second line.

Jägermeister gravatar image Jägermeister  ( 2016-03-01 05:58:17 -0600 )edit

next time please edit your question with the error output... See my edit above...

mgruhler gravatar image mgruhler  ( 2016-03-01 06:34:04 -0600 )edit

@ edit2 In the example given in the website, there was no such a header so I didn't put it either. Also, what do you mean by Int32MultiArray was of "wrong message type"? Is there no way in ROS, of synchronizing such simple, primitive two topics?

Jägermeister gravatar image Jägermeister  ( 2016-03-01 09:21:12 -0600 )edit
1

The messages need to contain a header and with this the timestamp, i.e. they need to be stamped. Otherwise, you'll only know when the message arrives, but not when it was sent. Int32MultiArray does not have a header, so no timestamp. So it is not possible to use this for time synchronization

mgruhler gravatar image mgruhler  ( 2016-03-01 09:34:50 -0600 )edit
1

You need to use stamped message type, (maybe you need to create you own). This is why it is "wrong" here. As you don't have any guarantees in ROS, when a message is delivered, you need to rely on the timestamp in the header for this. For types without headers, this is thus not possible, afaik.

mgruhler gravatar image mgruhler  ( 2016-03-01 09:38:43 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2016-03-01 04:19:33 -0600

Seen: 3,583 times

Last updated: Mar 01 '16