Skip to content
Merged
Show file tree
Hide file tree
Changes from 11 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
73 changes: 52 additions & 21 deletions image_transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@ find_package(message_filters REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(rclcpp_lifecycle REQUIRED)
find_package(sensor_msgs REQUIRED)

# Build image_transport library
Expand Down Expand Up @@ -119,39 +120,69 @@ if(BUILD_TESTING)

find_package(ament_cmake_gtest)

ament_add_gtest(${PROJECT_NAME}-camera_common test/test_camera_common.cpp)
if(TARGET ${PROJECT_NAME}-camera_common)
target_link_libraries(${PROJECT_NAME}-camera_common ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-camera_common test/test_camera_common.cpp)
if(TARGET test_${PROJECT_NAME}-camera_common)
target_link_libraries(test_${PROJECT_NAME}-camera_common ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-publisher test/test_publisher.cpp)
if(TARGET ${PROJECT_NAME}-publisher)
target_link_libraries(${PROJECT_NAME}-publisher ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-publisher test/test_publisher.cpp)
if(TARGET test_${PROJECT_NAME}-publisher)
target_link_libraries(test_${PROJECT_NAME}-publisher ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-subscriber test/test_subscriber.cpp)
if(TARGET ${PROJECT_NAME}-subscriber)
target_link_libraries(${PROJECT_NAME}-subscriber ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-publisher_lifecycle test/test_publisher_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-publisher_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-publisher_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()

ament_add_gtest(${PROJECT_NAME}-message_passing test/test_message_passing.cpp)
if(TARGET ${PROJECT_NAME}-message_passing)
target_link_libraries(${PROJECT_NAME}-message_passing ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-subscriber test/test_subscriber.cpp)
if(TARGET test_${PROJECT_NAME}-subscriber)
target_link_libraries(test_${PROJECT_NAME}-subscriber ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-remapping test/test_remapping.cpp)
if(TARGET ${PROJECT_NAME}-remapping)
target_link_libraries(${PROJECT_NAME}-remapping ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-subscriber_lifecycle test/test_subscriber_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-subscriber_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-subscriber_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()

ament_add_gtest(${PROJECT_NAME}-qos_override test/test_qos_override.cpp)
if(TARGET ${PROJECT_NAME}-qos_override)
target_link_libraries(${PROJECT_NAME}-qos_override ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-message_passing test/test_message_passing.cpp)
if(TARGET test_${PROJECT_NAME}-message_passing)
target_link_libraries(test_${PROJECT_NAME}-message_passing ${PROJECT_NAME})
endif()

ament_add_gtest(${PROJECT_NAME}-single_subscriber_publisher test/test_single_subscriber_publisher.cpp)
if(TARGET ${PROJECT_NAME}-single_subscriber_publisher)
target_link_libraries(${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME})
ament_add_gtest(test_${PROJECT_NAME}-message_passing_lifecycle test/test_message_passing_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-message_passing_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-message_passing_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()

ament_add_gtest(test_${PROJECT_NAME}-remapping test/test_remapping.cpp)
if(TARGET test_${PROJECT_NAME}-remapping)
target_link_libraries(test_${PROJECT_NAME}-remapping ${PROJECT_NAME})
endif()

ament_add_gtest(test_${PROJECT_NAME}-remapping_lifecycle test/test_remapping_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-remapping_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-remapping_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()

ament_add_gtest(test_${PROJECT_NAME}-qos_override test/test_qos_override.cpp)
if(TARGET test_${PROJECT_NAME}-qos_override)
target_link_libraries(test_${PROJECT_NAME}-qos_override ${PROJECT_NAME})
endif()

ament_add_gtest(test_${PROJECT_NAME}-qos_override_lifecycle test/test_qos_override_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-qos_override_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-qos_override_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()

ament_add_gtest(test_${PROJECT_NAME}-single_subscriber_publisher test/test_single_subscriber_publisher.cpp)
if(TARGET test_${PROJECT_NAME}-single_subscriber_publisher)
target_link_libraries(test_${PROJECT_NAME}-single_subscriber_publisher ${PROJECT_NAME})
endif()

ament_add_gtest(test_${PROJECT_NAME}-single_subscriber_publisher_lifecycle test/test_single_subscriber_publisher_lifecycle.cpp)
if(TARGET test_${PROJECT_NAME}-single_subscriber_publisher_lifecycle)
target_link_libraries(test_${PROJECT_NAME}-single_subscriber_publisher_lifecycle ${PROJECT_NAME} rclcpp_lifecycle::rclcpp_lifecycle)
endif()
endif()

Expand Down
9 changes: 9 additions & 0 deletions image_transport/include/image_transport/camera_publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "sensor_msgs/msg/image.hpp"
#include "sensor_msgs/msg/camera_info.hpp"

#include "image_transport/node_interfaces.hpp"
#include "image_transport/single_subscriber_publisher.hpp"
#include "image_transport/visibility_control.hpp"

Expand Down Expand Up @@ -68,12 +69,20 @@ class CameraPublisher
CameraPublisher() = default;

IMAGE_TRANSPORT_PUBLIC
[[deprecated("Use CameraPublisher(RequiredInterfaces node_interfaces, ...) instead.")]]
CameraPublisher(
rclcpp::Node * node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
CameraPublisher(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions = rclcpp::PublisherOptions());

/*!
* \brief Returns the number of subscribers that are currently connected to
* this CameraPublisher.
Expand Down
10 changes: 10 additions & 0 deletions image_transport/include/image_transport/camera_subscriber.hpp

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Has compilation error:

/ros2_ws/src/image_common/image_transport/src/camera_subscriber.cpp: In constructor ‘image_transport::CameraSubscriber::CameraSubscriber(image_transport::RequiredInterfaces, const std::string&, const Callback&, const std::string&, rmw_qos_profile_t)’:
/ros2_ws/src/image_common/image_transport/src/camera_subscriber.cpp:162:29: error: no matching function for call to ‘message_filters::Subscriber<sensor_msgs::msg::CameraInfo_<std::allocator<void> > >::subscribe(image_transport::RequiredInterfaces&, std::string&, rmw_qos_profile_t&)’
  162 |   impl_->info_sub_.subscribe(required_test_interfaces, info_topic, custom_qos);
      |   ~~~~~~~~~~~~~~~~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In file included from /ros2_ws/src/image_common/image_transport/src/camera_subscriber.cpp:34:
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:365:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodePtr, const std::string&, const rclcpp::QoS&) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; NodePtr = std::shared_ptr<rclcpp::Node>; std::string = std::__cxx11::basic_string<char>]’
  365 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:366:13: note:   no known conversion for argument 1 from ‘image_transport::RequiredInterfaces’ {aka ‘rclcpp::node_interfaces::NodeInterfaces<rclcpp::node_interfaces::NodeBaseInterface, rclcpp::node_interfaces::NodeParametersInterface, rclcpp::node_interfaces::NodeLoggingInterface, rclcpp::node_interfaces::NodeTimersInterface, rclcpp::node_interfaces::NodeTopicsInterface>’} to ‘message_filters::Subscriber<sensor_msgs::msg::CameraInfo_<std::allocator<void> > >::NodePtr’ {aka ‘std::shared_ptr<rclcpp::Node>’}
  366 |     NodePtr node, const std::string & topic,
      |     ~~~~~~~~^~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:381:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodeType*, const std::string&, const rclcpp::QoS&) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; std::string = std::__cxx11::basic_string<char>]’
  381 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:382:16: note:   no known conversion for argument 1 from ‘image_transport::RequiredInterfaces’ {aka ‘rclcpp::node_interfaces::NodeInterfaces<rclcpp::node_interfaces::NodeBaseInterface, rclcpp::node_interfaces::NodeParametersInterface, rclcpp::node_interfaces::NodeLoggingInterface, rclcpp::node_interfaces::NodeTimersInterface, rclcpp::node_interfaces::NodeTopicsInterface>’} to ‘rclcpp::Node*’
  382 |     NodeType * node, const std::string & topic,
      |     ~~~~~~~~~~~^~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:398:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodePtr, const std::string&, const rclcpp::QoS&, rclcpp::SubscriptionOptions) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; NodePtr = std::shared_ptr<rclcpp::Node>; std::string = std::__cxx11::basic_string<char>; rclcpp::SubscriptionOptions = rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >]’
  398 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:398:8: note:   candidate expects 4 arguments, 3 provided
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:419:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodeType*, const std::string&, const rclcpp::QoS&, rclcpp::SubscriptionOptions) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; std::string = std::__cxx11::basic_string<char>; rclcpp::SubscriptionOptions = rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >]’
  419 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:419:8: note:   candidate expects 4 arguments, 3 provided
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:451:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodePtr, const std::string&, rmw_qos_profile_t) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; NodePtr = std::shared_ptr<rclcpp::Node>; std::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_s]’
  451 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:452:13: note:   no known conversion for argument 1 from ‘image_transport::RequiredInterfaces’ {aka ‘rclcpp::node_interfaces::NodeInterfaces<rclcpp::node_interfaces::NodeBaseInterface, rclcpp::node_interfaces::NodeParametersInterface, rclcpp::node_interfaces::NodeLoggingInterface, rclcpp::node_interfaces::NodeTimersInterface, rclcpp::node_interfaces::NodeTopicsInterface>’} to ‘message_filters::Subscriber<sensor_msgs::msg::CameraInfo_<std::allocator<void> > >::NodePtr’ {aka ‘std::shared_ptr<rclcpp::Node>’}
  452 |     NodePtr node, const std::string & topic,
      |     ~~~~~~~~^~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:470:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodeType*, const std::string&, rmw_qos_profile_t) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; std::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_s]’
  470 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:471:16: note:   no known conversion for argument 1 from ‘image_transport::RequiredInterfaces’ {aka ‘rclcpp::node_interfaces::NodeInterfaces<rclcpp::node_interfaces::NodeBaseInterface, rclcpp::node_interfaces::NodeParametersInterface, rclcpp::node_interfaces::NodeLoggingInterface, rclcpp::node_interfaces::NodeTimersInterface, rclcpp::node_interfaces::NodeTopicsInterface>’} to ‘rclcpp::Node*’
  471 |     NodeType * node, const std::string & topic,
      |     ~~~~~~~~~~~^~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:490:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodePtr, const std::string&, rmw_qos_profile_t, rclcpp::SubscriptionOptions) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; NodePtr = std::shared_ptr<rclcpp::Node>; std::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_s; rclcpp::SubscriptionOptions = rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >]’
  490 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:490:8: note:   candidate expects 4 arguments, 3 provided
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:512:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe(NodeType*, const std::string&, rmw_qos_profile_t, rclcpp::SubscriptionOptions) [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node; std::string = std::__cxx11::basic_string<char>; rmw_qos_profile_t = rmw_qos_profile_s; rclcpp::SubscriptionOptions = rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> >]’
  512 |   void subscribe(
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:512:8: note:   candidate expects 4 arguments, 3 provided
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:538:8: note: candidate: ‘void message_filters::Subscriber<M, NodeType>::subscribe() [with M = sensor_msgs::msg::CameraInfo_<std::allocator<void> >; NodeType = rclcpp::Node]’
  538 |   void subscribe() override
      |        ^~~~~~~~~
/opt/ros/rolling/include/message_filters/message_filters/subscriber.hpp:538:8: note:   candidate expects 0 arguments, 3 provided
gmake[2]: *** [CMakeFiles/image_transport.dir/build.make:146: CMakeFiles/image_transport.dir/src/camera_subscriber.cpp.o] Error 1
gmake[1]: *** [CMakeFiles/Makefile2:189: CMakeFiles/image_transport.dir/all] Error 2
gmake: *** [Makefile:146: all] Error 2
---
Failed   <<< image_transport [6.97s, exited with code 2]

Copy link

@authaldo authaldo Apr 11, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I had no build problems on my machine, could it be that you are using an older version of the message filter package? The PR adapting the interface to rclcpp::NodeInterfaces (this commit) has just been merged a few days ago, thus, you'll likely need the current rolling branch for compatibility.

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You are right. It is good when I build message_filters from source since the binary is not released just yet.

Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@
#include "sensor_msgs/msg/camera_info.hpp"
#include "sensor_msgs/msg/image.hpp"

#include "image_transport/node_interfaces.hpp"
#include "image_transport/visibility_control.hpp"

namespace image_transport
Expand Down Expand Up @@ -70,13 +71,22 @@ class CameraSubscriber
CameraSubscriber() = default;

IMAGE_TRANSPORT_PUBLIC
[[deprecated("Use CameraSubscriber(RequiredInterfaces node_interfaces, ...) instead.")]]
CameraSubscriber(
rclcpp::Node * node,
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
rmw_qos_profile_t = rmw_qos_profile_default);

IMAGE_TRANSPORT_PUBLIC
CameraSubscriber(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
const Callback & callback,
const std::string & transport,
rmw_qos_profile_t = rmw_qos_profile_default);

/**
* \brief Get the base topic (on which the raw image is published).
*/
Expand Down
49 changes: 45 additions & 4 deletions image_transport/include/image_transport/image_transport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@

#include "image_transport/camera_publisher.hpp"
#include "image_transport/camera_subscriber.hpp"
#include "image_transport/node_interfaces.hpp"
#include "image_transport/publisher.hpp"
#include "image_transport/subscriber.hpp"
#include "image_transport/transport_hints.hpp"
Expand All @@ -46,16 +47,20 @@
namespace image_transport
{

/*!
* \brief Advertise an image topic, free function version.
*/
IMAGE_TRANSPORT_PUBLIC
Publisher create_publisher(
rclcpp::Node * node,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
Publisher create_publisher(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());

/**
* \brief Subscribe to an image topic, free function version.
*/
Expand All @@ -68,6 +73,18 @@ Subscriber create_subscription(
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

/**
* \brief Subscribe to an image topic, free function version.
*/
IMAGE_TRANSPORT_PUBLIC
Subscriber create_subscription(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
const Subscriber::Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

/*!
* \brief Advertise a camera, free function version.
*/
Expand All @@ -78,6 +95,16 @@ CameraPublisher create_camera_publisher(
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions pub_options = rclcpp::PublisherOptions());

/*!
* \brief Advertise a camera, free function version.
*/
IMAGE_TRANSPORT_PUBLIC
CameraPublisher create_camera_publisher(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default,
rclcpp::PublisherOptions pub_options = rclcpp::PublisherOptions());

/*!
* \brief Subscribe to a camera, free function version.
*/
Expand All @@ -89,6 +116,17 @@ CameraSubscriber create_camera_subscription(
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

/*!
* \brief Subscribe to a camera, free function version.
*/
IMAGE_TRANSPORT_PUBLIC
CameraSubscriber create_camera_subscription(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
const CameraSubscriber::Callback & callback,
const std::string & transport,
rmw_qos_profile_t custom_qos = rmw_qos_profile_default);

IMAGE_TRANSPORT_PUBLIC
std::vector<std::string> getDeclaredTransports();

Expand All @@ -112,6 +150,9 @@ class ImageTransport
IMAGE_TRANSPORT_PUBLIC
explicit ImageTransport(rclcpp::Node::SharedPtr node);

IMAGE_TRANSPORT_PUBLIC
explicit ImageTransport(RequiredInterfaces node_interfaces);

IMAGE_TRANSPORT_PUBLIC
ImageTransport(const ImageTransport & other);

Expand Down Expand Up @@ -372,7 +413,7 @@ class ImageTransport

struct ImageTransport::Impl
{
rclcpp::Node::SharedPtr node_;
RequiredInterfaces required_interfaces_;
Copy link

@authaldo authaldo Apr 13, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Out of curiosity: Why did you remove the old pointer in your second iteration?

In my view keeping this pointer was one key benefit of your suggested implementation, as it allowed to keep the image_transport_plugins unchanged. I would really appreciate a plugin interface centered around the rclcpp::NodeInterfaces as the long run solution, however, I cannot quantify the additional overhead caused by the synchronization need for both repositories. As a maintainer you have likely more insights regarding this topic.
Depending on how large that overhead is, I would see your first iteration which kept the pointer as an acceptable solution since backwards compatibility is included. The full switch to using only rclcpp::NodeInterfaces in the plugin interfaces may then still be carried later on (potentially including multiple steps / deprecation cycles for backwards compatibility?)

EDIT:

Did the first version which kept the old pointer even work with the unmodified rolling state of the plugins for you? Even though it compiles I would expect runtime problems, since the plugins (e.g. for compressed image transport) explicitly override advertiseImpl(rclcpp::Node * node, ...).

};

} // namespace image_transport
Expand Down
56 changes: 56 additions & 0 deletions image_transport/include/image_transport/node_interfaces.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
// Copyright (c) 2025, Open Source Robotics Foundation, Inc.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the Willow Garage nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef IMAGE_TRANSPORT__NODE_INTERFACES_HPP_
#define IMAGE_TRANSPORT__NODE_INTERFACES_HPP_

#include <rclcpp/node_interfaces/node_interfaces.hpp>

#include <rclcpp/node_interfaces/node_base_interface.hpp>
#include <rclcpp/node_interfaces/node_logging_interface.hpp>
#include <rclcpp/node_interfaces/node_parameters_interface.hpp>
#include <rclcpp/node_interfaces/node_timers_interface.hpp>
#include <rclcpp/node_interfaces/node_topics_interface.hpp>

namespace image_transport
{
using NodeBaseInterface = rclcpp::node_interfaces::NodeBaseInterface;
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface;
using NodeLoggingInterface = rclcpp::node_interfaces::NodeLoggingInterface;
using NodeTimersInterface = rclcpp::node_interfaces::NodeTimersInterface;
using NodeTopicsInterface = rclcpp::node_interfaces::NodeTopicsInterface;

using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<
NodeBaseInterface,
NodeParametersInterface,
NodeLoggingInterface,
NodeTimersInterface,
NodeTopicsInterface>;
} // namespace image_transport

#endif // IMAGE_TRANSPORT__NODE_INTERFACES_HPP_
12 changes: 11 additions & 1 deletion image_transport/include/image_transport/publisher.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@

#include "image_transport/exception.hpp"
#include "image_transport/loader_fwds.hpp"
#include "image_transport/node_interfaces.hpp"
#include "image_transport/single_subscriber_publisher.hpp"
#include "image_transport/visibility_control.hpp"

Expand Down Expand Up @@ -69,8 +70,17 @@ class Publisher
Publisher() = default;

IMAGE_TRANSPORT_PUBLIC
[[deprecated("Use Publisher(RequiredInterfaces node_interfaces, ...) instead.")]]
Publisher(
rclcpp::Node * nh,
rclcpp::Node * node,
const std::string & base_topic,
PubLoaderPtr loader,
rmw_qos_profile_t custom_qos,
rclcpp::PublisherOptions options = rclcpp::PublisherOptions());

IMAGE_TRANSPORT_PUBLIC
Publisher(
RequiredInterfaces node_interfaces,
const std::string & base_topic,
PubLoaderPtr loader,
rmw_qos_profile_t custom_qos,
Expand Down
Loading