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

message_filters doesn't call the callback function

asked 2020-12-09 03:12:52 -0500

hosh gravatar image

updated 2020-12-09 03:28:05 -0500

I gonna synchronize an image by its camera_info. The code is attached, after finishing constructor, it just stays without going to the callback function. I have tried different QoS, made sure topics are published, ...

  OverheadCamNode::OverheadCamNode(rclcpp::NodeOptions options): Node("overhead_camera_node", options){


       message_filters::Subscriber<sensor_msgs::msg::Image> overhead_cam1_sub_(this, "/image", 
       rmw_qos_profile_sensor_data);
      message_filters::Subscriber<sensor_msgs::msg::CameraInfo> camera_info_sub_(this, "/camera_info", 
      rmw_qos_profile_sensor_data);

      typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image , 
      sensor_msgs::msg::CameraInfo> approximate_policy;
      message_filters::Synchronizer<approximate_policy> syncApproximate(approximate_policy(10), 
      overhead_cam1_sub_, camera_info_sub_);

      syncApproximate.registerCallback(std::bind(&OverheadCamNode::synchronized_images_callback, 
      this,std::placeholders::_1, std::placeholders::_2));
      RCLCPP_INFO(this->get_logger(), "Constructor");
            }

void OverheadCamNode::synchronized_images_callback(
                                const sensor_msgs::msg::Image::ConstSharedPtr image_1,
                                const sensor_msgs::msg::CameraInfo::ConstSharedPtr cam_info) {

              RCLCPP_INFO(this->get_logger(), "in CB");
}
edit retag flag offensive close merge delete

Comments

Unfortunately, I don't think there is enough information to answer here. A few questions:

  1. What version of ROS 2 are you using?
  2. What does your main function look like? Are you properly spinning the node?
  3. What are the QoS settings of the topics you are subscribing to? If you are on Foxy or later, you can run your system and then run ros2 topic info -v /image and ros2 topic info -v /camera_info to get that information.
clalancette gravatar image clalancette  ( 2020-12-11 15:30:01 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2021-07-27 01:09:02 -0500

__spam__ gravatar image

Haven't compiled it yet, but something like this works for me:

#include <sensor_msgs/msg/image.hpp>
#include <sensor_msgs/msg/camera_info.hpp>
#include <rclcpp/rclcpp.hpp>
#include <message_filters/subscriber.h>
#include <message_filters/time_synchronizer.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>

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

class OverheadCamNode : public rclcpp::Node{

    public:
        OverheadCamNode() : Node("overhead_camera_node)
        {

            rclcpp::QoS qos(10);
            auto rmw_qos_profile = qos.get_rmw_qos_profile();

            overhead_cam1_sub_.subscribe(this, "/image", rmw_qos_profile );
            camera_info_sub_.subscribe(this, "/camera_info",rmw_qos_profile);

            sync.reset(new Sync(new Sync(MySyncPolicy(10),overhead_cam1_sub_,camera_info_sub_));
            sync->registerCallback(std::bind(&OverheadCamNode::synchronized_images_callback, 
                      this, _1, _2));

        }

    private:
        void synchronized_images_callback(
            const sensor_msgs::msg::Image::ConstSharedPtr& image_1,
            const sensor_msgs::msg::CameraInfo::ConstSharedPtr& cam_info)

        {
            RCLCPP_INFO(this->get_logger(), "in CB");
        }



    message_filters::Subscriber<sensor_msgs::msg::Image> overhead_cam1_sub_;
    message_filters::Subscriber<sensor_msgs::msg::CameraInfo> camera_info_sub_;


    typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image , 
    sensor_msgs::msg::CameraInfo> MySyncPolicy;
    typedef message_filters::Synchronizer<MySyncPolicy> Sync;
    std::shared_ptr<Sync> sync;

};

int main(int argc, char **argv)
{
    rclcpp::init(argc, argv);
    auto node = std::make_shared<OverheadCamNode>();
    rclcpp::spin(node);
    rclcpp::shutdown();
    return 0;
}
edit flag offensive delete link more

Question Tools

3 followers

Stats

Asked: 2020-12-09 03:12:52 -0500

Seen: 510 times

Last updated: Jul 27 '21