ros-perception / image_pipeline

An image processing pipeline for ROS.
Other
762 stars 715 forks source link

Topics do not appear to be synchronized #977

Open Rudresh172 opened 2 months ago

Rudresh172 commented 2 months ago

We are trying to use a stereo camera setup to generate pointcloud. This is our desired flow - Screenshot from 2024-05-02 00-33-12

We are using the image_proc node for rectification of images. We have created a custom publisher which subscribes to the /camera_info topic and publishes out the /camera_info_rect at the same publish rate (60) -

public:
    CameraInfoPublisher() : Node("camera_info_publisher")
    {
        camera_ = this->declare_parameter("camera", "camera0");

        image_sub_ = this->create_subscription<sensor_msgs::msg::CameraInfo>("/olive/camera/olv_cam01/camera_info", 60,
              std::bind(&CameraInfoPublisher::image_callback_01, this, _1));

        image_sub2_ = this->create_subscription<sensor_msgs::msg::CameraInfo>("/olive/camera/olv_cam02/camera_info", 60,
              std::bind(&CameraInfoPublisher::image_callback_02, this, _1));

        publisher_ = this->create_publisher<sensor_msgs::msg::CameraInfo>("/olive/camera/olv_cam01/camera_info_rect", 60);
        publisher2_ = this->create_publisher<sensor_msgs::msg::CameraInfo>("/olive/camera/olv_cam02/camera_info_rect", 60); ///olive/camera/olv_cam02/camera_info_rect
    }

But it gives out this warning message in the terminal -

[image_proc-7] [WARN] [1714602948.619293932] [rect_left]: [image_transport] Topics '/olive/camera/olv_cam01/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[image_proc-7]  Image messages received:      0
[image_proc-7]  CameraInfo messages received: 36
[image_proc-7]  Synchronized pairs:           0
[image_proc-6] [WARN] [1714602948.713715736] [rect_right]: [image_transport] Topics '/olive/camera/olv_cam02/image_raw' and '/camera_info' do not appear to be synchronized. In the last 10s:
[image_proc-6]  Image messages received:      0
[image_proc-6]  CameraInfo messages received: 38
[image_proc-6]  Synchronized pairs:           0

Eventually, the pointcloud stops publishing (after around 2-3 minutes of use) We want to know If this is happening because of the above warning? Note that I am using a 40GB RAM i9 along with a RTX 3060, so we don't think compute is a problem here.

Our launch file is -

camera_info_rect = Node(
        package='camera_intrinsics',
        executable='camera_info_publisher',      
    )

    rect_right = Node(
        package='image_proc',
        executable='image_proc',
        name='rect_right',
        arguments=['image:=/olive/camera/olv_cam02/image_raw', 'image_rect:=/olive/camera/olv_cam02/image_rect', 'camera_info:=/olive/camera/olv_cam02/camera_info_rect'],
        output='screen'
    )

    rect_left = Node(
        package='image_proc',
        executable='image_proc',
        name='rect_left',
        arguments=['image:=/olive/camera/olv_cam01/image_raw', 'image_rect:=/olive/camera/olv_cam01/image_rect', 'camera_info:=/olive/camera/olv_cam01/camera_info_rect'],
        output='screen'
    )

    disparity_node = Node(
            package='stereo_image_proc',
            executable='disparity_node',
            parameters=[{
                'approximate_sync': True,
                'use_system_default_qos': False,
                'stereo_algorithm': 0,
                'prefilter_size': 9,
                'prefilter_cap': 31,
                'correlation_window_size': 15,
                'min_disparity': -70,
                'disparity_range': 64,
                'texture_threshold': 10,
                'speckle_size': 100,
                'speckle_range': 4,
                'disp12_max_diff': 0,
                'uniqueness_ratio': 15.0,
                'P1': 200.0,
                'P2':400.0,
                'full_dp': False
            }],
            remappings=[
                ('left/image_rect', '/olive/camera/olv_cam01/image_rect'), 
                ('left/camera_info', '/olive/camera/olv_cam01/camera_info_rect'),   
                ('right/image_rect', '/olive/camera/olv_cam02/image_rect'), 
                ('right/camera_info','/olive/camera/olv_cam02/camera_info_rect')
            ]
        )

    pointcloud_node = Node(
            package='stereo_image_proc',
            executable= 'point_cloud_node',
            parameters=[{
                'approximate_sync': True,
                'avoid_point_cloud_padding': False,
                'use_color': True,
                'use_system_default_qos': False,
            }],
            remappings=[
                ('left/camera_info', '/olive/camera/olv_cam01/camera_info_rect'), 
                ('right/camera_info', '/olive/camera/olv_cam02/camera_info_rect'), 
                (
                    'left/image_rect_color', '/olive/camera/olv_cam01/image_rect'
                ),
            ]
        )

    pointcloud_to_laserscan = Node(
            package='pointcloud_to_laserscan', executable='pointcloud_to_laserscan_node',
            remappings=[('cloud_in',  '/points2'),
                        ('scan', '/scan')],
            parameters=[{
                'target_frame': 'base_link',
                'transform_tolerance': 0.01,
                'min_height': 0.0,
                'max_height': 1.0,
                'angle_min': -1.5708,  # -M_PI/2
                'angle_max': 1.5708,  # M_PI/2
                'angle_increment': 0.00174, #0.1 DEG  #0.0087,  # M_PI/360.0
                'scan_time': 0.3333,
                'range_min': 0.0,
                'range_max': 20.0,
                'use_inf': True,
                'inf_epsilon': 0.01 # 1.0
            }],
            name='pointcloud_to_laserscan'
        )

Thanks!

JWhitleyWork commented 2 months ago

By default, nodes use a SingleThreadedExecutor which executes callbacks sequentially rather than in parallel. However, even a MultiThreadedExecutor would not really solve this issue. The solution is to use a message_filters::Synchronizer to time-synchronize the subscriptions. A basic example can be found here: https://answers.ros.org/question/366440/ros-2-message_filters-timesynchronizer-minimal-example-does-not-reach-callback-function/

Rudresh172 commented 2 months ago

Hello @JWhitleyWork,

Thanks a lot for your quick response. Do we need Time synchronizer since the ros2 camera plugin is publishing /image_raw and /camera_info msgs which are already synchronized? We are subscribing to camera01/camera_info and publishing camera01/camera_info_rect and similarly for camera02. This is our callback -

private:
    void image_callback_01(sensor_msgs::msg::Image::SharedPtr img_msg)
    {
      // start with a blank message
      sensor_msgs::msg::CameraInfo info;

      path file_path = ament_index_cpp::get_package_share_directory("camera_intrinsics");
      //file_path /= path("config") / path(camera_ + "_cal") / path("ost.yaml");
      file_path /= path("config") / path("left_40.yaml");

      std::string saved_name; // camera name in file - to be loaded

      // parse the calibration into a CameraInfo message
      if (!camera_calibration_parsers::readCalibration(file_path, saved_name, info))
      {
        RCLCPP_INFO(this->get_logger(), "Error parsing calibration");
        return;
      }

      // need to fill in timestamp and frame info
      info.header = img_msg->header;

      //RCLCPP_INFO(this->get_logger(), "Publishing camera info");

      publisher_->publish(info);
    }

    void image_callback_02(sensor_msgs::msg::Image::SharedPtr img_msg)
    {
      // start with a blank message
      sensor_msgs::msg::CameraInfo info;

      path file_path = ament_index_cpp::get_package_share_directory("camera_intrinsics");
      file_path /= path("config") / path("right_40.yaml");

      std::string saved_name; // camera name in file - to be loaded

      // parse the calibration into a CameraInfo message
      if (!camera_calibration_parsers::readCalibration(file_path, saved_name, info))
      {
        RCLCPP_INFO(this->get_logger(), "Error parsing calibration");
        return;
      }

      // need to fill in timestamp and frame info
      info.header = img_msg->header;

      //RCLCPP_INFO(this->get_logger(), "Publishing camera info");

      publisher2_->publish(info);
    }

    rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub_;
    rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr image_sub2_;
    rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr publisher_;
    rclcpp::Publisher<sensor_msgs::msg::CameraInfo>::SharedPtr publisher2_;
    std::string camera_;

};

We also tried subscribing to /image_raw instead of /camera_info since we are using the header directly from subscription, but it gives the same issue. When we use the "stereo_image_proc.launch.py" and remap the topics, it works without issues. Is it because of the use of composable node and GroupAction?

mikeferguson commented 1 month ago

So I just scanned this issue - not digging super deep - but I'm going to to note it looks like you are using the "image_proc" node in ROS2 - which, basically has been horribly broken for a long time (I'm not sure it ever worked - it creates two instances of RectifyNode internally but doesn't set any names for them, so they have the same parameters). That node was actually removed in https://github.com/ros-perception/image_pipeline/pull/925 - and that PR also makes the image_proc.launch.py actually work (in porting the documentation, I tested all of these things).

Docs are now building here: https://docs.ros.org/en/rolling/p/image_proc/ - and there is a tutorial on using the launch file. I'm not sure which ROS2 distro you are using, some of the fixes haven't been ported all the way back