Skip to content
Open
Show file tree
Hide file tree
Changes from 4 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
6 changes: 4 additions & 2 deletions rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,12 +118,14 @@ create_subscription(
subscription_topic_stats->set_publisher_timer(timer);
}

auto factory = rclcpp::create_subscription_factory<MessageT>(
auto factory = rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT,
SubscriptionT, MessageMemoryStrategyT
>(
std::forward<CallbackT>(callback),
options,
msg_mem_strat,
subscription_topic_stats
);
);

const rclcpp::QoS & actual_qos = options.qos_overriding_options.get_policy_kinds().size() ?
rclcpp::detail::declare_qos_parameters(
Expand Down
3 changes: 2 additions & 1 deletion rclcpp/include/rclcpp/node_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,8 @@ Node::create_subscription(
const SubscriptionOptionsWithAllocator<AllocatorT> & options,
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
{
return rclcpp::create_subscription<MessageT>(
return rclcpp::create_subscription<
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
*this,
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
qos,
Expand Down
7 changes: 2 additions & 5 deletions rclcpp/include/rclcpp/subscription_factory.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -100,10 +100,7 @@ create_subscription_factory(
const rclcpp::QoS & qos
) -> rclcpp::SubscriptionBase::SharedPtr
{
using rclcpp::Subscription;
using rclcpp::SubscriptionBase;

auto sub = Subscription<MessageT, AllocatorT>::make_shared(
auto sub = std::make_shared<SubscriptionT>(
node_base,
rclcpp::get_message_type_support_handle<MessageT>(),
topic_name,
Expand All @@ -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<SubscriptionBase>(sub);
auto sub_base_ptr = std::dynamic_pointer_cast<rclcpp::SubscriptionBase>(sub);
return sub_base_ptr;
}
};
Expand Down
7 changes: 7 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
86 changes: 86 additions & 0 deletions rclcpp/test/rclcpp/test_create_custom_subscription.cpp
Original file line number Diff line number Diff line change
@@ -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 <gtest/gtest.h>

#include <chrono>
#include <memory>
#include <type_traits>

#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 TestCreateSubscription : public ::testing::Test
{
public:
void SetUp() override
{
rclcpp::init(0, nullptr);
}

void TearDown() override
{
rclcpp::shutdown();
}
};

template<
typename MessageT,
typename AllocatorT = std::allocator<void>,
typename SubscribedT = typename rclcpp::TypeAdapter<MessageT>::custom_type,
typename ROSMessageT = typename rclcpp::TypeAdapter<MessageT>::ros_message_type,
typename MessageMemoryStrategyT = rclcpp::message_memory_strategy::MessageMemoryStrategy<
ROSMessageT,
AllocatorT
>>
class CustomSubscription : public rclcpp::Subscription<
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>
{
public:
template<typename ... Args>
explicit CustomSubscription(Args &&... args)
: rclcpp::Subscription<
MessageT, AllocatorT, SubscribedT, ROSMessageT, MessageMemoryStrategyT>(
std::forward<Args>(args)...) {}
};

TEST_F(TestCreateSubscription, create) {
using MessageT = test_msgs::msg::Empty;

auto node = std::make_shared<rclcpp::Node>("my_node", "/ns");
const rclcpp::QoS qos(10);
auto options = rclcpp::SubscriptionOptions();
auto callback = [](MessageT::ConstSharedPtr) {};

using CallbackT = std::decay_t<decltype(callback)>;
using AllocatorT = std::allocator<void>;
using SubscriptionT = CustomSubscription<MessageT, AllocatorT>;
using CallbackMessageT =
typename rclcpp::subscription_traits::has_message_type<CallbackT>::type;
using MessageMemoryStrategyT =
rclcpp::message_memory_strategy::MessageMemoryStrategy<CallbackMessageT, AllocatorT>;

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<std::decay_t<decltype(*subscription.get())>, SubscriptionT>);
}