ros-perception / image_common

Common code for working with images in ROS

Home Page:http://www.ros.org/wiki/image_common

Geek Repo:Geek Repo

Github PK Tool:Github PK Tool

Unable to leverage compressed image topics as expected, ROS2 Humble

BradySheehan opened this issue · comments

Compressed image topics do not appear to be working in ROS2 Humble. I have a node panel_detector and a Sterelabs Zed 2i sensor. I am trying to get that node to subscribe to compressed image topics from the Zed 2i.

Setup:
Stereolabs Zed2i Camera
ROS2 Humble
Installed compressed image transport plugin dependencies - https://github.com/ros-perception/image_transport_plugins/blob/rolling/image_transport_plugins/package.xml
Verified that compressed topics are viewable on the system with ros2 topic list.

Steps to Reproduce:

  1. Launch the detector node with _image_transport:=compressed as seen in this document https://github.com/ros-perception/image_transport_tutorials#changing-the-transport-used.
  2. Launch the stereolabs Zed 2i camera

Result:
The node is not subscribing to the compressed topics, e.g.,

$ ros2 node info /panel_detector 
/panel_detector
  Subscribers:
    /parameter_events: rcl_interfaces/msg/ParameterEvent
    /rail_center_zed2i/zed_node/depth/camera_info: sensor_msgs/msg/CameraInfo
    /rail_center_zed2i/zed_node/depth/depth_registered: sensor_msgs/msg/Image
    /rail_center_zed2i/zed_node/left/camera_info: sensor_msgs/msg/CameraInfo
    /rail_center_zed2i/zed_node/left/image_rect_color: sensor_msgs/msg/Image
  Publishers:
    /parameter_events: rcl_interfaces/msg/ParameterEvent
    /rosout: rcl_interfaces/msg/Log
    /tf: tf2_msgs/msg/TFMessage
  Service Servers:
  Service Clients:
  Action Servers:
  Action Clients:

It is only subscribing to the uncompressed topics.

Expected Result:
I expected ros2 node info panel_detector to list that it was subscribed to the compressed image topics.

Debugging
I confirmed that the image_transport/compressed is an available transport.

$ ros2 run image_transport list_transports
Declared transports:
image_transport/compressed
image_transport/compressedDepth
image_transport/raw
image_transport/theoraDetails:
----------
"image_transport/compressed"
- Provided by package: compressed_image_transport
- Publisher:      This plugin publishes a CompressedImage using either JPEG or PNG compression.    
- Subscriber:      This plugin decompresses a CompressedImage topic.    
----------
"image_transport/compressedDepth"
- Provided by package: compressed_depth_image_transport
- Publisher:      This plugin publishes a compressed depth images using PNG compression.    
- Subscriber:      This plugin decodes a compressed depth images.    
----------
"image_transport/raw"
- Provided by package: image_transport
- Publisher:      This is the default publisher. It publishes the Image as-is on the base topic.    
- Subscriber:      This is the default pass-through subscriber for topics of type sensor_msgs/Image.    
----------
"image_transport/theora"
- Provided by package: theora_image_transport
- Publisher:      This plugin publishes a video packet stream encoded using Theora.    
- Subscriber:      This plugin decodes a video packet stream encoded using Theora.

I also tried explicitly changing the topics which were subscribed to be the actual compressed topics, but the camera image callback was never fired.

Hi @BradySheehan , I'm facing the exact same issue with the examples provided by image_transport_tutorials, did you manage to find a solution?

I think I found the issue.
You manually need to define the parameter called image_transport in your node. That's all, after that, starting the node with

--ros-args -p image_transport:=compressed

correctly changed the transport protocol. Note that image_transport and not _image_transport is required.

Before opening a PR to fix this, it this the correct way? Or should the image_transport package responsible to create the parameter?

Hi,

I wrote in the description that I did this but did not see the messages get compressed.

I don't see in the description any mention to manually defining the parameter.

For example, this is the modified and working main of https://github.com/ros-perception/image_transport_tutorials/blob/main/src/my_subscriber.cpp

int main(int argc, char ** argv)
{
  rclcpp::init(argc, argv);
  rclcpp::NodeOptions options;
  rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("image_listener", options);
  node->declare_parameter("image_transport","raw");
  cv::namedWindow("view");
  cv::startWindowThread();
  image_transport::ImageTransport it(node);
  image_transport::Subscriber sub = it.subscribe("camera/image", 1, imageCallback);
  rclcpp::spin(node);
  cv::destroyWindow("view");

  return 0;
}

the diff is

diff --git a/src/my_subscriber.cpp b/src/my_subscriber.cpp
index fc5fccd..c32cbc5 100644
--- a/src/my_subscriber.cpp
+++ b/src/my_subscriber.cpp
@@ -35,6 +35,7 @@ int main(int argc, char ** argv)
   rclcpp::init(argc, argv);
   rclcpp::NodeOptions options;
   rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared("image_listener", options);
+  node->declare_parameter("image_transport","raw");
   cv::namedWindow("view");
   cv::startWindowThread();
   image_transport::ImageTransport it(node);