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

nh.subscribe works but message_filters::Subscriber not

asked 2022-09-24 03:31:22 -0600

Janebek gravatar image

updated 2022-09-26 06:52:32 -0600

ravijoshi gravatar image

I'm trying to learn the ROS topic, but I met a problem that really confused me.

Here is the origin code. It works well, I can receive the image and pass it to CamImgCb.

mSubCam = mNh.subscribe<sensor_msgs::Image>(TopicNameCamSub,10,boost::bind(&ClientHandler::CamImgCb,this,_1));

But when I change it to this code below, CamImgCb can not receive anything. The whole program is stuck to wait for the image to come.

message_filters::Subscriber<sensor_msgs::Image> rgb_sub(mNh, TopicNameCamSub, 10);
rgb_sub.registerCallback(boost::bind(&ClientHandler::CamImgCb,this,_1));

My question is, aren't those two codes the same thing? Why is there a difference between them? I just can't figure it out.

Does anyone know what the problem is? Please help me, and thank you so much!

edit retag flag offensive close merge delete

Comments

You need to use TimeSynchronizer or others with message_filters. For more info, please check the official documentation at http://wiki.ros.org/message_filters

ravijoshi gravatar image ravijoshi  ( 2022-09-26 04:58:52 -0600 )edit

@ravijoshi: +100 for spending the time to post something, but please try to avoid link-only answers/comments.

If you believe the documentation directly answers @Janebek's question, please quote the relevant parts of the page(s) you link to, or explain it in your own words, backed up by quotes from that documentation.

I'm familiar with the message_filters documentation, but I would not be able to answer @Janebek's question directly from it.

If you can, please do, as it would help all of us avoid having to ask the same question again in the future.

gvdhoorn gravatar image gvdhoorn  ( 2022-09-26 05:01:05 -0600 )edit

@gvdhoorn: Thanks to your observation, I was able to find the actual culprit. I am sorry, but my first comment about TimeSynchronizer is invalid. Unfortunately, I can not edit/delete it. Nevertheless, I am posting the answer below.

ravijoshi gravatar image ravijoshi  ( 2022-09-26 06:48:12 -0600 )edit

1 Answer

Sort by » oldest newest most voted
4

answered 2022-09-26 06:45:30 -0600

ravijoshi gravatar image

Thanks to the sharp observation of @gvdhoorn, I had to look it back to create a minimal reproducible example.

It is an interesting problem. In summary, in the second case, the subscriber, i.e., rgb_sub, is in local scope. Therefore after the construction call, it does not exist. So we must make it a class member to make it work.

Please see a minimal reproducible example below:

#include <ros/ros.h>
#include <message_filters/subscriber.h>
#include <sensor_msgs/Image.h>

using namespace sensor_msgs;
using namespace message_filters;

class ClientHandler
{
public:
  ClientHandler(ros::NodeHandle& nh, std::string& topic_name);
  void CamImgCb(const ImageConstPtr& image);

private:
  ros::NodeHandle n;
  std::string topic;
  message_filters::Subscriber<Image> rgb_sub;
};

ClientHandler::ClientHandler(ros::NodeHandle& nh, std::string& topic_name) : n(nh), topic(topic_name)
{
  // the following declaration does not work. hence it is commented.
  // the subscriber is in a local scope
  // message_filters::Subscriber<Image> rgb_sub(n, topic, 1);

  // let's make it a class member and then call subscribe as shown below
  rgb_sub.subscribe(n, topic, 1);

  // now bind a callback
  rgb_sub.registerCallback(boost::bind(&ClientHandler::CamImgCb, this, _1));
}

void ClientHandler::CamImgCb(const ImageConstPtr& image)
{
  ROS_INFO("Sequence: [%d]", image->header.seq);
}

int main(int argc, char** argv)
{
  ros::init(argc, argv, "image_listener");
  ros::NodeHandle n;

  std::string topic = "/usb_cam/image_raw";
  ClientHandler ClientHandler(n, topic);

  ros::spin();
  return 0;
}

I used the usb_cam package to publish my webcam and used the above node to subscribe, as shown below:

$ rosrun usb_cam usb_cam_node 
$ rosrun beginner_tutorials listener_class_filter 
[ INFO] [1664192571.776300573]: Sequence: [0]
[ INFO] [1664192571.808083556]: Sequence: [1]
[ INFO] [1664192571.839569528]: Sequence: [2]
[ INFO] [1664192571.875559602]: Sequence: [3]
[ INFO] [1664192571.907563678]: Sequence: [4]
[ INFO] [1664192571.943604144]: Sequence: [5]
[ INFO] [1664192571.975550851]: Sequence: [6]
[ INFO] [1664192572.007569647]: Sequence: [7]
[ INFO] [1664192572.043564526]: Sequence: [8]
[ INFO] [1664192572.075685918]: Sequence: [9]
[ INFO] [1664192572.107556296]: Sequence: [10]
edit flag offensive delete link more

Comments

Thanks for posting this @ravijoshi.

Minor comment: should topic be topic_name in:

rgb_sub.subscribe(n, topic, 1);

?

gvdhoorn gravatar image gvdhoorn  ( 2022-09-26 06:55:03 -0600 )edit

Both should be fine. I made topic as a class member, which is not required for this example though.

ravijoshi gravatar image ravijoshi  ( 2022-09-26 07:04:52 -0600 )edit

Ah, right. I assumed class members would be suffixed by _ (as I'm used to / many code styles do), which would make topic an argument to the ctor. Hence my confusion.

gvdhoorn gravatar image gvdhoorn  ( 2022-09-26 07:08:06 -0600 )edit

Thank you so much for answering this! This solved my problem!

Janebek gravatar image Janebek  ( 2022-09-26 08:23:00 -0600 )edit

But I still have a small problem, when there are two topics, I need to use sychronizer to make it work, but how do I put the function message_filters::Synchronizer in the Class member? The code is shown below

message_filters::Subscriber<sensor_msgs::Image> rgb_sub(nh, "/camera/rgb/image_raw", 1); message_filters::Subscriber<sensor_msgs::Image> depth_sub(nh, "/camera/depth_registered/image_raw", 1); 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); sync.registerCallback(boost::bind(&ImageGrabber::GrabRGBD,&igb,_1,_2));

Please help me @ravijoshi , thank you so much!

Janebek gravatar image Janebek  ( 2022-09-26 08:26:00 -0600 )edit

@Janebek : Glad it worked. Please upvote and mark this answer as accepted. Next, for the new problem, please create a new question. Let's keep one question in one page!

ravijoshi gravatar image ravijoshi  ( 2022-09-26 08:31:47 -0600 )edit

Thank you!I clicked the green "right" icon , is that the accept button? I'm new to this.

Janebek gravatar image Janebek  ( 2022-09-26 08:33:23 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2022-09-24 03:25:30 -0600

Seen: 328 times

Last updated: Sep 26 '22