From 89705ccd8d52fdbf165c560dde9b0c8280264ad2 Mon Sep 17 00:00:00 2001 From: Gonzalo de Pedro Date: Mon, 20 Dec 2021 15:28:42 -0500 Subject: [PATCH] Add required conversions to any subscription callback (#8) * Add required conversions to any subscription callback * Style fixes for the linters. (#9) Signed-off-by: Chris Lalancette Signed-off-by: Gonzalo de Pedro --- .../rclcpp/any_subscription_callback.hpp | 137 ++++++++++++------ .../experimental/intra_process_manager.hpp | 74 +++++----- .../ros_message_intra_process_buffer.hpp | 1 - .../subscription_intra_process.hpp | 18 ++- .../subscription_intra_process_buffer.hpp | 19 ++- rclcpp/include/rclcpp/publisher.hpp | 8 +- rclcpp/include/rclcpp/subscription.hpp | 1 - ...ption_publisher_with_same_type_adapter.cpp | 3 - 8 files changed, 156 insertions(+), 105 deletions(-) diff --git a/rclcpp/include/rclcpp/any_subscription_callback.hpp b/rclcpp/include/rclcpp/any_subscription_callback.hpp index 061ded9c4b..191abd2228 100644 --- a/rclcpp/include/rclcpp/any_subscription_callback.hpp +++ b/rclcpp/include/rclcpp/any_subscription_callback.hpp @@ -16,7 +16,6 @@ #define RCLCPP__ANY_SUBSCRIPTION_CALLBACK_HPP_ #include -#include //TODO remove when removed std::cout s #include #include #include @@ -477,6 +476,21 @@ class AnySubscriptionCallback } } + std::unique_ptr + convert_custom_type_to_ros_message_unique_ptr(const SubscribedType & msg) + { + if constexpr (rclcpp::TypeAdapter::is_specialized::value) { + auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator_, 1); + ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator_, ptr); + rclcpp::TypeAdapter::convert_to_ros_message(msg, *ptr); + return std::unique_ptr(ptr, ros_message_type_deleter_); + } else { + throw std::runtime_error( + "convert_custom_type_to_ros_message_unique_ptr " + "unexpectedly called without TypeAdapter"); + } + } + // Dispatch when input is a ros message and the output could be anything. void dispatch( @@ -687,21 +701,21 @@ class AnySubscriptionCallback std::is_same_v )) { - // callback(message); //TODO Convert + callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message)); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| std::is_same_v )) { - // callback(message, message_info); //TODO Convert + callback(create_custom_unique_ptr_from_custom_shared_ptr_message(message), message_info); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| std::is_same_v )) { - // callback(message); //TODO Convert + callback(message); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| @@ -711,30 +725,56 @@ class AnySubscriptionCallback callback(message, message_info); } // conditions for ros message type - else if constexpr (std::is_same_v) { // NOLINT - //callback(*message); //TODO convert to rosMessage - } else if constexpr (std::is_same_v) { - //callback(*message, message_info); //TODO convert to rosMessage + else if constexpr (std::is_same_v) { // NOLINT[readability/braces] + if constexpr (is_ta) { + auto local = convert_custom_type_to_ros_message_unique_ptr(*message); + callback(*local); + } else { + callback(*message); + } + } else if constexpr (std::is_same_v) { // NOLINT[readability/braces] + if constexpr (is_ta) { + auto local = convert_custom_type_to_ros_message_unique_ptr(*message); + callback(*local, message_info); + } else { + callback(*message, message_info); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message)); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message)); + } else { + callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message)); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info); + } else { + callback(create_ros_unique_ptr_from_ros_shared_ptr_message(message), message_info); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(message); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message)); + } else { + callback(message); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(message, message_info); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info); + } else { + callback(message, message_info); + } } // condition to catch SerializedMessage types else if constexpr ( // NOLINT[readability/braces] @@ -761,14 +801,11 @@ class AnySubscriptionCallback TRACEPOINT(callback_end, static_cast(this)); } - void + void dispatch_intra_process( std::unique_ptr message, const rclcpp::MessageInfo & message_info) { - - std::cout << "ASC dispatch_intra_process" << std::endl; - TRACEPOINT(callback_start, static_cast(this), true); // Check if the variant is "unset", throw if it is. if (callback_variant_.index() == 0) { @@ -783,80 +820,90 @@ class AnySubscriptionCallback using T = std::decay_t; static constexpr bool is_ta = rclcpp::TypeAdapter::is_specialized::value; - std::cout << "IS TA: " << is_ta << std::endl; - // conditions for custom type if constexpr (is_ta && std::is_same_v) { - //We won't need to convert - //auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message); - std::cout << "ASC crcb" << std::endl; callback(*message); } else if constexpr (is_ta && std::is_same_v) { // NOLINT - //auto local_message = convert_ros_message_to_custom_type_unique_ptr(*message); - std::cout << "ASC crcb+info" << std::endl; callback(*message, message_info); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| - std::is_same_v - )) + std::is_same_v)) { - std::cout << "ASC unorshcb" << std::endl; - //callback(convert_ros_message_to_custom_type_unique_ptr(*message)); - callback(std::move(message)); //TODO convert + callback(std::move(message)); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| std::is_same_v )) { - std::cout << "ASC unorshcb+info" << std::endl; - //callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info); - callback(std::move(message), message_info); //TODO convert + callback(std::move(message), message_info); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| std::is_same_v )) { - std::cout << "ASC shconsrref" << std::endl; - //callback(convert_ros_message_to_custom_type_unique_ptr(*message)); - // callback(message); //TODO Convert + callback(std::move(message)); } else if constexpr ( // NOLINT[readability/braces] is_ta && ( std::is_same_v|| std::is_same_v )) { - std::cout << "ASC shconsrref+info" << std::endl; - //callback(convert_ros_message_to_custom_type_unique_ptr(*message), message_info); - //callback(message, message_info); //TODO Convert + callback(std::move(message), message_info); } // conditions for ros message type - else if constexpr (std::is_same_v) { // NOLINT - //callback(*message); - } else if constexpr (std::is_same_v) { - // callback(*message, message_info); + else if constexpr (std::is_same_v) { // NOLINT[readability/braces] + if constexpr (is_ta) { + auto local = convert_custom_type_to_ros_message_unique_ptr(*message); + callback(*local); + } else { + callback(*message); + } + } else if constexpr (std::is_same_v) { // NOLINT[readability/braces] + if constexpr (is_ta) { + auto local = convert_custom_type_to_ros_message_unique_ptr(*message); + callback(*local, message_info); + } else { + callback(*message, message_info); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(std::move(message)); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message)); + } else { + callback(std::move(message)); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(std::move(message), message_info); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info); + } else { + callback(std::move(message), message_info); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(std::move(message)); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message)); + } else { + callback(std::move(message)); + } } else if constexpr ( // NOLINT[readability/braces] std::is_same_v|| std::is_same_v) { - // callback(std::move(message), message_info); + if constexpr (is_ta) { + callback(convert_custom_type_to_ros_message_unique_ptr(*message), message_info); + } else { + callback(std::move(message), message_info); + } } // condition to catch SerializedMessage types else if constexpr ( // NOLINT[readability/braces] diff --git a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp index c471e949ce..b6dc0684b0 100644 --- a/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp +++ b/rclcpp/include/rclcpp/experimental/intra_process_manager.hpp @@ -210,7 +210,7 @@ class IntraProcessManager std::shared_ptr msg = std::move(message); this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); @@ -231,8 +231,8 @@ class IntraProcessManager sub_ids.take_ownership_subscriptions.end()); this->template add_owned_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, + PublishedTypeAllocator>( std::move(message), concatenated_vector, published_type_allocator, @@ -241,16 +241,18 @@ class IntraProcessManager } else { // Construct a new shared pointer from the message // for the buffers that do not require ownership - auto shared_msg = std::allocate_shared(published_type_allocator, *message); + auto shared_msg = std::allocate_shared( + published_type_allocator, + *message); this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( shared_msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); - this->template add_owned_msg_to_buffers( + this->template add_owned_msg_to_buffers( std::move(message), sub_ids.take_ownership_subscriptions, published_type_allocator, @@ -301,7 +303,7 @@ class IntraProcessManager std::shared_ptr shared_msg = std::move(message); if (!sub_ids.take_shared_subscriptions.empty()) { this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( shared_msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); @@ -310,19 +312,21 @@ class IntraProcessManager } else { // Construct a new shared pointer from the message for the buffers that // do not require ownership and to return. - auto shared_msg = std::allocate_shared(published_type_allocator, *message); + auto shared_msg = std::allocate_shared( + published_type_allocator, + *message); if (!sub_ids.take_shared_subscriptions.empty()) { this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( shared_msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); } this->template add_owned_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, + PublishedTypeAllocator>( std::move(message), sub_ids.take_ownership_subscriptions, published_type_allocator, @@ -359,7 +363,9 @@ class IntraProcessManager { auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator, 1); ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator, ptr); - auto unique_ros_msg = std::unique_ptr(ptr, ros_message_type_deleter); + auto unique_ros_msg = std::unique_ptr( + ptr, + ros_message_type_deleter); rclcpp::TypeAdapter::convert_to_ros_message(*message, *unique_ros_msg); std::shared_lock lock(mutex_); @@ -379,7 +385,7 @@ class IntraProcessManager std::shared_ptr shared_msg = std::move(message); if (!sub_ids.take_shared_subscriptions.empty()) { this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( shared_msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); @@ -387,19 +393,21 @@ class IntraProcessManager } else { // Construct a new shared pointer from the message for the buffers that // do not require ownership and to return. - auto shared_msg = std::allocate_shared(published_type_allocator, *message); + auto shared_msg = std::allocate_shared( + published_type_allocator, + *message); if (!sub_ids.take_shared_subscriptions.empty()) { this->template add_shared_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator>( shared_msg, sub_ids.take_shared_subscriptions, ros_message_type_allocator); } this->template add_owned_msg_to_buffers( + Deleter, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, + PublishedTypeAllocator>( std::move(message), sub_ids.take_ownership_subscriptions, published_type_allocator, @@ -482,10 +490,9 @@ class IntraProcessManager auto subscription_base = subscription_it->second.lock(); if (subscription_base) { auto subscription = std::dynamic_pointer_cast< - rclcpp::experimental::SubscriptionIntraProcessBuffer - >(subscription_base); + rclcpp::experimental::SubscriptionIntraProcessBuffer>(subscription_base); if (nullptr == subscription) { - auto ros_message_subscription = std::dynamic_pointer_cast< rclcpp::experimental::ROSMessageIntraProcessBuffer >(subscription_base); @@ -493,7 +500,7 @@ class IntraProcessManager if (nullptr == ros_message_subscription) { throw std::runtime_error( "failed to dynamic cast SubscriptionIntraProcessBase to " - "SubscriptionIntraProcessBuffer, which " + "SubscriptionIntraProcessBuffer, which " "can happen when the publisher and subscription use different " "allocator types, which is not supported"); } else { @@ -506,13 +513,10 @@ class IntraProcessManager } else { ros_message_subscription->provide_intra_process_message(message); } - } } else { subscription->provide_intra_process_data(message); } - - } else { subscriptions_.erase(id); } @@ -538,7 +542,6 @@ class IntraProcessManager ROSMessageTypeAllocator & ros_message_type_allocator, ROSMessageTypeDeleter & ros_message_type_deleter) { - std::cout << "add owned msg to buffers" << std::endl; std::cout << "message has type : " << typeid(message).name() << std::endl; @@ -554,15 +557,13 @@ class IntraProcessManager auto subscription_base = subscription_it->second.lock(); std::cout << "Subscription Base?" << std::endl; if (subscription_base) { - std::cout << "Typed Subscription" << std::endl; auto subscription = std::dynamic_pointer_cast< - rclcpp::experimental::SubscriptionIntraProcessBuffer - >(subscription_base); + rclcpp::experimental::SubscriptionIntraProcessBuffer>(subscription_base); if (nullptr == subscription) { - - std::cout << "ROSMessage Subscription" << std::endl; + std::cout << "ROSMessage Subscription" << std::endl; auto ros_message_subscription = std::dynamic_pointer_cast< rclcpp::experimental::ROSMessageIntraProcessBuffer @@ -571,17 +572,18 @@ class IntraProcessManager if (nullptr == ros_message_subscription) { throw std::runtime_error( "failed to dynamic cast SubscriptionIntraProcessBase to " - "SubscriptionIntraProcessBuffer, which " + "SubscriptionIntraProcessBuffer, which " "can happen when the publisher and subscription use different " "allocator types, which is not supported"); } else { - std::cout << "ROSMessage TypeAdapted Subscription" << std::endl; if constexpr (rclcpp::TypeAdapter::is_specialized::value) { auto ptr = ROSMessageTypeAllocatorTraits::allocate(ros_message_type_allocator, 1); ROSMessageTypeAllocatorTraits::construct(ros_message_type_allocator, ptr); - auto ros_msg = std::unique_ptr(ptr, ros_message_type_deleter); + auto ros_msg = std::unique_ptr( + ptr, + ros_message_type_deleter); rclcpp::TypeAdapter::convert_to_ros_message(*message, *ros_msg); ros_message_subscription->provide_intra_process_message(std::move(ros_msg)); } else { @@ -600,7 +602,6 @@ class IntraProcessManager ros_message_subscription->provide_intra_process_message(std::move(copy_message)); } } - } } else { std::cout << "Typed Subscription" << std::endl; @@ -618,7 +619,6 @@ class IntraProcessManager subscription->provide_intra_process_data(std::move(copy_message)); } } - } else { std::cout << "Erasing subscription" << std::endl; subscriptions_.erase(subscription_it); diff --git a/rclcpp/include/rclcpp/experimental/ros_message_intra_process_buffer.hpp b/rclcpp/include/rclcpp/experimental/ros_message_intra_process_buffer.hpp index 30f9d08efd..3a3b1ed81b 100644 --- a/rclcpp/include/rclcpp/experimental/ros_message_intra_process_buffer.hpp +++ b/rclcpp/include/rclcpp/experimental/ros_message_intra_process_buffer.hpp @@ -61,7 +61,6 @@ class ROSMessageIntraProcessBuffer : public SubscriptionIntraProcessBase virtual void provide_intra_process_message(MessageUniquePtr message) = 0; - }; } // namespace experimental diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp index 13e8e56031..d02302a7c5 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process.hpp @@ -43,14 +43,14 @@ template< typename SubscribedType, typename SubscribedTypeAlloc = std::allocator, typename SubscribedTypeDeleter = std::default_delete - > +> class SubscriptionIntraProcess : public SubscriptionIntraProcessBuffer< - MessageT, - SubscribedType, - SubscribedTypeAlloc, - SubscribedTypeDeleter - > + MessageT, + SubscribedType, + SubscribedTypeAlloc, + SubscribedTypeDeleter + > { using SubscriptionIntraProcessBufferT = SubscriptionIntraProcessBuffer< MessageT, @@ -62,7 +62,8 @@ class SubscriptionIntraProcess public: RCLCPP_SMART_PTR_DEFINITIONS(SubscriptionIntraProcess) - using MessageAllocTraits = typename SubscriptionIntraProcessBufferT::SubscribedTypeAllocatorTraits; + using MessageAllocTraits = + typename SubscriptionIntraProcessBufferT::SubscribedTypeAllocatorTraits; using MessageAlloc = typename SubscriptionIntraProcessBufferT::SubscribedTypeAllocator; using ConstMessageSharedPtr = typename SubscriptionIntraProcessBufferT::ConstMessageSharedPtr; using MessageUniquePtr = typename SubscriptionIntraProcessBufferT::MessageUniquePtr; @@ -75,7 +76,8 @@ class SubscriptionIntraProcess const std::string & topic_name, const rclcpp::QoS & qos_profile, rclcpp::IntraProcessBufferType buffer_type) - : SubscriptionIntraProcessBuffer( + : SubscriptionIntraProcessBuffer( allocator, context, topic_name, diff --git a/rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp b/rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp index 1f96931da7..abb891d1d4 100644 --- a/rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp +++ b/rclcpp/include/rclcpp/experimental/subscription_intra_process_buffer.hpp @@ -15,7 +15,7 @@ #ifndef RCLCPP__EXPERIMENTAL__SUBSCRIPTION_INTRA_PROCESS_BUFFER_HPP_ #define RCLCPP__EXPERIMENTAL__SUBSCRIPTION_INTRA_PROCESS_BUFFER_HPP_ -#include // TODO remove +#include // TODO(anyone) remove #include #include #include @@ -46,7 +46,8 @@ template< /// otherwise just MessageT. typename ROSMessageType = typename rclcpp::TypeAdapter::ros_message_type > -class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBuffer +class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBuffer { public: RCLCPP_SMART_PTR_DEFINITIONS(SubscriptionIntraProcessBuffer) @@ -77,10 +78,12 @@ class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBuffer(context, topic_name, qos_profile) + : ROSMessageIntraProcessBuffer(context, topic_name, + qos_profile) { // Create the intra-process buffer. - buffer_ = rclcpp::experimental::create_intra_process_buffer( + buffer_ = rclcpp::experimental::create_intra_process_buffer( buffer_type, qos_profile, allocator); @@ -96,7 +99,6 @@ class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBuffer::is_specialized::value) { @@ -105,7 +107,8 @@ class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBufferadd_shared(std::unique_ptr(ptr, subscribed_type_deleter_)); + // buffer_->add_shared(std::unique_ptr( + // ptr, subscribed_type_deleter_)); // trigger_guard_condition(); } } @@ -121,10 +124,10 @@ class SubscriptionIntraProcessBuffer : public ROSMessageIntraProcessBuffer::convert_to_custom(*message, *ptr); - // buffer_->add_unique(std::unique_ptr(ptr, subscribed_type_deleter_)); + // buffer_->add_unique(std::unique_ptr( + // ptr, subscribed_type_deleter_)); // trigger_guard_condition(); } - } void diff --git a/rclcpp/include/rclcpp/publisher.hpp b/rclcpp/include/rclcpp/publisher.hpp index 9f7fc58eee..244f489557 100644 --- a/rclcpp/include/rclcpp/publisher.hpp +++ b/rclcpp/include/rclcpp/publisher.hpp @@ -512,7 +512,9 @@ class Publisher : public PublisherBase throw std::runtime_error("cannot publish msg which is a null pointer"); } - ipm->template do_intra_process_publish, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, PublishedTypeAllocator>( + ipm->template do_intra_process_publish, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, + ROSMessageTypeDeleter, PublishedTypeAllocator>( intra_process_publisher_id_, std::move(msg), published_type_allocator_, @@ -536,7 +538,9 @@ class Publisher : public PublisherBase } return ipm->template do_intra_process_publish_and_return_shared, ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, PublishedTypeAllocator>( + ROSMessageType, AllocatorT, std::default_delete, + ROSMessageTypeAllocatorTraits, ROSMessageTypeAllocator, ROSMessageTypeDeleter, + PublishedTypeAllocator>( intra_process_publisher_id_, std::move(msg), published_type_allocator_, diff --git a/rclcpp/include/rclcpp/subscription.hpp b/rclcpp/include/rclcpp/subscription.hpp index cf8732bf3d..ad23d60882 100644 --- a/rclcpp/include/rclcpp/subscription.hpp +++ b/rclcpp/include/rclcpp/subscription.hpp @@ -411,7 +411,6 @@ class Subscription : public SubscriptionBase AllocatorT, SubscribedTypeDeleter>; std::shared_ptr subscription_intra_process_; - }; } // namespace rclcpp diff --git a/rclcpp/test/rclcpp/test_subscription_publisher_with_same_type_adapter.cpp b/rclcpp/test/rclcpp/test_subscription_publisher_with_same_type_adapter.cpp index 9ae90e61d6..036fa11359 100644 --- a/rclcpp/test/rclcpp/test_subscription_publisher_with_same_type_adapter.cpp +++ b/rclcpp/test/rclcpp/test_subscription_publisher_with_same_type_adapter.cpp @@ -143,15 +143,12 @@ TEST_F( const std::string message_data = "Message Data"; const std::string topic_name = "topic_name"; - auto node = rclcpp::Node::make_shared( "test_intra_process", rclcpp::NodeOptions().use_intra_process_comms(true)); auto pub = node->create_publisher(topic_name, 1); - - { { // std::unique_ptr bool is_received = false;