Skip to content

Commit 4dfefcf

Browse files
committed
Bug with creating a custom subscriber was fixed.
Signed-off-by: olesya <[email protected]>
1 parent 1977397 commit 4dfefcf

File tree

3 files changed

+8
-7
lines changed

3 files changed

+8
-7
lines changed

rclcpp/include/rclcpp/create_subscription.hpp

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -119,7 +119,10 @@ create_subscription(
119119
subscription_topic_stats->set_publisher_timer(timer);
120120
}
121121

122-
auto factory = rclcpp::create_subscription_factory<MessageT>(
122+
auto factory = rclcpp::create_subscription_factory<MessageT, CallbackT, AllocatorT,
123+
SubscriptionT, MessageMemoryStrategyT,
124+
ROSMessageType
125+
>(
123126
std::forward<CallbackT>(callback),
124127
options,
125128
msg_mem_strat,

rclcpp/include/rclcpp/node_impl.hpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -96,7 +96,8 @@ Node::create_subscription(
9696
const SubscriptionOptionsWithAllocator<AllocatorT> & options,
9797
typename MessageMemoryStrategyT::SharedPtr msg_mem_strat)
9898
{
99-
return rclcpp::create_subscription<MessageT>(
99+
return rclcpp::create_subscription<
100+
MessageT, CallbackT, AllocatorT, SubscriptionT, MessageMemoryStrategyT>(
100101
*this,
101102
extend_name_with_sub_namespace(topic_name, this->get_sub_namespace()),
102103
qos,

rclcpp/include/rclcpp/subscription_factory.hpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -101,10 +101,7 @@ create_subscription_factory(
101101
const rclcpp::QoS & qos
102102
) -> rclcpp::SubscriptionBase::SharedPtr
103103
{
104-
using rclcpp::Subscription;
105-
using rclcpp::SubscriptionBase;
106-
107-
auto sub = Subscription<MessageT, AllocatorT>::make_shared(
104+
auto sub = std::make_shared<SubscriptionT>(
108105
node_base,
109106
rclcpp::get_message_type_support_handle<MessageT>(),
110107
topic_name,
@@ -117,7 +114,7 @@ create_subscription_factory(
117114
// require this->shared_from_this() which cannot be called from
118115
// the constructor.
119116
sub->post_init_setup(node_base, qos, options);
120-
auto sub_base_ptr = std::dynamic_pointer_cast<SubscriptionBase>(sub);
117+
auto sub_base_ptr = std::dynamic_pointer_cast<rclcpp::SubscriptionBase>(sub);
121118
return sub_base_ptr;
122119
}
123120
};

0 commit comments

Comments
 (0)