diff --git a/rclcpp/include/rclcpp/create_subscription.hpp b/rclcpp/include/rclcpp/create_subscription.hpp index 3a1e4b1a13..d41ba5a892 100644 --- a/rclcpp/include/rclcpp/create_subscription.hpp +++ b/rclcpp/include/rclcpp/create_subscription.hpp @@ -118,7 +118,9 @@ create_subscription( subscription_topic_stats->set_publisher_timer(timer); } - auto factory = rclcpp::create_subscription_factory( + auto factory = rclcpp::create_subscription_factory( std::forward(callback), options, msg_mem_strat, diff --git a/rclcpp/include/rclcpp/node_impl.hpp b/rclcpp/include/rclcpp/node_impl.hpp index 5b81bdcba4..4ff4732d92 100644 --- a/rclcpp/include/rclcpp/node_impl.hpp +++ b/rclcpp/include/rclcpp/node_impl.hpp @@ -97,7 +97,8 @@ Node::create_subscription( const SubscriptionOptionsWithAllocator & options, typename MessageMemoryStrategyT::SharedPtr msg_mem_strat) { - return rclcpp::create_subscription( + return rclcpp::create_subscription< + MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>( *this, extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()), qos, diff --git a/rclcpp/include/rclcpp/subscription_factory.hpp b/rclcpp/include/rclcpp/subscription_factory.hpp index 0e9d9fefe5..ae60f05b4a 100644 --- a/rclcpp/include/rclcpp/subscription_factory.hpp +++ b/rclcpp/include/rclcpp/subscription_factory.hpp @@ -100,10 +100,7 @@ create_subscription_factory( const rclcpp::QoS & qos ) -> rclcpp::SubscriptionBase::SharedPtr { - using rclcpp::Subscription; - using rclcpp::SubscriptionBase; - - auto sub = Subscription::make_shared( + auto sub = std::make_shared( node_base, rclcpp::get_message_type_support_handle(), topic_name, @@ -116,7 +113,7 @@ create_subscription_factory( // require this->shared_from_this() which cannot be called from // the constructor. sub->post_init_setup(node_base, qos, options); - auto sub_base_ptr = std::dynamic_pointer_cast(sub); + auto sub_base_ptr = std::dynamic_pointer_cast(sub); return sub_base_ptr; } }; diff --git a/rclcpp/test/rclcpp/CMakeLists.txt b/rclcpp/test/rclcpp/CMakeLists.txt index 35fa8fdd32..e1c2bdf75e 100644 --- a/rclcpp/test/rclcpp/CMakeLists.txt +++ b/rclcpp/test/rclcpp/CMakeLists.txt @@ -95,6 +95,13 @@ if(TARGET test_generic_service) ${test_msgs_TARGETS} ) endif() +ament_add_gtest(test_create_custom_subscription test_create_custom_subscription.cpp) +if(TARGET test_create_custom_subscription) + target_link_libraries(test_create_custom_subscription ${PROJECT_NAME}) + ament_target_dependencies(test_create_custom_subscription + "test_msgs" + ) +endif() ament_add_gtest(test_client_common test_client_common.cpp) ament_add_test_label(test_client_common mimick) if(TARGET test_client_common) diff --git a/rclcpp/test/rclcpp/test_create_custom_subscription.cpp b/rclcpp/test/rclcpp/test_create_custom_subscription.cpp new file mode 100644 index 0000000000..b1ceb4f320 --- /dev/null +++ b/rclcpp/test/rclcpp/test_create_custom_subscription.cpp @@ -0,0 +1,86 @@ +// Copyright 2025 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +#include +#include +#include + +#include "rclcpp/subscription.hpp" +#include "rclcpp/create_subscription.hpp" +#include "rclcpp/node.hpp" +#include "test_msgs/msg/empty.hpp" +#include "test_msgs/msg/empty.h" + +using namespace std::chrono_literals; + +class TestCreateCustomSubscription : public ::testing::Test +{ +public: + void SetUp() override + { + rclcpp::init(0, nullptr); + } + + void TearDown() override + { + rclcpp::shutdown(); + } +}; + +template< + typename MessageT, + typename AllocatorT = std::allocator, + typename SubscribedT = typename rclcpp::TypeAdapter::custom_type, + typename ROSMessageT = typename rclcpp::TypeAdapter::ros_message_type, + typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy< + ROSMessageT, + AllocatorT + >> +class CustomSubscription : public rclcpp::Subscription< + MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT> +{ +public: + template + explicit CustomSubscription(Args &&... args) + : rclcpp::Subscription< + MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>( + std::forward(args)...) {} +}; + +TEST_F(TestCreateCustomSubscription, create) { + using MessageT = test_msgs::msg::Empty; + + auto node = std::make_shared("my_node", "/ns"); + const rclcpp::QoS qos(10); + auto options = rclcpp::SubscriptionOptions(); + auto callback = [](MessageT::ConstSharedPtr) {}; + + using CallbackT = std::decay_t; + using AllocatorT = std::allocator; + using SubscriptionT = CustomSubscription; + using CallbackMessageT = + typename rclcpp::subscription_traits::has_message_type::type; + using MessageMemoryStrategyT = + rclcpp::message_memory_strategy::MessageMemoryStrategy; + + auto subscription = rclcpp::create_subscription< + MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>( + node, "topic_name", qos, std::move(callback), options); + + ASSERT_NE(nullptr, subscription); + EXPECT_STREQ("/ns/topic_name", subscription->get_topic_name()); + static_assert(std::is_same_v, SubscriptionT>); +}