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

How to pass publisher to callback

asked 2017-10-20 17:27:03 -0500

rnunziata gravatar image

How to pass publisher to callback, as far as I can see this should work but keep getting errors: The two param case works without the publisher being passed.

 ImageGrabber igb(&SLAM);
ros::NodeHandle nh; 
ros::Publisher pub = nh.advertise<sensor_msgs::Image>("/camera/depth-converted/image_raw", 1);

message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/camera/rgb/image_raw", 100);
message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "camera/depth_registered/image_raw", 100);
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> sync_pol;
message_filters::Synchronizer<sync_pol> sync(sync_pol(10), rgb_sub, depth_sub, &pub);
sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD, &igb, _1, _3));

call back def:

void ImageGrabber::GrabRGBD(const sensor_msgs::ImageConstPtr& msgRGB,const sensor_msgs::ImageConstPtr& msgD, const ros::Publisher *pub)

error:

error: no matching function for call to ‘message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::Image_<std::allocator<void> >, sensor_msgs::Image_<std::allocator<void> > > >::Synchronizer(sync_pol, message_filters::Subscriber<sensor_msgs::Image_<std::allocator<void> > >&, message_filters::Subscriber<sensor_msgs::Image_<std::allocator<void> > >&, const ros::Publisher*)’
     message_filters::Synchronizer<sync_pol> sync(sync_pol(10), rgb_sub, depth_sub, &pub);
edit retag flag offensive close merge delete

1 Answer

Sort by » oldest newest most voted
0

answered 2017-10-21 02:08:51 -0500

ahendrix gravatar image

updated 2017-10-21 02:10:32 -0500

You're trying to create a topic synchronizer with a publisher as an input, and the compiler is telling you that isn't allowed. You're only allowed to pass a policy and some number of subscribers to the sync() method.

Instead, you can either make your publisher a global variable, a class variable if your callback is a member of a class, or pass the publisher to the callback as one of the arguments when you use boost::bind.

Try:

sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD, &igb, _1, _2, &pub));
edit flag offensive delete link more

Comments

did not work....but I did go ahead and make it a class var. Should I close this? It seem that it is just not permitted.

rnunziata gravatar image rnunziata  ( 2017-10-21 14:20:47 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2017-10-20 17:27:03 -0500

Seen: 1,097 times

Last updated: Oct 21 '17