From c4d84344deae3c013ab7485324de41943a6914d2 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Mon, 23 Sep 2024 21:00:25 +0200 Subject: [PATCH 01/25] feat: python bindings for image_transport and publish --- .../image_transport/image_transport.hpp | 11 ++ image_transport/src/image_transport.cpp | 6 +- image_transport_py/CHANGELOG.rst | 3 + image_transport_py/CMakeLists.txt | 66 +++++++ .../image_transport_py/__init__.py | 30 ++++ .../include/image_transport_py/cast_image.hpp | 161 ++++++++++++++++++ image_transport_py/package.xml | 34 ++++ .../src/image_transport_py/pybind11.hpp | 31 ++++ .../pybind_image_transport.cpp | 85 +++++++++ 9 files changed, 423 insertions(+), 4 deletions(-) create mode 100644 image_transport_py/CHANGELOG.rst create mode 100644 image_transport_py/CMakeLists.txt create mode 100644 image_transport_py/image_transport_py/__init__.py create mode 100644 image_transport_py/include/image_transport_py/cast_image.hpp create mode 100644 image_transport_py/package.xml create mode 100644 image_transport_py/src/image_transport_py/pybind11.hpp create mode 100644 image_transport_py/src/image_transport_py/pybind_image_transport.cpp diff --git a/image_transport/include/image_transport/image_transport.hpp b/image_transport/include/image_transport/image_transport.hpp index e430cd92..372778f3 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..189fccd8 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..f87e6d4a --- /dev/null +++ b/image_transport_py/CMakeLists.txt @@ -0,0 +1,66 @@ +cmake_minimum_required(VERSION 3.5) +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() + +# Figure out Python3 debug/release before anything else can find_package it +if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug") + find_package(python_cmake_module REQUIRED) + find_package(PythonExtra REQUIRED) + + # Force FindPython3 to use the debug interpreter where ROS 2 expects it + set(Python3_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}") +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(pluginlib REQUIRED) +find_package(rclcpp REQUIRED) +find_package(sensor_msgs REQUIRED) + +# 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}" +) + +ament_package() 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..f8fe945d --- /dev/null +++ b/image_transport_py/image_transport_py/__init__.py @@ -0,0 +1,30 @@ +# Copyright 2023 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, + ) + + +__all__ = [ + 'ImageTransport', + 'Publisher', +] \ No newline at end of file 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..486b9be5 --- /dev/null +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -0,0 +1,161 @@ +// Copyright 2023 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 "pybind11/operators.h" +#include "pybind11/pybind11.h" +#include "pybind11/stl.h" + +#include "sensor_msgs/msg/image.hpp" + +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; + } +}; + +} // 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..f29eb72c --- /dev/null +++ b/image_transport_py/package.xml @@ -0,0 +1,34 @@ + + 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_transport + https://github.com/ros-perception/image_transport/issues + + ament_cmake_ros + ament_cmake_python + python_cmake_module + + image_transport + pybind11_vendor + pluginlib + rclcpp + sensor_msgs + + 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..3d5e20e1 --- /dev/null +++ b/image_transport_py/src/image_transport_py/pybind11.hpp @@ -0,0 +1,31 @@ +// Copyright 2023 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..5537d16a --- /dev/null +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -0,0 +1,85 @@ +// Copyright 2023 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 "./pybind11.hpp" +#include "image_transport_py/cast_image.hpp" + +#include +#include +#include +#include +#include +#include + +namespace image_transport_python +{ +// Bindings for the ImageCodec class +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, "ImageTransport") + .def( + pybind11::init([](const std::string & node_name, 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}); + } + 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); + })) + .def( + "advertise", + pybind11::overload_cast( + &image_transport::ImageTransport::advertise), + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false); +} +} // namespace image_transport_python From ac72a101cc65489f722f21f0b0d1651c396c4f20 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 24 Sep 2024 14:25:26 +0200 Subject: [PATCH 02/25] style: reformat code --- .../image_transport/image_transport.hpp | 4 +- image_transport_py/CMakeLists.txt | 11 ++++ .../image_transport_py/__init__.py | 2 +- .../include/image_transport_py/cast_image.hpp | 12 ++-- image_transport_py/package.xml | 3 + .../pybind_image_transport.cpp | 55 ++++++++++--------- 6 files changed, 51 insertions(+), 36 deletions(-) diff --git a/image_transport/include/image_transport/image_transport.hpp b/image_transport/include/image_transport/image_transport.hpp index 372778f3..5821e1db 100644 --- a/image_transport/include/image_transport/image_transport.hpp +++ b/image_transport/include/image_transport/image_transport.hpp @@ -113,10 +113,10 @@ class ImageTransport explicit ImageTransport(rclcpp::Node::SharedPtr node); IMAGE_TRANSPORT_PUBLIC - ImageTransport(const ImageTransport& other); + ImageTransport(const ImageTransport & other); IMAGE_TRANSPORT_PUBLIC - ImageTransport& operator=(const ImageTransport& other); + ImageTransport & operator=(const ImageTransport & other); IMAGE_TRANSPORT_PUBLIC ~ImageTransport(); diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index f87e6d4a..97f5892e 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -63,4 +63,15 @@ install( 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() + + ament_cppcheck(LANGUAGE "c++") +endif() + ament_package() diff --git a/image_transport_py/image_transport_py/__init__.py b/image_transport_py/image_transport_py/__init__.py index f8fe945d..0462fd6e 100644 --- a/image_transport_py/image_transport_py/__init__.py +++ b/image_transport_py/image_transport_py/__init__.py @@ -27,4 +27,4 @@ __all__ = [ 'ImageTransport', 'Publisher', -] \ No newline at end of file +] diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index 486b9be5..dc7480bb 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -40,7 +40,7 @@ namespace detail using ContainerAllocator = std::allocator; -template <> +template<> struct type_caster> { public: @@ -71,7 +71,7 @@ struct type_caster> } }; -template <> +template<> struct type_caster> { public: @@ -86,7 +86,7 @@ struct type_caster> value.stamp = src.attr("stamp").cast>(); value.frame_id = src.attr("frame_id") - .cast, typename std::allocator_traits::template rebind_alloc>>(); return true; @@ -106,7 +106,7 @@ struct type_caster> } }; -template <> +template<> struct type_caster> { public: @@ -123,14 +123,14 @@ struct type_caster> 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; diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml index f29eb72c..d4b57829 100644 --- a/image_transport_py/package.xml +++ b/image_transport_py/package.xml @@ -25,6 +25,9 @@ rclcpp sensor_msgs + ament_lint_auto + ament_lint_common + rpyutils 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 index 5537d16a..5f8e47ac 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -34,24 +34,25 @@ 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."); + .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, "ImageTransport") - .def( - pybind11::init([](const std::string & node_name, const std::string & launch_params_filepath) { + .def( + pybind11::init( + [](const std::string & node_name, const std::string & launch_params_filepath) { if (!rclcpp::ok()) { rclcpp::init(0, nullptr); } @@ -59,27 +60,27 @@ PYBIND11_MODULE(_image_transport, m) 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}); + .automatically_declare_parameters_from_overrides(true) + .arguments({"--ros-args", "--params-file", launch_params_filepath}); } rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options); std::shared_ptr executor = - std::make_shared(); + std::make_shared(); auto spin_node = [node, executor]() { - executor->add_node(node); - executor->spin(); - }; + executor->add_node(node); + executor->spin(); + }; std::thread execution_thread(spin_node); execution_thread.detach(); return image_transport::ImageTransport(node); })) - .def( - "advertise", - pybind11::overload_cast( - &image_transport::ImageTransport::advertise), - pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false); + .def( + "advertise", + pybind11::overload_cast( + &image_transport::ImageTransport::advertise), + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false); } } // namespace image_transport_python From 4f95097c95fea8c50807f7b02e1b751020739e6c Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 24 Sep 2024 14:36:50 +0200 Subject: [PATCH 03/25] style: missing headers, copyright year --- image_transport/src/image_transport.cpp | 2 +- image_transport_py/image_transport_py/__init__.py | 2 +- image_transport_py/include/image_transport_py/cast_image.hpp | 3 ++- image_transport_py/src/image_transport_py/pybind11.hpp | 2 +- .../src/image_transport_py/pybind_image_transport.cpp | 3 ++- 5 files changed, 7 insertions(+), 5 deletions(-) diff --git a/image_transport/src/image_transport.cpp b/image_transport/src/image_transport.cpp index 189fccd8..67c3039c 100644 --- a/image_transport/src/image_transport.cpp +++ b/image_transport/src/image_transport.cpp @@ -128,7 +128,7 @@ std::vector getLoadableTransports() return loadableTransports; } -ImageTransport::ImageTransport(const ImageTransport& other) +ImageTransport::ImageTransport(const ImageTransport & other) : impl_(std::make_unique(*other.impl_)) {} ImageTransport::ImageTransport(rclcpp::Node::SharedPtr node) diff --git a/image_transport_py/image_transport_py/__init__.py b/image_transport_py/image_transport_py/__init__.py index 0462fd6e..c24bc672 100644 --- a/image_transport_py/image_transport_py/__init__.py +++ b/image_transport_py/image_transport_py/__init__.py @@ -1,4 +1,4 @@ -# Copyright 2023 Open Source Robotics Foundation, Inc. +# 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. diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index dc7480bb..031cb98c 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Open Source Robotics Foundation, Inc. +// 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. @@ -17,6 +17,7 @@ #ifndef IMAGE_TRANSPORT_PY__CAST_IMAGE_HPP_ #define IMAGE_TRANSPORT_PY__CAST_IMAGE_HPP_ +#include #include #include #include diff --git a/image_transport_py/src/image_transport_py/pybind11.hpp b/image_transport_py/src/image_transport_py/pybind11.hpp index 3d5e20e1..9599b324 100644 --- a/image_transport_py/src/image_transport_py/pybind11.hpp +++ b/image_transport_py/src/image_transport_py/pybind11.hpp @@ -1,4 +1,4 @@ -// Copyright 2023 Open Source Robotics Foundation, Inc. +// 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. 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 index 5f8e47ac..2f567cd9 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -1,4 +1,4 @@ -// Copyright 2023 Open Source Robotics Foundation, Inc. +// 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. @@ -12,6 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. +#include #include #include #include From ff4ffd7f2ed75a2964dfad4caff4ef20a3c0153e Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 24 Sep 2024 14:39:21 +0200 Subject: [PATCH 04/25] build: add tests --- image_transport_py/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml index d4b57829..a9fbf6a9 100644 --- a/image_transport_py/package.xml +++ b/image_transport_py/package.xml @@ -21,7 +21,6 @@ image_transport pybind11_vendor - pluginlib rclcpp sensor_msgs From 8a4250c0f2596586ac3a30beab9e667828c79b17 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 24 Sep 2024 14:40:59 +0200 Subject: [PATCH 05/25] build: remove pluginlib (not used) --- image_transport_py/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index 97f5892e..9a0dd585 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -30,7 +30,6 @@ find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_ros REQUIRED) find_package(image_transport REQUIRED) -find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(sensor_msgs REQUIRED) From 898d875efcc233e0cb0d3177d7a65fb1979ecdbb Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 24 Sep 2024 16:00:21 +0200 Subject: [PATCH 06/25] style: reformat with rolling ament config --- .../src/image_transport_py/pybind_image_transport.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) 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 index 2f567cd9..200500ff 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -70,9 +70,9 @@ PYBIND11_MODULE(_image_transport, m) std::make_shared(); auto spin_node = [node, executor]() { - executor->add_node(node); - executor->spin(); - }; + executor->add_node(node); + executor->spin(); + }; std::thread execution_thread(spin_node); execution_thread.detach(); From 4ceb2ecbd33d64b3c8081e3baf5a2d1ea1598cfe Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Thu, 26 Sep 2024 07:50:47 +0200 Subject: [PATCH 07/25] WIP: before moving spin to custom class --- .../pybind_image_transport.cpp | 115 +++++++++++++++++- 1 file changed, 109 insertions(+), 6 deletions(-) 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 index 2f567cd9..da4e9865 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -27,9 +27,30 @@ #include #include +using namespace std::chrono_literals; + namespace image_transport_python { -// Bindings for the ImageCodec class + +class PyImageTransport : public image_transport::ImageTransport { +public: + // Constructor that takes an rclcpp::Node::SharedPtr + PyImageTransport(const rclcpp::Node::SharedPtr& node) + : image_transport::ImageTransport(node) {} + + // Public member variable for the subscriber + thread_local image_transport::Subscriber subscriber_; +}; + + +void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) +{ + RCLCPP_INFO( + rclcpp::get_logger( + "image_transport"), "message arrived yoho. %s", msg->encoding.c_str()); + +} +// Bindings for the image_transport classes PYBIND11_MODULE(_image_transport, m) { m.doc() = "Python wrapper of the image_transport API"; @@ -50,7 +71,27 @@ PYBIND11_MODULE(_image_transport, m) }, "Publish an image on the topics associated with this Publisher."); - pybind11::class_(m, "ImageTransport") + 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") + pybind11::class_(m, "ImageTransport") .def( pybind11::init( [](const std::string & node_name, const std::string & launch_params_filepath) { @@ -66,22 +107,84 @@ PYBIND11_MODULE(_image_transport, m) } rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options); - std::shared_ptr executor = - std::make_shared(); + + RCLCPP_INFO(node->get_logger(), "starting thread"); + std::shared_ptr executor = + std::make_shared(); auto spin_node = [node, executor]() { + // auto subscription = node->create_subscription( + // "camera/image", 10, image_transport_python::imageCallback); + + RCLCPP_INFO(node->get_logger(), "spin on!"); executor->add_node(node); executor->spin(); + // while (rclcpp::ok()) { + // Spin some to process available callbacks, but do not block indefinitely + // executor->spin_some(); // Spin for up to 100ms at a time + // std::this_thread::sleep_for(1000ms); // Simulate other tasks or waiting + // RCLCPP_INFO(node->get_logger(), "spinnn!"); + // } + + RCLCPP_INFO(node->get_logger(), "spin off!"); }; std::thread execution_thread(spin_node); execution_thread.detach(); - return image_transport::ImageTransport(node); + // return image_transport::ImageTransport(node); + return image_transport_python::PyImageTransport(node); })) .def( "advertise", pybind11::overload_cast( &image_transport::ImageTransport::advertise), - pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false); + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false) + .def( + "advertise_camera", + pybind11::overload_cast( + &image_transport::ImageTransport::advertiseCamera), + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false) + .def( + "subscribe", + [](image_transport_python::PyImageTransport & image_transport, + const std::string & base_topic, + uint32_t queue_size, + const std::function & callback) { + + RCLCPP_INFO(image_transport.impl_->node_->get_logger(), "in subscribe"); + + // image_transport.subscriber_ = std::make_unique(image_transport.subscribe(base_topic, queue_size, image_transport_python::imageCallback)) ; + // auto subscription = + thread_local auto subscription = std::make_shared(image_transport.subscribe(base_topic, queue_size, image_transport_python::imageCallback)) ; + // RCLCPP_INFO(image_transport.impl_->node_->get_logger(), "subscribed to %s", subscription.getTopic().c_str()); + + return subscription; + + }, + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback")) + + ; + + 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."); + + } } // namespace image_transport_python From 591c0fe9d80a5b224e57560af9655735fdec70c7 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Thu, 26 Sep 2024 11:01:48 +0200 Subject: [PATCH 08/25] doc: fix repository and bugtracker url --- image_transport_py/package.xml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml index a9fbf6a9..0b31598e 100644 --- a/image_transport_py/package.xml +++ b/image_transport_py/package.xml @@ -12,8 +12,8 @@ BSD - https://github.com/ros-perception/image_transport - https://github.com/ros-perception/image_transport/issues + https://github.com/ros-perception/image_common + https://github.com/ros-perception/image_common/issues ament_cmake_ros ament_cmake_python From 2eddcbfb2d8f6418a6812d691942bacea8fdab6a Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Thu, 26 Sep 2024 11:02:32 +0200 Subject: [PATCH 09/25] feat: camera_info and subscriber support --- .../include/image_transport_py/cast_image.hpp | 158 ++++++++++++++++++ .../pybind_image_transport.cpp | 99 ++++++----- 2 files changed, 211 insertions(+), 46 deletions(-) diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index 031cb98c..28d1a04c 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -27,6 +27,7 @@ #include "pybind11/stl.h" #include "sensor_msgs/msg/image.hpp" +#include "sensor_msgs/msg/camera_info.hpp" static inline bool is_ros_msg_type(pybind11::handle src, const std::string & msg_type_name) { @@ -156,6 +157,163 @@ struct type_caster> } }; +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 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 index da4e9865..ff9f3dbb 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -32,24 +32,9 @@ using namespace std::chrono_literals; namespace image_transport_python { -class PyImageTransport : public image_transport::ImageTransport { -public: - // Constructor that takes an rclcpp::Node::SharedPtr - PyImageTransport(const rclcpp::Node::SharedPtr& node) - : image_transport::ImageTransport(node) {} +template +using SubscriberMap = std::unordered_map>; - // Public member variable for the subscriber - thread_local image_transport::Subscriber subscriber_; -}; - - -void imageCallback(const sensor_msgs::msg::Image::ConstSharedPtr & msg) -{ - RCLCPP_INFO( - rclcpp::get_logger( - "image_transport"), "message arrived yoho. %s", msg->encoding.c_str()); - -} // Bindings for the image_transport classes PYBIND11_MODULE(_image_transport, m) { @@ -90,8 +75,7 @@ PYBIND11_MODULE(_image_transport, m) }, "Publish an image and camera info on the topics associated with this Publisher."); - // pybind11::class_(m, "ImageTransport") - pybind11::class_(m, "ImageTransport") + pybind11::class_(m, "ImageTransport") .def( pybind11::init( [](const std::string & node_name, const std::string & launch_params_filepath) { @@ -107,32 +91,17 @@ PYBIND11_MODULE(_image_transport, m) } rclcpp::Node::SharedPtr node = rclcpp::Node::make_shared(node_name, "", node_options); - - RCLCPP_INFO(node->get_logger(), "starting thread"); std::shared_ptr executor = std::make_shared(); auto spin_node = [node, executor]() { - // auto subscription = node->create_subscription( - // "camera/image", 10, image_transport_python::imageCallback); - - RCLCPP_INFO(node->get_logger(), "spin on!"); executor->add_node(node); executor->spin(); - // while (rclcpp::ok()) { - // Spin some to process available callbacks, but do not block indefinitely - // executor->spin_some(); // Spin for up to 100ms at a time - // std::this_thread::sleep_for(1000ms); // Simulate other tasks or waiting - // RCLCPP_INFO(node->get_logger(), "spinnn!"); - // } - - RCLCPP_INFO(node->get_logger(), "spin off!"); }; std::thread execution_thread(spin_node); execution_thread.detach(); - // return image_transport::ImageTransport(node); - return image_transport_python::PyImageTransport(node); + return image_transport::ImageTransport(node); })) .def( "advertise", @@ -146,24 +115,42 @@ PYBIND11_MODULE(_image_transport, m) pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("latch") = false) .def( "subscribe", - [](image_transport_python::PyImageTransport & image_transport, + [](image_transport::ImageTransport & image_transport, const std::string & base_topic, uint32_t queue_size, - const std::function & callback) { + const image_transport::Subscriber::Callback & callback) { - RCLCPP_INFO(image_transport.impl_->node_->get_logger(), "in subscribe"); - - // image_transport.subscriber_ = std::make_unique(image_transport.subscribe(base_topic, queue_size, image_transport_python::imageCallback)) ; - // auto subscription = - thread_local auto subscription = std::make_shared(image_transport.subscribe(base_topic, queue_size, image_transport_python::imageCallback)) ; - // RCLCPP_INFO(image_transport.impl_->node_->get_logger(), "subscribed to %s", subscription.getTopic().c_str()); + // 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")) + .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")); pybind11::class_>( m, @@ -186,5 +173,25 @@ PYBIND11_MODULE(_image_transport, m) "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 From 1d331aba74d9c8cc8df2daabc6ec230526d7ecdf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?F=C3=B6ldi=20Tam=C3=A1s?= Date: Thu, 26 Sep 2024 19:35:50 +0200 Subject: [PATCH 10/25] doc: create initial version of the README.md file --- README.md | 90 +++++++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 90 insertions(+) create mode 100644 README.md diff --git a/README.md b/README.md new file mode 100644 index 00000000..c22dc9bc --- /dev/null +++ b/README.md @@ -0,0 +1,90 @@ +# image_transport_py: Python Bindings for ROS2 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 ROS2 topics. + +## Usage + +### Publishing Images + +To publish images using `image_transport_py`, you create an `ImageTransport` object and use it to advertise an image topic. The first parameter for `ImageTransport` is the image transport +node's name which needs to be unique in the namespace. + +Steps: + +1. Import Necessary Modules: + +```python +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import Image +from image_transport_py import ImageTransport +``` + +2. Initialize the Node and ImageTransport: + +```python +class ImagePublisher(Node): + def __init__(self): + super().__init__('image_publisher') + self.image_transport = ImageTransport("imagetransport_pub", image_transport="raw") + self.publisher = self.image_transport.advertise('camera/image', 10) + + # read images at 10Hz frequency + self.timer = self.create_timer(0.1, self.publish_image) +``` + +3. Publish Images in the Callback: +```python + def publish_image(self): + image_msg = .. # Read image from your devices + + image_msg.header.stamp = self.get_clock().now().to_msg() + self.publisher.publish(image_msg) +``` + +`advertise_camera` can publish `CameraInfo` along with `Image` message. + + +### Subscribing to Images + +To subscribe to images, use `ImageTransport` to create a subscription to the image topic. + +Steps: + +1. Import Necessary Modules: + +```python +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import Image +from image_transport_py import ImageTransport +``` + +2. Initialize the Node and ImageTransport: +```python +class ImageSubscriber(Node): + def __init__(self): + super().__init__('image_subscriber') + self.image_transport = ImageTransport("imagetransport_sub", image_transport="raw") + self.subscription = self.image_transport.subscribe('camera/image', self.image_callback, 10) +``` + +3. Handle Incoming Images: +```python + def image_callback(self, msg): + # do something with msg (= sensor_msgs.msg.Image type) +``` + +`subscribe_camera` will add `CameraInfo` along with `Image` message for the callback. + + +### Transport Selection + +By default, `image_transport` uses the `raw` transport. You can specify a different transport by passing `image_transport` parameter to `ImageTransport`. Alternatively, +you can use your own ROS2 parameter file for the imagetransport node + + + From 74e32f156802a33a85db1113814a67e80f762127 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Thu, 26 Sep 2024 19:52:25 +0200 Subject: [PATCH 11/25] doc: move README.md to the right location --- README.md => image_transport_py/README.md | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename README.md => image_transport_py/README.md (100%) diff --git a/README.md b/image_transport_py/README.md similarity index 100% rename from README.md rename to image_transport_py/README.md From f3ece7d3b73e940c75b7f91485c2064d0d2eaa5a Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Thu, 26 Sep 2024 19:54:10 +0200 Subject: [PATCH 12/25] feat: add image_transport parameter --- .../pybind_image_transport.cpp | 32 +++++++++++++------ 1 file changed, 23 insertions(+), 9 deletions(-) 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 index 0dff1272..c8b90251 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -78,7 +78,8 @@ PYBIND11_MODULE(_image_transport, m) pybind11::class_(m, "ImageTransport") .def( pybind11::init( - [](const std::string & node_name, const std::string & launch_params_filepath) { + [](const std::string & node_name, const std::string & image_transport, + const std::string & launch_params_filepath) { if (!rclcpp::ok()) { rclcpp::init(0, nullptr); } @@ -88,31 +89,42 @@ PYBIND11_MODULE(_image_transport, m) 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(); - }; + 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 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) + 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) + 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, @@ -131,7 +143,8 @@ PYBIND11_MODULE(_image_transport, m) return subscription; }, - pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback")) + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"), + "Subscribe to an image topic.") .def( "subscribe_camera", [](image_transport::ImageTransport & image_transport, @@ -150,7 +163,8 @@ PYBIND11_MODULE(_image_transport, m) return subscription; }, - pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback")); + pybind11::arg("base_topic"), pybind11::arg("queue_size"), pybind11::arg("callback"), + "Subscribe to an image topic with camera info."); pybind11::class_>( m, From 98042aa821baf0a1c4b4fb995a623a0c34298d31 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Fri, 27 Sep 2024 08:55:02 +0200 Subject: [PATCH 13/25] doc: complete documentation --- image_transport_py/README.md | 118 +++++++++++++++++- .../image_transport_py/__init__.py | 6 + .../pybind_image_transport.cpp | 8 +- 3 files changed, 127 insertions(+), 5 deletions(-) diff --git a/image_transport_py/README.md b/image_transport_py/README.md index c22dc9bc..68158550 100644 --- a/image_transport_py/README.md +++ b/image_transport_py/README.md @@ -84,7 +84,123 @@ class ImageSubscriber(Node): ### Transport Selection By default, `image_transport` uses the `raw` transport. You can specify a different transport by passing `image_transport` parameter to `ImageTransport`. Alternatively, -you can use your own ROS2 parameter file for the imagetransport node +you can use your own ROS2 parameter file for the imagetransport node via `launch_params_filepath` parameter. +## 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 index c24bc672..e4421c41 100644 --- a/image_transport_py/image_transport_py/__init__.py +++ b/image_transport_py/image_transport_py/__init__.py @@ -21,10 +21,16 @@ from image_transport_py._image_transport import ( ImageTransport, Publisher, + Subscriber, + CameraPublisher, + CameraSubscriber, ) __all__ = [ 'ImageTransport', 'Publisher', + 'Subscriber', + 'CameraPublisher', + 'CameraSubscriber', ] 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 index c8b90251..7ba94060 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -101,9 +101,9 @@ PYBIND11_MODULE(_image_transport, m) std::make_shared(); auto spin_node = [node, executor]() { - executor->add_node(node); - executor->spin(); - }; + executor->add_node(node); + executor->spin(); + }; std::thread execution_thread(spin_node); execution_thread.detach(); @@ -112,7 +112,7 @@ PYBIND11_MODULE(_image_transport, m) pybind11::arg("node_name"), pybind11::arg("image_transport") = "", pybind11::arg("launch_params_filepath") = "", - "Initialize an ImageTransport object with a node name and launch params file path.") + "Initialize an ImageTransport object with a node name, image_transport and launch params file path.") .def( "advertise", pybind11::overload_cast( From 1cc8b23932e829848353233ac6916f7102fc0543 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Fri, 27 Sep 2024 09:04:46 +0200 Subject: [PATCH 14/25] style: remove too long line --- .../src/image_transport_py/pybind_image_transport.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) 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 index 7ba94060..9913b666 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -112,7 +112,8 @@ PYBIND11_MODULE(_image_transport, m) 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.") + "Initialize an ImageTransport object with a node name, image_transport" + " and launch params file path.") .def( "advertise", pybind11::overload_cast( From 03b8e9ae22e6259c04bdf383299a03e3cd870317 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?F=C3=B6ldi=20Tam=C3=A1s?= Date: Fri, 27 Sep 2024 15:14:50 +0200 Subject: [PATCH 15/25] style: reformat MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- image_transport_py/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index 9a0dd585..f553837c 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -25,7 +25,6 @@ if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug") set(Python3_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}") endif() - find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_ros REQUIRED) From d2983f8e1352a079477bb8fcfd0aae79606a3cb1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?F=C3=B6ldi=20Tam=C3=A1s?= Date: Fri, 27 Sep 2024 15:18:06 +0200 Subject: [PATCH 16/25] style: fix documentation formating MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- image_transport_py/README.md | 11 ++++------- .../src/image_transport_py/pybind_image_transport.cpp | 3 +-- 2 files changed, 5 insertions(+), 9 deletions(-) diff --git a/image_transport_py/README.md b/image_transport_py/README.md index 68158550..536547a8 100644 --- a/image_transport_py/README.md +++ b/image_transport_py/README.md @@ -1,9 +1,9 @@ -# image_transport_py: Python Bindings for ROS2 Image Transport +# 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 ROS2 topics. +The package allows developers to handle image topics more efficiently and with less overhead than using standard ROS 2 topics. ## Usage @@ -47,7 +47,6 @@ class ImagePublisher(Node): `advertise_camera` can publish `CameraInfo` along with `Image` message. - ### Subscribing to Images To subscribe to images, use `ImageTransport` to create a subscription to the image topic. @@ -69,7 +68,7 @@ class ImageSubscriber(Node): def __init__(self): super().__init__('image_subscriber') self.image_transport = ImageTransport("imagetransport_sub", image_transport="raw") - self.subscription = self.image_transport.subscribe('camera/image', self.image_callback, 10) + self.subscription = self.image_transport.subscribe('camera/image', 10, self.image_callback) ``` 3. Handle Incoming Images: @@ -80,13 +79,11 @@ class ImageSubscriber(Node): `subscribe_camera` will add `CameraInfo` along with `Image` message for the callback. - ### Transport Selection By default, `image_transport` uses the `raw` transport. You can specify a different transport by passing `image_transport` parameter to `ImageTransport`. Alternatively, you can use your own ROS2 parameter file for the imagetransport node via `launch_params_filepath` parameter. - ## Classes ### Publisher @@ -141,7 +138,7 @@ An object for image transport operations. - `__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. + 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 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 index 9913b666..9311aedf 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -187,11 +187,10 @@ PYBIND11_MODULE(_image_transport, m) "shutdown", &image_transport::Subscriber::shutdown, "Unsubscribe the callback associated with this Subscriber."); - pybind11::class_>( m, - "CameraSubscriber") + "Camera subscriber constructor") .def(pybind11::init()) .def( "get_topic", From 6b615d2dd94fa773924b18cc9f1c81599bb8b120 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 1 Oct 2024 17:12:23 +0200 Subject: [PATCH 17/25] fix: CameraSubscriber class name --- .../src/image_transport_py/pybind_image_transport.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) 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 index 9311aedf..0c0b4cd5 100644 --- a/image_transport_py/src/image_transport_py/pybind_image_transport.cpp +++ b/image_transport_py/src/image_transport_py/pybind_image_transport.cpp @@ -190,7 +190,7 @@ PYBIND11_MODULE(_image_transport, m) pybind11::class_>( m, - "Camera subscriber constructor") + "CameraSubscriber") .def(pybind11::init()) .def( "get_topic", From 0f0f3c7567c4b36ea4895e0bbeeb6735ac981cc5 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Wed, 2 Oct 2024 09:52:45 +0200 Subject: [PATCH 18/25] build: move pybind11 to build only dep --- image_transport_py/package.xml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml index 0b31598e..880614ee 100644 --- a/image_transport_py/package.xml +++ b/image_transport_py/package.xml @@ -19,8 +19,9 @@ ament_cmake_python python_cmake_module + pybind11_vendor + image_transport - pybind11_vendor rclcpp sensor_msgs From 9246ea698e6e9669255444e6fccb559d0b5bd8af Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Fri, 4 Oct 2024 18:22:56 +0200 Subject: [PATCH 19/25] chore: implement review suggestions --- image_transport_py/CMakeLists.txt | 26 +++++++---- image_transport_py/README.md | 77 +------------------------------ image_transport_py/package.xml | 1 - 3 files changed, 17 insertions(+), 87 deletions(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index f553837c..4f4957ae 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.5) +cmake_minimum_required(VERSION 3.20) project(image_transport_py) # Default to C99 @@ -16,15 +16,6 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") add_compile_options(-Wall -Wextra -Wpedantic) endif() -# Figure out Python3 debug/release before anything else can find_package it -if(WIN32 AND CMAKE_BUILD_TYPE STREQUAL "Debug") - find_package(python_cmake_module REQUIRED) - find_package(PythonExtra REQUIRED) - - # Force FindPython3 to use the debug interpreter where ROS 2 expects it - set(Python3_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}") -endif() - find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_ros REQUIRED) @@ -32,6 +23,21 @@ 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) diff --git a/image_transport_py/README.md b/image_transport_py/README.md index 536547a8..97c8259e 100644 --- a/image_transport_py/README.md +++ b/image_transport_py/README.md @@ -7,82 +7,7 @@ The package allows developers to handle image topics more efficiently and with l ## Usage -### Publishing Images - -To publish images using `image_transport_py`, you create an `ImageTransport` object and use it to advertise an image topic. The first parameter for `ImageTransport` is the image transport -node's name which needs to be unique in the namespace. - -Steps: - -1. Import Necessary Modules: - -```python -import rclpy -from rclpy.node import Node -from sensor_msgs.msg import Image -from image_transport_py import ImageTransport -``` - -2. Initialize the Node and ImageTransport: - -```python -class ImagePublisher(Node): - def __init__(self): - super().__init__('image_publisher') - self.image_transport = ImageTransport("imagetransport_pub", image_transport="raw") - self.publisher = self.image_transport.advertise('camera/image', 10) - - # read images at 10Hz frequency - self.timer = self.create_timer(0.1, self.publish_image) -``` - -3. Publish Images in the Callback: -```python - def publish_image(self): - image_msg = .. # Read image from your devices - - image_msg.header.stamp = self.get_clock().now().to_msg() - self.publisher.publish(image_msg) -``` - -`advertise_camera` can publish `CameraInfo` along with `Image` message. - -### Subscribing to Images - -To subscribe to images, use `ImageTransport` to create a subscription to the image topic. - -Steps: - -1. Import Necessary Modules: - -```python -import rclpy -from rclpy.node import Node -from sensor_msgs.msg import Image -from image_transport_py import ImageTransport -``` - -2. Initialize the Node and ImageTransport: -```python -class ImageSubscriber(Node): - def __init__(self): - super().__init__('image_subscriber') - self.image_transport = ImageTransport("imagetransport_sub", image_transport="raw") - self.subscription = self.image_transport.subscribe('camera/image', 10, self.image_callback) -``` - -3. Handle Incoming Images: -```python - def image_callback(self, msg): - # do something with msg (= sensor_msgs.msg.Image type) -``` - -`subscribe_camera` will add `CameraInfo` along with `Image` message for the callback. - -### Transport Selection - -By default, `image_transport` uses the `raw` transport. You can specify a different transport by passing `image_transport` parameter to `ImageTransport`. Alternatively, -you can use your own ROS2 parameter file for the imagetransport node via `launch_params_filepath` parameter. +The detailed tutorial on `image_transport` and `image_transport_py` can be found at: https://github.com/ros-perception/image_transport_tutorials. ## Classes diff --git a/image_transport_py/package.xml b/image_transport_py/package.xml index 880614ee..bb428ef7 100644 --- a/image_transport_py/package.xml +++ b/image_transport_py/package.xml @@ -17,7 +17,6 @@ ament_cmake_ros ament_cmake_python - python_cmake_module pybind11_vendor From e6428aeb2f78e2c33812b918060fea0c1f38e430 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 8 Oct 2024 11:19:17 +0200 Subject: [PATCH 20/25] build: add <2.9 pybind11 compatibility --- image_transport_py/include/image_transport_py/cast_image.hpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index 28d1a04c..be9a4803 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -29,6 +29,10 @@ #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__") && From e6e71f0fc042b446e43bba8c98b8a3b88a0251c9 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 8 Oct 2024 11:40:28 +0200 Subject: [PATCH 21/25] build: add <2.9 pybind11 compatibility --- image_transport_py/include/image_transport_py/cast_image.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index be9a4803..2ac43215 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -29,7 +29,7 @@ #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) +#if PYBIND11_VERSION_MAJOR > 2 || (PYBIND11_VERSION_MAJOR == 2 && PYBIND11_VERSION_MINOR < 9) #define const_name _ #endif From 2424f26ebe728052bdf1e2f3b7a6571618391ad1 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 8 Oct 2024 11:42:33 +0200 Subject: [PATCH 22/25] build: add <2.9 pybind11 compatibility --- image_transport_py/include/image_transport_py/cast_image.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_transport_py/include/image_transport_py/cast_image.hpp b/image_transport_py/include/image_transport_py/cast_image.hpp index 2ac43215..6263c5af 100644 --- a/image_transport_py/include/image_transport_py/cast_image.hpp +++ b/image_transport_py/include/image_transport_py/cast_image.hpp @@ -29,7 +29,7 @@ #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) +#if PYBIND11_VERSION_MAJOR < 2 || (PYBIND11_VERSION_MAJOR == 2 && PYBIND11_VERSION_MINOR < 9) #define const_name _ #endif From 817ed6cbeceee829b25d817bfe87114a42772d0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?F=C3=B6ldi=20Tam=C3=A1s?= Date: Tue, 8 Oct 2024 15:07:56 +0200 Subject: [PATCH 23/25] build: ament_cppcheck(LANGUAGE "c++") after ament_lint_auto_find_test_dependencies MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Alejandro Hernández Cordero --- image_transport_py/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index 4f4957ae..0ae0a290 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -74,7 +74,7 @@ if(BUILD_TESTING) ament_cmake_cppcheck ) ament_lint_auto_find_test_dependencies() - +ament_cppcheck(LANGUAGE c++) ament_cppcheck(LANGUAGE "c++") endif() From 7c1ea65f1e717ffe77d79171e169fee392bf3cc7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?F=C3=B6ldi=20Tam=C3=A1s?= Date: Tue, 8 Oct 2024 15:09:03 +0200 Subject: [PATCH 24/25] build: cpp check after test dependencies --- image_transport_py/CMakeLists.txt | 1 - 1 file changed, 1 deletion(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index 0ae0a290..9a4ac676 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -74,7 +74,6 @@ if(BUILD_TESTING) ament_cmake_cppcheck ) ament_lint_auto_find_test_dependencies() -ament_cppcheck(LANGUAGE c++) ament_cppcheck(LANGUAGE "c++") endif() From bf4eae94f88f23e2f6638c79846e392c460c73b5 Mon Sep 17 00:00:00 2001 From: Tamas Foldi Date: Tue, 8 Oct 2024 15:30:40 +0200 Subject: [PATCH 25/25] build: skip cppcheck on Windows --- image_transport_py/CMakeLists.txt | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/image_transport_py/CMakeLists.txt b/image_transport_py/CMakeLists.txt index 9a4ac676..21ff9d31 100644 --- a/image_transport_py/CMakeLists.txt +++ b/image_transport_py/CMakeLists.txt @@ -74,7 +74,12 @@ if(BUILD_TESTING) ament_cmake_cppcheck ) ament_lint_auto_find_test_dependencies() - ament_cppcheck(LANGUAGE "c++") + + if(NOT WIN32) + ament_cppcheck(LANGUAGE "c++") + else() + message(STATUS "Skipping ament_cppcheck on Windows") + endif() endif() ament_package()