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

message_filters in C++ not subscribing to topics when implemented in a class

asked 2021-02-02 10:13:08 -0500

g.bardaro gravatar image

Hi all, I am having some issues with message filters, but I am not sure if I am doing something wrong or if there is a bug somewhere.

After some difficulties, I decided to implement a couple of minimal examples to describe the problem.

So, the toy example is very simple, I have a publisher node that publishes on two topics (topic1 and topic2) a custom-defined IntStamped message. They have exactly the same timestamp, so there are no issues in the generated messages.

Then, I have implemented two C++ nodes using message_filters, the first one wraps everything in a class, while the second doesn't.

Here are the nodes.

Whit the classes:

#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "boundingbox_msg/msg/int_stamped.hpp"

using namespace  message_filters;

using std::placeholders::_1;
using std::placeholders::_2;

class MinimalSyncClass : public rclcpp::Node {
public:
    MinimalSyncClass() : Node("minimal_sync_class") {
        Subscriber<boundingbox_msg::msg::IntStamped> sub1(this, "topic1");
        Subscriber<boundingbox_msg::msg::IntStamped> sub2(this, "topic2");
        TimeSynchronizer<boundingbox_msg::msg::IntStamped, boundingbox_msg::msg::IntStamped> sync(
                sub1,
                sub2,
                10);
        sync.registerCallback(std::bind(&MinimalSyncClass::callback, this,
                                        std::placeholders::_1,
                                        std::placeholders::_2));
        RCLCPP_INFO_STREAM(this->get_logger(), "Init complete");
    }
private:
    void callback(
            const boundingbox_msg::msg::IntStamped::ConstSharedPtr& msg1,
            const boundingbox_msg::msg::IntStamped::ConstSharedPtr& msg2) const {
        RCLCPP_INFO_STREAM(this->get_logger(), "Result: "<<msg1->value + msg2->value );
    }
};


int main(int argc, char *argv[]) {
    rclcpp::init(argc, argv);
    rclcpp::spin(std::make_shared<MinimalSyncClass>());
    rclcpp::shutdown();
    return 0;
}

And this one without the class:

#include "message_filters/subscriber.h"
#include "message_filters/time_synchronizer.h"
#include "boundingbox_msg/msg/int_stamped.hpp"

using namespace  message_filters;

using std::placeholders::_1;
using std::placeholders::_2;

void callback(
        const boundingbox_msg::msg::IntStamped::ConstSharedPtr& msg1,
        const boundingbox_msg::msg::IntStamped::ConstSharedPtr& msg2) {
    RCLCPP_INFO_STREAM(rclcpp::get_logger("minimal_sync"), "Result: "<<msg1->value + msg2->value );
}

int main(int argc, char** argv)
{
    rclcpp::init(argc, argv);
    auto nh = std::make_shared<rclcpp::Node>("minimal_sync");
    Subscriber<boundingbox_msg::msg::IntStamped> sub1(nh.get(), "topic1");
    Subscriber<boundingbox_msg::msg::IntStamped> sub2(nh.get(), "topic2");
    TimeSynchronizer<
            boundingbox_msg::msg::IntStamped,
            boundingbox_msg::msg::IntStamped> sync(sub1, sub2, 10);
    sync.registerCallback(std::bind(&callback, _1, _2));
    RCLCPP_INFO(rclcpp::get_logger("minimal_sync"), "Init" );
    rclcpp::spin(nh);
    return 0;
}

If I run all the three nodes together, this is the result in rqt_graph:

image description

As you can see, the one without the class is connected to the topics and it is working properly, while the other with the class it's completely disconnected.

I am honestly lost, and can't figure out where the problem is.

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
2

answered 2021-02-02 10:18:02 -0500

gvdhoorn gravatar image

This is a C++ problem, not related to ROS 2 nor the message_filters.

You have this:

Subscriber<boundingbox_msg::msg::IntStamped> sub1(this, "topic1");
Subscriber<boundingbox_msg::msg::IntStamped> sub2(this, "topic2");
TimeSynchronizer<boundingbox_msg::msg::IntStamped, boundingbox_msg::msg::IntStamped> sync(..);

in your constructor.

This makes sub1, sub2 and sync temporary objects which only exist in the scope of the constructor. They are then immediately destructed.

You'll need to make them members of your class.

edit flag offensive delete link more

Comments

1

Of course! Thanks a lot!

g.bardaro gravatar image g.bardaro  ( 2021-02-02 10:52:06 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2021-02-02 10:13:08 -0500

Seen: 657 times

Last updated: Feb 02 '21