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

Writing a C++ class with message_filters member

asked 2014-06-04 10:57:43 -0500

schizzz8 gravatar image

updated 2014-06-04 10:58:39 -0500

Hi,

I have the following code:

#include ....

using namespace sensor_msgs;
using namespace message_filters;

std::vector<boost::shared_ptr<capygroovy::Ticks const> > ticks;
ros::Time last = ros::Time::now();

void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3)
{
    ......

    ticks = ticks_cache.getInterval(last,msg3->header.stamp);

    ......
}

int main(int argc, char** argv)
{
    ros::init(argc, argv, "db_creator_node");
    ros::NodeHandle nh;
    message_filters::Subscriber<capygroovy::Ticks> ticks_sub(nh,"/ticks",1);
    message_filters::Cache<capygroovy::Ticks> ticks_cache(ticks_sub,10);

    message_filters::Subscriber<Image> rgb_sub(nh,"/camera/rgb/image_rect",1);
    message_filters::Subscriber<Image> dpt_sub(nh,"/camera/depth/image_rect_raw",1);
    typedef sync_policies::ApproximateTime<Image, Image, capygroovy::Ticks> MySyncPolicy;
    Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), rgb_sub, dpt_sub, ticks_sub);
    sync.registerCallback(boost::bind(&callback, _1, _2, _3));

    ......

    return 0;
}

That, of course, is wrong because I declare ticks_cache in the main and when I call the method getInterval() in the callback I get the error:

/home/dede/catkin_ws/src/db_creator/src/db_creator_node.cpp:24: error: ‘ticks_cache’ was not declared in this scope

I suppose that a nice solution would be to write a class with the message_filters as members but in order to initialize them you need to pass to their constructor the node handle and the topic names. The problem is that I really can't figure out how this could be done, so any help would be appreciated! Thanks!

edit retag flag offensive close merge delete

2 Answers

Sort by » oldest newest most voted
3

answered 2019-11-05 19:28:50 -0500

KenYN gravatar image

updated 2019-11-06 01:39:56 -0500

Without adding a class (which would be best) or globals, you can pass easily an extra parameter to your callback, something like this:

void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
              message_filters::Cache<capygroovy::Ticks> &ticks_cache)
{
    ......

    ticks = ticks_cache.getInterval(last,msg3->header.stamp);

    ......
}

int main(int argc, char** argv)
{
    ......

    sync.registerCallback(boost::bind(&callback, _1, _2, _3, ticks_cache));

    ......

    return 0;
}

It really is as simple as that!


BTW, to make classes easier to create, we use a template like this:

template <typename T>
int NodeMain(int argc, char **argv, std::string const &nodeName)
{
    ros::init(argc, argv, nodeName);
    ros::NodeHandle nh;
    ros::NodeHandle pnh("~");

    T a(nh, pnh);

    ros::spin();
    return EXIT_SUCCESS;
}

Now you just need:

class MyNode
{
private:
    void callback(const ImageConstPtr& msg,const ImageConstPtr& msg2,const capygroovy::TicksConstPtr& msg3,
          message_filters::Cache<capygroovy::Ticks> &ticks_cache)
    { ... }
public:
    MyNode(ros::NodeHandle publicNodeHandle, ros::NodeHandle privateNodeHandle)
    {
        ....
        sync.registerCallback(boost::bind(&callback, this, _1, _2, _3, ticks_cache));
        ....
    }
}

int main(int argc, char **argv)
{
    NodeMain<MyNode>(argc, argv, "MyNode");
}

We also have a slightly more complicated template for a nodelet, and it means we can use class MyNode as either a stand-alone node or a nodelet without any code changes.

edit flag offensive delete link more
5

answered 2019-11-05 05:35:09 -0500

arminkazim gravatar image

updated 2019-11-05 23:51:18 -0500

jayess gravatar image

I use the following code to use message filters inside a class

class SubscribeAndPublish
{

public:

SubscribeAndPublish():sync2(image_sub,image_sub2,500){      

image_sub.subscribe(n, "/camera/color/image_raw", 1);

image_sub2.subscribe(n, "/camera/aligned_depth_to_color/image_raw", 1);

sync2.registerCallback(boost::bind(&SubscribeAndPublish::callback,this, _1, _2));

odom_pub = n.advertise<nav_msgs::Odometry>("RGBDodom", 50);

}

private:
    ros::NodeHandle n;

    ros::Publisher odom_pub;

    message_filters::Subscriber<Image> image_sub;

    message_filters::Subscriber<Image> image_sub2;

    TimeSynchronizer<Image, Image> sync2;
};
edit flag offensive delete link more

Comments

I also had to add Node:: before callback to make it work. Otherwise throws "ISO C++ forbids taking the address of an unqualified or parenthesized non-static member function to form a pointer to member function." error.

            sync.registerCallback(boost::bind(&Node::callback, this, _1, _2));
berk tepebag gravatar image berk tepebag  ( 2020-03-23 05:22:59 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2014-06-04 10:57:43 -0500

Seen: 2,701 times

Last updated: Nov 06 '19