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]
You need to use
TimeSynchronizer
or others withmessage_filters
. For more info, please check the official documentation at http://wiki.ros.org/message_filters@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: 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.