0. Package Structure
image_subscriber/
├── launch/
│ └── image_subscriber_launch.py
├── config/
│ └── rviz_image_subscriber.rviz
│ └── params.yaml
├── src/
│ └── image_subscriber.cpp
├── CMakeLists.txt
├── package.xml
1. Install dependencies
$ sudo apt update
$ sudo apt install ros-humble-image-transport
2. Create a package
$ cd ~/robot_ws/src
$ ros2 pkg create --build-type ament_cmake image_subscriber --dependencies rclcpp sensor_msgs cv_bridge
3. C++ source code (src/image_subscriber.cpp)
#include <rclcpp/rclcpp.hpp>
#include <cv_bridge/cv_bridge.h>
#include <opencv2/opencv.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <image_transport/image_transport.hpp>
#include <sensor_msgs/msg/image.hpp>
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr pub_img;
double canny_threshold1 = 100.0;
double canny_threshold2 = 200.0;
void image_callback(const sensor_msgs::msg::Image::ConstSharedPtr image)
{
RCLCPP_INFO(
rclcpp::get_logger("image_subscribe_node"),
"Subscribed image! Canny thresholds: threshold1 = %.2f, threshold2 = %.2f",
canny_threshold1, canny_threshold2
);
// ROS → OpenCV
cv::Mat image_opencv = cv_bridge::toCvShare(image, "bgr8")->image;
/* Applying OpenCV algorithm */
cv::Mat image_gray;
cv::cvtColor(image_opencv, image_gray, cv::COLOR_BGR2GRAY);
cv::Mat edges;
cv::Canny(image_gray, edges, canny_threshold1, canny_threshold2);
// OpenCV → ROS
auto image_msg = cv_bridge::CvImage(image->header, "mono8", edges).toImageMsg();
// Publish
pub_img->publish(*image_msg);
}
int main(int argc, char **argv)
{
rclcpp::init(argc, argv);
auto node = rclcpp::Node::make_shared("image_subscribe_node");
// Declare parameters with defaults
node->declare_parameter<double>("canny_threshold1", 100.0);
node->declare_parameter<double>("canny_threshold2", 200.0);
// Get params
node->get_parameter("canny_threshold1", canny_threshold1);
node->get_parameter("canny_threshold2", canny_threshold2);
// Publisher
pub_img = node->create_publisher<sensor_msgs::msg::Image>("/camera_array/left/image_output", 10);
// Subscriber
auto sub_img = node->create_subscription<sensor_msgs::msg::Image>(
"/camera_array/left/image_raw", 10, image_callback);
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
4. CMakeLists.txt
cmake_minimum_required(VERSION 3.8)
project(image_subscriber)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(image_transport REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(OpenCV REQUIRED)
add_executable(image_subscriber_node src/image_subscriber.cpp)
ament_target_dependencies(image_subscriber_node rclcpp sensor_msgs cv_bridge image_transport)
target_include_directories(image_subscriber_node PRIVATE ${OpenCV_INCLUDE_DIRS})
target_link_libraries(image_subscriber_node ${OpenCV_LIBS})
install(TARGETS
image_subscriber_node
DESTINATION lib/${PROJECT_NAME}
)
install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME}/
)
ament_package()
5. rviz configuration
locate ‘rviz_image_subscriber.rviz’ in ‘config’ folder
6. params.yaml file
image_subscriber:
ros__parameters:
canny_threshold1: 50.0
canny_threshold2: 300.0
7. launch file
from launch import LaunchDescription
from launch_ros.actions import Node
import os
def generate_launch_description():
pkg_name = 'image_subscriber'
pkg_dir = os.popen('/bin/bash -c "source /usr/share/colcon_cd/function/colcon_cd.sh && \
colcon_cd %s && pwd"' % pkg_name).read().strip()
return LaunchDescription([
Node(
package='image_subscriber',
executable='image_subscriber_node',
name='image_subscriber',
output='screen',
parameters= [os.path.join(pkg_dir, 'config', 'params.yaml')]
),
Node(
package='rviz2',
namespace='',
executable='rviz2',
name='rviz2',
arguments=['-d', [os.path.join(pkg_dir, 'config', 'rviz_image_subscriber.rviz')]]
)
])
8. Run
$ colcon build --packages-select image_subscriber
$ source install/setup.bash
$ ros2 launch image_subscriber image_subscriber_launch.py
9. Play ROS Bag File
$ ros2 bag play {bagfile}
10. Results

Read canny edge detection parameters from ‘config/params.yaml’ and publish image topic