diff --git a/image_transport/include/image_transport/image_transport.hpp b/image_transport/include/image_transport/image_transport.hpp index e430cd92..5821e1db 100644 --- a/image_transport/include/image_transport/image_transport.hpp +++ b/image_transport/include/image_transport/image_transport.hpp @@ -112,6 +112,12 @@ class ImageTransport IMAGE_TRANSPORT_PUBLIC explicit ImageTransport(rclcpp::Node::SharedPtr node); + IMAGE_TRANSPORT_PUBLIC + ImageTransport(const ImageTransport & other); + + IMAGE_TRANSPORT_PUBLIC + ImageTransport & operator=(const ImageTransport & other); + IMAGE_TRANSPORT_PUBLIC ~ImageTransport(); @@ -364,6 +370,11 @@ class ImageTransport std::unique_ptr impl_; }; +struct ImageTransport::Impl +{ + rclcpp::Node::SharedPtr node_; +}; + } // namespace image_transport #endif // IMAGE_TRANSPORT__IMAGE_TRANSPORT_HPP_ diff --git a/image_transport/src/image_transport.cpp b/image_transport/src/image_transport.cpp index dfddcb91..67c3039c 100644 --- a/image_transport/src/image_transport.cpp +++ b/image_transport/src/image_transport.cpp @@ -128,10 +128,8 @@ std::vector getLoadableTransports() return loadableTransports; } -struct ImageTransport::Impl -{ - rclcpp::Node::SharedPtr node_; -}; +ImageTransport::ImageTransport(const ImageTransport & other) +: impl_(std::make_unique(*other.impl_)) {} ImageTransport::ImageTransport(rclcpp::Node::SharedPtr node) : impl_(std::make_unique()) diff --git a/image_transport_py/CHANGELOG.rst b/image_transport_py/CHANGELOG.rst new file mode 100644 index 00000000..8d393d32 --- /dev/null +++ b/image_transport_py/CHANGELOG.rst @@ -0,0 +1,3 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package image_transport_py +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt new file mode 100644 index 00000000..21ff9d31 --- /dev/null +++ b/image_transport_py/CMakeLists.txt @@ -0,0 +1,85 @@ +cmake_minimum_required(VERSION 3.20) +project(image_transport_py) + +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(ament_cmake_ros REQUIRED) +find_package(image_transport REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) + +# By default, without the settings below, find_package(Python3) will attempt +# to find the newest python version it can, and additionally will find the +# most specific version. For instance, on a system that has +# /usr/bin/python3.10, /usr/bin/python3.11, and /usr/bin/python3, it will find +# /usr/bin/python3.11, even if /usr/bin/python3 points to /usr/bin/python3.10. +# The behavior we want is to prefer the "system" installed version unless the +# user specifically tells us othewise through the Python3_EXECUTABLE hint. +# Setting CMP0094 to NEW means that the search will stop after the first +# python version is found. Setting Python3_FIND_UNVERSIONED_NAMES means that +# the search will prefer /usr/bin/python3 over /usr/bin/python3.11. And that +# latter functionality is only available in CMake 3.20 or later, so we need +# at least that version. +cmake_policy(SET CMP0094 NEW) +set(Python3_FIND_UNVERSIONED_NAMES FIRST) + +# Find python before pybind11 +find_package(Python3 REQUIRED COMPONENTS Interpreter Development) + +find_package(pybind11_vendor REQUIRED) +find_package(pybind11 REQUIRED) + +ament_python_install_package(${PROJECT_NAME}) + +pybind11_add_module(_image_transport MODULE + src/image_transport_py/pybind_image_transport.cpp +) + +target_include_directories(_image_transport PUBLIC + "$" + "$") + +target_link_libraries(_image_transport PUBLIC + image_transport::image_transport + rclcpp::rclcpp + ${sensor_msgs_TARGETS} +) + +# Install cython modules as sub-modules of the project +install( + TARGETS + _image_transport + DESTINATION "${PYTHON_INSTALL_DIR}/${PROJECT_NAME}" +) + +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + + list(APPEND AMENT_LINT_AUTO_EXCLUDE + ament_cmake_cppcheck + ) + ament_lint_auto_find_test_dependencies() + + if(NOT WIN32) + ament_cppcheck(LANGUAGE "c++") + else() + message(STATUS "Skipping ament_cppcheck on Windows") + endif() +endif() + +ament_package() diff --git a/image_transport_py/README.md b/image_transport_py/README.md new file mode 100644 index 00000000..97c8259e --- /dev/null +++ b/image_transport_py/README.md @@ -0,0 +1,128 @@ +# image_transport_py: Python Bindings for ROS 2 Image Transport + +## Introduction + +`image_transport_py` is a Python package that provides bindings for `image_transport`. It enables efficient publishing and subscribing of images in Python, leveraging various transport plugins (e.g., `raw`, `compressed`). +The package allows developers to handle image topics more efficiently and with less overhead than using standard ROS 2 topics. + +## Usage + +The detailed tutorial on `image_transport` and `image_transport_py` can be found at: https://github.com/ros-perception/image_transport_tutorials. + +## Classes + +### Publisher + +A publisher for images. + +#### Methods + +- `get_topic()` + + Returns the base image topic. + +- `get_num_subscribers()` + + Returns the number of subscribers this publisher is connected to. + +- `shutdown()` + + Unsubscribe the callback associated with this Publisher. + +- `publish(img)` + + Publish an image on the topics associated with this Publisher. + +### CameraPublisher + +A publisher for images with camera info. + +#### Methods + +- `get_topic()` + + Returns the base (image) topic of this CameraPublisher. + +- `get_num_subscribers()` + + Returns the number of subscribers this camera publisher is connected to. + +- `shutdown()` + + Unsubscribe the callback associated with this CameraPublisher. + +- `publish(img, info)` + + Publish an image and camera info on the topics associated with this Publisher. + +### ImageTransport + +An object for image transport operations. + +#### Constructor + +- `__init__(node_name, image_transport="", launch_params_filepath="")` + + Initialize an ImageTransport object with its node name, `image_transport` and launch params file path. If no `image_transport` specified, the default `raw` plugin will be initialized. + +#### Methods + +- `advertise(base_topic, queue_size, latch=False)` + + Advertise an image topic. + +- `advertise_camera(base_topic, queue_size, latch=False)` + + Advertise an image topic with camera info. + +- `subscribe(base_topic, queue_size, callback)` + + Subscribe to an image topic. + +- `subscribe_camera(base_topic, queue_size, callback)` + + Subscribe to an image topic with camera info. + +### Subscriber + +A subscriber for images. + +#### Methods + +- `get_topic()` + + Returns the base image topic. + +- `get_num_publishers()` + + Returns the number of publishers this subscriber is connected to. + +- `get_transport()` + + Returns the name of the transport being used. + +- `shutdown()` + + Unsubscribe the callback associated with this Subscriber. + +### CameraSubscriber + +A subscriber for images with camera info. + +#### Methods + +- `get_topic()` + + Returns the base image topic. + +- `get_num_publishers()` + + Returns the number of publishers this subscriber is connected to. + +- `get_transport()` + + Returns the name of the transport being used. + +- `shutdown()` + + Unsubscribe the callback associated with this CameraSubscriber. diff --git a/image_transport_py/image_transport_py/__init__.py b/image_transport_py/image_transport_py/__init__.py new file mode 100644 index 00000000..e4421c41 --- /dev/null +++ b/image_transport_py/image_transport_py/__init__.py @@ -0,0 +1,36 @@ +# Copyright 2024 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from rpyutils import add_dll_directories_from_env + +# Since Python 3.8, on Windows we should ensure DLL directories are explicitly added +# to the search path. +# See https://docs.python.org/3/whatsnew/3.8.html#bpo-36085-whatsnew +with add_dll_directories_from_env('PATH'): + from image_transport_py._image_transport import ( + ImageTransport, + Publisher, + Subscriber, + CameraPublisher, + CameraSubscriber, + ) + + +__all__ = [ + 'ImageTransport', + 'Publisher', + 'Subscriber', + 'CameraPublisher', + 'CameraSubscriber', +] diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp new file mode 100644 index 00000000..6263c5af --- /dev/null +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -0,0 +1,324 @@ +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +// +// File generated by gen_ros_casters.py. Do not manually change. + +#ifndef IMAGE_TRANSPORT_PY__CAST_IMAGE_HPP_ +#define IMAGE_TRANSPORT_PY__CAST_IMAGE_HPP_ + +#include +#include +#include +#include + +#include "pybind11/operators.h" +#include "pybind11/pybind11.h" +#include "pybind11/stl.h" + +#include "sensor_msgs/msg/image.hpp" +#include "sensor_msgs/msg/camera_info.hpp" + +#if PYBIND11_VERSION_MAJOR < 2 || (PYBIND11_VERSION_MAJOR == 2 && PYBIND11_VERSION_MINOR < 9) + #define const_name _ +#endif + +static inline bool is_ros_msg_type(pybind11::handle src, const std::string & msg_type_name) +{ + return pybind11::hasattr(src, "__module__") && + src.attr("__module__").cast() == msg_type_name; +} + +namespace pybind11 +{ +namespace detail +{ + +using ContainerAllocator = std::allocator; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + builtin_interfaces::msg::Time_, + const_name("builtin_interfaces::msg::Time_")); + bool load(handle src, bool) + { + if (!is_ros_msg_type(src, "builtin_interfaces.msg._time")) { + return false; + } + value.sec = src.attr("sec").cast(); + value.nanosec = src.attr("nanosec").cast(); + return true; + } + + static handle cast( + builtin_interfaces::msg::Time_ cpp_msg, return_value_policy /* policy */, + handle /* parent */) + { + object mod = module::import("builtin_interfaces.msg._time"); + object MsgType = mod.attr("Time"); + object msg = MsgType(); + msg.attr("sec") = pybind11::cast(cpp_msg.sec); + msg.attr("nanosec") = pybind11::cast(cpp_msg.nanosec); + msg.inc_ref(); + return msg; + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + std_msgs::msg::Header_, + const_name("std_msgs::msg::Header_")); + bool load(handle src, bool) + { + if (!is_ros_msg_type(src, "std_msgs.msg._header")) { + return false; + } + value.stamp = src.attr("stamp").cast>(); + value.frame_id = + src.attr("frame_id") + .cast, + typename std::allocator_traits::template rebind_alloc>>(); + return true; + } + + static handle cast( + std_msgs::msg::Header_ cpp_msg, return_value_policy /* policy */, + handle /* parent */) + { + object mod = module::import("std_msgs.msg._header"); + object MsgType = mod.attr("Header"); + object msg = MsgType(); + msg.attr("stamp") = pybind11::cast(cpp_msg.stamp); + msg.attr("frame_id") = pybind11::cast(cpp_msg.frame_id); + msg.inc_ref(); + return msg; + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + sensor_msgs::msg::Image_, + const_name("sensor_msgs::msg::Image_")); + bool load(handle src, bool) + { + if (!is_ros_msg_type(src, "sensor_msgs.msg._image")) { + return false; + } + value.header = src.attr("header").cast>(); + value.height = src.attr("height").cast(); + value.width = src.attr("width").cast(); + value.encoding = + src.attr("encoding") + .cast, + typename std::allocator_traits::template rebind_alloc>>(); + value.is_bigendian = src.attr("is_bigendian").cast(); + value.step = src.attr("step").cast(); + value.data = + src.attr("data") + .cast::template rebind_alloc>>(); + return true; + } + + static handle cast( + sensor_msgs::msg::Image_ cpp_msg, return_value_policy /* policy */, + handle /* parent */) + { + object mod = module::import("sensor_msgs.msg._image"); + object MsgType = mod.attr("Image"); + object msg = MsgType(); + msg.attr("header") = pybind11::cast(cpp_msg.header); + msg.attr("height") = pybind11::cast(cpp_msg.height); + msg.attr("width") = pybind11::cast(cpp_msg.width); + msg.attr("encoding") = pybind11::cast(cpp_msg.encoding); + msg.attr("is_bigendian") = pybind11::cast(cpp_msg.is_bigendian); + msg.attr("step") = pybind11::cast(cpp_msg.step); + msg.attr("data") = pybind11::cast(cpp_msg.data); + msg.inc_ref(); + return msg; + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + std::shared_ptr, + const_name("sensor_msgs::msg::Image")); + + bool load(handle src, bool) + { + type_caster base_caster; + if (!base_caster.load(src, false)) { + return false; + } + value = + std::make_shared( + std::move( + base_caster.operator sensor_msgs::msg + ::Image & ())); + return true; + } + + static handle cast( + const std::shared_ptr & ptr, + return_value_policy policy, handle parent) + { + if (!ptr) { + return pybind11::none().release(); + } + return type_caster::cast(*ptr, policy, parent); + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + sensor_msgs::msg::RegionOfInterest_, + const_name("sensor_msgs::msg::RegionOfInterest_")); + bool load(handle src, bool) + { + if (!is_ros_msg_type(src, "sensor_msgs.msg._region_of_interest")) { + return false; + } + value.x_offset = src.attr("x_offset").cast(); + value.y_offset = src.attr("y_offset").cast(); + value.height = src.attr("height").cast(); + value.width = src.attr("width").cast(); + value.do_rectify = src.attr("do_rectify").cast(); + return true; + } + + static handle cast( + sensor_msgs::msg::RegionOfInterest_ cpp_msg, + return_value_policy /* policy */, + handle /* parent */) + { + object mod = module::import("sensor_msgs.msg._region_of_interest"); + object MsgType = mod.attr("RegionOfInterest"); + object msg = MsgType(); + msg.attr("x_offset") = pybind11::cast(cpp_msg.x_offset); + msg.attr("y_offset") = pybind11::cast(cpp_msg.y_offset); + msg.attr("height") = pybind11::cast(cpp_msg.height); + msg.attr("width") = pybind11::cast(cpp_msg.width); + msg.attr("do_rectify") = pybind11::cast(cpp_msg.do_rectify); + msg.inc_ref(); + return msg; + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + sensor_msgs::msg::CameraInfo_, + const_name("sensor_msgs::msg::CameraInfo_")); + bool load(handle src, bool) + { + if (!is_ros_msg_type(src, "sensor_msgs.msg._camera_info")) { + return false; + } + value.header = src.attr("header").cast>(); + value.height = src.attr("height").cast(); + value.width = src.attr("width").cast(); + value.distortion_model = src.attr("distortion_model").cast, + typename std::allocator_traits::template rebind_alloc>>(); + value.d = src.attr("d").cast::template rebind_alloc>>(); + value.k = src.attr("k").cast>(); + value.r = src.attr("r").cast>(); + value.p = src.attr("p").cast>(); + value.binning_x = src.attr("binning_x").cast(); + value.binning_y = src.attr("binning_y").cast(); + value.roi = src.attr("roi").cast>(); + return true; + } + + static handle cast( + sensor_msgs::msg::CameraInfo_ cpp_msg, + return_value_policy /* policy */, + handle /* parent */) + { + object mod = module::import("sensor_msgs.msg._camera_info"); + object MsgType = mod.attr("CameraInfo"); + object msg = MsgType(); + msg.attr("header") = pybind11::cast(cpp_msg.header); + msg.attr("height") = pybind11::cast(cpp_msg.height); + msg.attr("width") = pybind11::cast(cpp_msg.width); + msg.attr("distortion_model") = pybind11::cast(cpp_msg.distortion_model); + msg.attr("d") = pybind11::cast(cpp_msg.d); + msg.attr("k") = pybind11::cast(cpp_msg.k); + msg.attr("r") = pybind11::cast(cpp_msg.r); + msg.attr("p") = pybind11::cast(cpp_msg.p); + msg.attr("binning_x") = pybind11::cast(cpp_msg.binning_x); + msg.attr("binning_y") = pybind11::cast(cpp_msg.binning_y); + msg.attr("roi") = pybind11::cast(cpp_msg.roi); + msg.inc_ref(); + return msg; + } +}; + +template<> +struct type_caster> +{ +public: + PYBIND11_TYPE_CASTER( + std::shared_ptr, + const_name("sensor_msgs::msg::CameraInfo")); + + bool load(handle src, bool) + { + type_caster base_caster; + if (!base_caster.load(src, false)) { + return false; + } + value = + std::make_shared( + std::move( + base_caster.operator sensor_msgs + ::msg::CameraInfo & ())); + return true; + } + + static handle cast( + const std::shared_ptr & ptr, + return_value_policy policy, handle parent) + { + if (!ptr) { + return pybind11::none().release(); + } + return type_caster::cast(*ptr, policy, parent); + } +}; + +} // namespace detail +} // namespace pybind11 + +#endif // IMAGE_TRANSPORT_PY__CAST_IMAGE_HPP_ diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml new file mode 100644 index 00000000..bb428ef7 --- /dev/null +++ b/image_transport_py/package.xml @@ -0,0 +1,36 @@ + + image_transport_py + + 5.0.3 + + Python API for image_transport + + Tamas Foldi + + Alejandro Hernández + John D'Angelo + + BSD + + https://github.com/ros-perception/image_common + https://github.com/ros-perception/image_common/issues + + ament_cmake_ros + ament_cmake_python + + pybind11_vendor + + image_transport + rclcpp + sensor_msgs + + ament_lint_auto + ament_lint_common + + rpyutils + + + ament_cmake + + + diff --git a/image_transport_py/src/image_transport_py/pybind11.hpp b/image_transport_py/src/image_transport_py/pybind11.hpp new file mode 100644 index 00000000..9599b324 --- /dev/null +++ b/image_transport_py/src/image_transport_py/pybind11.hpp @@ -0,0 +1,31 @@ +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef IMAGE_TRANSPORT_PY__PYBIND11_HPP_ +#define IMAGE_TRANSPORT_PY__PYBIND11_HPP_ + +// Ignore -Wunused-value for clang. +// Based on https://github.com/pybind/pybind11/issues/2225 +#if defined(__clang__) +#pragma clang diagnostic push +#pragma clang diagnostic ignored "-Wunused-value" +#endif +#include +#if defined(__clang__) +#pragma clang diagnostic pop +#endif +#include +#include + +#endif // IMAGE_TRANSPORT_PY__PYBIND11_HPP_ diff --git a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp new file mode 100644 index 00000000..0c0b4cd5 --- /dev/null +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -0,0 +1,211 @@ +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include +#include + +#include "./pybind11.hpp" +#include "image_transport_py/cast_image.hpp" + +#include +#include +#include +#include +#include +#include + +using namespace std::chrono_literals; + +namespace image_transport_python +{ + +template +using SubscriberMap = std::unordered_map>; + +// Bindings for the image_transport classes +PYBIND11_MODULE(_image_transport, m) +{ + m.doc() = "Python wrapper of the image_transport API"; + + pybind11::class_(m, "Publisher") + .def(pybind11::init()) + .def("get_topic", &image_transport::Publisher::getTopic, "Returns the base image topic.") + .def( + "get_num_subscribers", &image_transport::Publisher::getNumSubscribers, + "Returns the number of subscribers this publisher is connected to.") + .def( + "shutdown", &image_transport::Publisher::shutdown, + "Unsubscribe the callback associated with this Publisher.") + .def( + "publish", + [](image_transport::Publisher & publisher, sensor_msgs::msg::Image & img) { + publisher.publish(img); + }, + "Publish an image on the topics associated with this Publisher."); + + pybind11::class_(m, "CameraPublisher") + .def(pybind11::init()) + .def( + "get_topic", &image_transport::CameraPublisher::getTopic, + "Returns the base (image) topic of this CameraPublisher.") + .def( + "get_num_subscribers", &image_transport::CameraPublisher::getNumSubscribers, + "Returns the number of subscribers this camera publisher is connected to.") + .def( + "shutdown", &image_transport::CameraPublisher::shutdown, + "Unsubscribe the callback associated with this CameraPublisher.") + .def( + "publish", + [](image_transport::CameraPublisher & publisher, sensor_msgs::msg::Image & img, + sensor_msgs::msg::CameraInfo & info) { + publisher.publish(img, info); + }, + "Publish an image and camera info on the topics associated with this Publisher."); + + pybind11::class_(m, "ImageTransport") + .def( + pybind11::init( + [](const std::string & node_name, const std::string & image_transport, + const std::string & launch_params_filepath) { + if (!rclcpp::ok()) { + rclcpp::init(0, nullptr); + } + rclcpp::NodeOptions node_options; + + if (!launch_params_filepath.empty()) { + node_options.allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true) + .arguments({"--ros-args", "--params-file", launch_params_filepath}); + } else if (!image_transport.empty()) { + node_options.allow_undeclared_parameters(true) + .automatically_declare_parameters_from_overrides(true) + .append_parameter_override("image_transport", image_transport); + } + + rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options); + + std::shared_ptr executor = + std::make_shared(); + + auto spin_node = [node, executor]() { + executor->add_node(node); + executor->spin(); + }; + std::thread execution_thread(spin_node); + execution_thread.detach(); + + return image_transport::ImageTransport(node); + }), + pybind11::arg("node_name"), pybind11::arg("image_transport") = "", + pybind11::arg("launch_params_filepath") = "", + + "Initialize an ImageTransport object with a node name, image_transport" + " and launch params file path.") + .def( + "advertise", + pybind11::overload_cast( + &image_transport::ImageTransport::advertise), + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false, + "Advertise an image topic.") + .def( + "advertise_camera", + pybind11::overload_cast( + &image_transport::ImageTransport::advertiseCamera), + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false, + "Advertise an image topic with camera info.") + .def( + "subscribe", + [](image_transport::ImageTransport & image_transport, + const std::string & base_topic, + uint32_t queue_size, + const image_transport::Subscriber::Callback & callback) { + + // Static vector to keep the subscriptions alive + thread_local auto vec = std::vector>(); + auto subscription = + std::make_shared( + image_transport.subscribe( + base_topic, + queue_size, callback)); + vec.push_back(subscription); + + return subscription; + }, + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"), + "Subscribe to an image topic.") + .def( + "subscribe_camera", + [](image_transport::ImageTransport & image_transport, + const std::string & base_topic, + uint32_t queue_size, + const image_transport::CameraSubscriber::Callback & callback) { + + // Static vector to keep the subscriptions alive + thread_local auto vec = std::vector>(); + auto subscription = + std::make_shared( + image_transport.subscribeCamera( + base_topic, + queue_size, callback)); + vec.push_back(subscription); + + return subscription; + }, + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"), + "Subscribe to an image topic with camera info."); + + pybind11::class_>( + m, + "Subscriber") + .def(pybind11::init()) + .def( + "get_topic", + &image_transport::Subscriber::getTopic, + "Returns the base image topic.") + .def( + "get_num_publishers", + &image_transport::Subscriber::getNumPublishers, + "Returns the number of publishers this subscriber is connected to.") + .def( + "get_transport", + &image_transport::Subscriber::getTransport, + "Returns the name of the transport being used.") + .def( + "shutdown", &image_transport::Subscriber::shutdown, + "Unsubscribe the callback associated with this Subscriber."); + + pybind11::class_>( + m, + "CameraSubscriber") + .def(pybind11::init()) + .def( + "get_topic", + &image_transport::CameraSubscriber::getTopic, + "Returns the base image topic.") + .def( + "get_num_publishers", + &image_transport::CameraSubscriber::getNumPublishers, + "Returns the number of publishers this subscriber is connected to.") + .def( + "get_transport", + &image_transport::CameraSubscriber::getTransport, + "Returns the name of the transport being used.") + .def( + "shutdown", &image_transport::CameraSubscriber::shutdown, + "Unsubscribe the callback associated with this CameraSubscriber."); +} +} // namespace image_transport_python