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

ROS2 Message filters in a class, initializing message_filters::Subscriber object

asked 2020-08-15 19:17:57 -0500

updated 2020-08-16 11:28:50 -0500

I am trying to sync two message streams of 2 image topics. So I am using message filters. I was using a class to do all this, however, the member initialisation doesn't work for me for message_filters::Subscriber. This is my code-

class MultiSubscriber : public rclcpp::Node
{
  public:

      message_filters::Subscriber<sensor_msgs::msg::Image> image_sub_;
      message_filters::Subscriber<sensor_msgs::msg::Image> disparity_sub_;

    MultiSubscriber(const std::string& name)
    : Node(name), 
      image_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_color_topic")),
      disparity_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_disparity_topic"))
    {

      typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::Image> approximate_policy;
      message_filters::Synchronizer<approximate_policy>syncApproximate(approximate_policy(10), image_sub_, disparity_sub_);

      syncApproximate.registerCallback(&MultSubscriber::disparityCb,this);


    }
    private:
    void disparityCb(const sensor_msgs::msg::Image::SharedPtr disparity_msg, const sensor_msgs::msg::Image::SharedPtr color_msg){
   //dosomething
                }
};

Because of these 2 lines-

  image_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_color_topic")),
  disparity_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "image_disparity_topic"))

I get this error-

/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp: In constructor ‘MultiSenseSubscriber::MultiSenseSubscriber(const string&)’:
/home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:68:120: error: use of deleted function ‘message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >::Subscriber(const message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
     : Node(name), image_sub_(message_filters::Subscriber<sensor_msgs::msg::Image>(this, "/multisense/left/image_color"))
                                                                                                                        ^
In file included from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:0:
/opt/ros/eloquent/include/message_filters/subscriber.h:102:7: note: ‘message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >::Subscriber(const message_filters::Subscriber<sensor_msgs::msg::Image_<std::allocator<void> > >&)’ is implicitly deleted because the default definition would be ill-formed:
 class Subscriber : public SubscriberBase, public SimpleFilter<M>
       ^~~~~~~~~~
/opt/ros/eloquent/include/message_filters/subscriber.h:102:7: error: use of deleted function ‘message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >::SimpleFilter(const message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:41:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: note: ‘message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >::SimpleFilter(const message_filters::SimpleFilter<sensor_msgs::msg::Image_<std::allocator<void> > >&)’ is implicitly deleted because the default definition would be ill-formed:
 class SimpleFilter : public noncopyable
       ^~~~~~~~~~~~
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: error: use of deleted function ‘message_filters::noncopyable::noncopyable(const message_filters::noncopyable&)’
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:40:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/connection.h:51:3: note: declared here
   noncopyable( const noncopyable& ) = delete;
   ^~~~~~~~~~~
In file included from /opt/ros/eloquent/include/message_filters/subscriber.h:41:0,
                 from /home/hsharma/Documents/internship/ws/ros2_ws/src/stereo_ground_surface/obstacle_detection/src/multisense_subscriber.cpp:10:
/opt/ros/eloquent/include/message_filters/simple_filter.h:57:7: error: use of deleted function ‘message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >::Signal1(const message_filters::Signal1<sensor_msgs::msg::Image_<std::allocator<void> > >&)’
 class SimpleFilter : public noncopyable
       ^~~~~~~~~~~~
In file included from /opt/ros/eloquent/include/message_filters/simple_filter.h:43:0,
                 from /opt ...
(more)
edit retag flag offensive close merge delete

Comments

1

Do you need to use the initializer list for construction? Can you try to initialize through the constructor as below?

Note the default Quality of Service profile would be used in the example below.

image_sub_.subscribe(this, "image_color_topic");

disparity_sub_.subscribe(this, "image_disparity_topic");

surfertas gravatar image surfertas  ( 2020-08-16 08:07:25 -0500 )edit

Thanks your method works. Would be good if I can pass qos variable too. Side note, It doesn't work with this too, I get the same error-

 MultiSubscriber(const std::string& name)
    : Node(name), 
    {
     image_sub_=message_filters::Subscriber<sensor_msgs::msg::Image>(this, "/multi/left/image_color",qos);
     disparity_sub_= message_filters::Subscriber<sensor_msgs::msg::Image>(this, "/multi/left/disparity");
      typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::Image> approximate_policy;
      message_filters::Synchronizer<approximate_policy>syncApproximate(approximate_policy(10), image_sub_, disparity_sub_);

      // register the exact time callback
      syncApproximate.registerCallback(&MultiSubscriber::disparityCb,this);

    }

Probably the question could be interpreted as how do I assign the subscription topic and qos to the message_filters::subscriber object ?

Harsh2308 gravatar image Harsh2308  ( 2020-08-16 11:27:27 -0500 )edit

My guess is copying a message_filters::Subscriber is not allowed and what I am doing above is copying a newly created message_filters::Subscriber object's values to another object I previously created.

Harsh2308 gravatar image Harsh2308  ( 2020-08-16 11:30:48 -0500 )edit

1 Answer

Sort by » oldest newest most voted
1

answered 2020-08-16 17:24:59 -0500

Instead of list initialization for construction, initialize through the constructor by calling subscribe().

image_sub_.subscribe(this, "image_color_topic");

disparity_sub_.subscribe(this, "image_disparity_topic");

edit flag offensive delete link more

Comments

I tried your code but callback is not executed somehow. https://answers.ros.org/question/3792...

dinesh gravatar image dinesh  ( 2021-05-31 00:20:17 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-08-15 19:17:57 -0500

Seen: 3,749 times

Last updated: Aug 16 '20