Skip to content

Commit

Permalink
Bug with creating a custom subscriber was fixed.
Browse files Browse the repository at this point in the history
Signed-off-by: olesya <[email protected]>
  • Loading branch information
bks-ol committed Jan 19, 2025
1 parent 1977397 commit 4dfefcf
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 7 deletions.
5 changes: 4 additions & 1 deletion rclcpp/include/rclcpp/create_subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,10 @@ 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,
ROSMessageType
>(
std::forward<CallbackT>(callback),
options,
msg_mem_strat,
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 @@ -96,7 +96,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 @@ -101,10 +101,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 @@ -117,7 +114,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

0 comments on commit 4dfefcf

Please sign in to comment.