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

Time Synchronizer (message_filters) with Custom Message type

asked 2014-11-19 17:03:20 -0500

satk gravatar image

updated 2014-11-20 10:17:01 -0500

Hi,

I want to have one callback function for subscription of two topics. I read online here that I can use the message_filters library to time synchronize the topics.

In my ROS node when I use the Image and Camera_info topic as suggested in the example code below, I get no errors.

  message_filters::Subscriber<Image> image_sub(n, "image", 1);
  message_filters::Subscriber<CameraInfo> info_sub(n, "camera_info", 1);
  TimeSynchronizer<Image, CameraInfo> sync(image_sub, info_sub, 10);
  sync.registerCallback(boost::bind(&callback, _1, _2));

But when I replace the Image and CameraInfo message formats with custom messages, as shown below, I get a lot of errors. I am attaching the

  message_filters::Subscriber<coop_est::FeatureBArray> fea_sub(n, "Feature", 1);
  message_filters::Subscriber<nav_msgs::Odometry> odo_sub(n, "odom", 1);
  message_filters::TimeSynchronizer<coop_est::FeatureBArray, nav_msgs::Odometry> sync(fea_sub, odo_sub, 10);
  sync.registerCallback(boost::bind(&FeaturesReceived, _1, _2));

Is message_filters time synchronizer only applicable to certain message formats ?

The error message I get it very long. I am pasting it here:

In file included from /opt/ros/hydro/include/message_filters/time_synchronizer.h:39:0,
                 from /home/quadrotor/catkin_ws/src/coop_est/src/coop_node.cpp:15:
/opt/ros/hydro/include/message_filters/sync_policies/exact_time.h: In member function ‘void message_filters::sync_policies::ExactTime<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 = 0, M0 = coop_est::FeatureBArray_<std::allocator<void> >, M1 = nav_msgs::Odometry_<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 coop_est::FeatureBArray_<std::allocator<void> > >]’:
/opt/ros/hydro/include/message_filters/synchronizer.h:358:5:   instantiated from ‘void message_filters::Synchronizer<Policy>::cb(const typename boost::mpl::at_c<typename Policy::Events, i>::type&) [with int i = 0, Policy = message_filters::sync_policies::ExactTime<coop_est::FeatureBArray_<std::allocator<void> >, nav_msgs::Odometry_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>, typename boost::mpl::at_c<typename Policy::Events, i>::type = ros::MessageEvent<const coop_est::FeatureBArray_<std::allocator<void> > >]’
/opt/ros/hydro/include/message_filters/synchronizer.h:290:5:   instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&, F7&, F8&) [with F0 = message_filters::Subscriber<coop_est::FeatureBArray_<std::allocator<void> > >, F1 = message_filters::Subscriber<nav_msgs::Odometry_<std::allocator<void> > >, F2 = message_filters::NullFilter<message_filters::NullType>, F3 = message_filters::NullFilter<message_filters::NullType>, F4 = message_filters::NullFilter<message_filters::NullType>, F5 = message_filters::NullFilter<message_filters::NullType>, F6 = message_filters::NullFilter<message_filters::NullType>, F7 = message_filters::NullFilter<message_filters::NullType>, F8 = message_filters::NullFilter<message_filters::NullType>, Policy = message_filters::sync_policies::ExactTime<coop_est::FeatureBArray_<std::allocator<void> >, nav_msgs::Odometry_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>]’
/opt/ros/hydro/include/message_filters/synchronizer.h:282:5:   instantiated from ‘void message_filters::Synchronizer<Policy>::connectInput(F0&, F1&, F2&, F3&, F4&, F5&, F6&, F7&) [with F0 ...
(more)
edit retag flag offensive close merge delete

Comments

1

TimeSynchronizer should work with any type that has a standard header. Can you post the error message?

kmhallen gravatar image kmhallen  ( 2014-11-19 19:57:07 -0500 )edit

Thank you for your reply kmhallen. I have edited the original question to include the error message.

satk gravatar image satk  ( 2014-11-20 10:18:06 -0500 )edit

I got the same synchrony problem with my custom message. and My message did has Header. part of error as follow:

/usr/include/boost/bind/bind.hpp:392:35: error: no match for call to ‘(boost::_mfi::mf2<void, subAndPub, const boost::shared_ptr<const sensor_msgs::Image_<std::allocator<void> > >&
pan gravatar image pan  ( 2018-07-12 06:49:42 -0500 )edit

1 Answer

Sort by » oldest newest most voted
2

answered 2014-11-20 11:02:35 -0500

Wolf gravatar image

This error happens if your custom message does not have a header. Add the line:

Header header

at the top of you .msg file.

Note that you have to fill header.stamp with a time stamp for making the time sychronizer work at runtime.

edit flag offensive delete link more

Comments

1

Adding Header header in my .msg file fixed the problem. Thanks! Also I filled the header.stamp by writing this command msg.header.stamp = ros::Time::now(); before publishing to the custom message.

satk gravatar image satk  ( 2014-11-20 15:59:43 -0500 )edit

Plz mark the answer as accepted, if the issue is completely solved....

Wolf gravatar image Wolf  ( 2014-11-21 01:43:18 -0500 )edit

That didn't solve it for me...My custom message has the Header and I still get that leghty error message from the question. I know my custom message works as using a different callback for it gets it working, but I really need it to sinchronize with another message type

JKaiser gravatar image JKaiser  ( 2018-08-09 18:17:30 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2014-11-19 17:03:20 -0500

Seen: 2,702 times

Last updated: Nov 20 '14