Skip to content
Simon Kang edited this page Jun 16, 2021 · 4 revisions

Overview

The ROS2 port of the image_common stack allows users to continue using familiar ROS concepts, such as camera_info_manager and image_transport in the ROS2 ecosystem.

In the image_common repository, the image_transport implements the "raw" transport. For additional transports, use the ros-${DISTRO}-image-transport-plugins package, or install from source via the GitHub repository (ros2 branch)

Migration Status

  • image_transport - Migrated
    • TODO: Implement SubscriberStatusCallback when RMWs support them
    • TODO: Improve publisher/subscriber counts when RMWs support them
  • camera_calibration_parsers - Migrated
  • camera_info_manager - Migrated
  • compressed_image_transport - Migrated
    • TODO: Improve Windows support (cv_bridge currently depends on Boost)
  • compressed_depth_image_transport - Migrated
    • TODO: Improve Windows support (cv_bridge currently depends on Boost)
  • theora_image_transport - Migrated
  • polled_camera - Not Migrated

Migration from ROS to ROS2

Since the concept of ros::NodeHandle does not exist in ROS2, the image_transport::ImageTransport object now operates on a rclcpp::Node*

image_transport

Previously in ROS1, the C++ code to utilize ImageTransport looked like this:

// Use the image_transport classes instead.
#include <ros/ros.h>
#include <image_transport/image_transport.h>

void imageCallback(const sensor_msgs::ImageConstPtr& msg)
{
  // ...
}

ros::NodeHandle nh;
image_transport::ImageTransport it(nh);
image_transport::Subscriber sub = it.subscribe("in_image_base_topic", 1, imageCallback);
image_transport::Publisher pub = it.advertise("out_image_base_topic", 1);

In ROS2, the callback signature must be updated (or typedef'ed), and a pointer to node is used, rather than a NodeHandle.

#include "rclcpp/rclcpp.hpp"
#include "image_transport/image_transport.h"

void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) 
{
  // ...
}

auto node_ = rclcpp::Node::make_shared("test_subscriber");
image_transport::ImageTransport it(node_.get());
auto sub = it.subscribe("in_image_base_topic", 1, imageCallback);
auto pub = it.advertise("out_image_base_topic", 1);

Alternatively, there are free functions that can be used without creating the ImageTransport object. These methods are closer to the way that the rclcpp API works, and also support passing custom QoS settings to the underlying RMW implementation

#include "rclcpp/rclcpp.hpp"
#include "image_transport/image_transport.h"

void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) 
{
  // ...
}

auto node_ = rclcpp::Node::make_shared("test_subscriber");
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;  // Could be any of the profiles or completely custom
auto sub = image_transport::create_subscription(node_.get(), "in_image_base_topic", imageCallback, "raw", custom_qos);
auto pub = image_transport::create_publisher(node_.get(), "out_image_base_topic", custom_qos);

Similar methods are available for CameraPublisher and CameraSubscription

#include "rclcpp/rclcpp.hpp"
#include "image_transport/image_transport.h"

void cameraCallback(
  const sensor_msgs::msg::Image::ConstSharedPtr & msg,
  const sensor_msgs::msg::CameraInfo::ConstSharedPtr & info) 
{
  // ...
}

auto node_ = rclcpp::Node::make_shared("test_subscriber");
rmw_qos_profile_t custom_qos = rmw_qos_profile_default;  // Could be any of the profiles or completely custom
auto sub = image_transport::create_camera_subscription(node_.get(), "camera/image", cameraCallback, "raw", custom_qos);
auto pub = image_transport::create_camera_publisher(node_.get(), "camera/image", custom_qos);

Getting available transports is available via free functions as well:

auto declared = image_transport::getDeclaredTransports();
auto loadable = image_transport::getLoadableTransports();

camera_info_manager

Much like image_transport, rather than using a NodeHandle, use a pointer to rclcpp::Node:

// ROS1
ros::NodeHandle nh;
camera_info::CameraInfoManager cim(nh, "camera");

// ROS2
auto node_ = rclcpp::Node::make_shared("camera_info");
camera_info_manager::CameraInfoManager cim(node_.get());