Skip to content

Commit eff6476

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

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
@@ -118,7 +118,10 @@ create_subscription(
118118
subscription_topic_stats->set_publisher_timer(timer);
119119
}
120120

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

rclcpp/include/rclcpp/node_impl.hpp

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

rclcpp/include/rclcpp/subscription_factory.hpp

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

0 commit comments

Comments
 (0)