Skip to content

improve lookup time for matches_any_publishers().#3068

Merged
ahcorde merged 2 commits intorollingfrom
issues/3067
Feb 18, 2026
Merged

improve lookup time for matches_any_publishers().#3068
ahcorde merged 2 commits intorollingfrom
issues/3067

Conversation

@fujitatomoya
Copy link
Collaborator

Description

Fixes #3067

Is this user-facing behavior change?

No, just a minor performance improvement.

Did you use Generative AI?

Yes, Copilot Claude Sonnet 4.5

Additional Information

Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
@fujitatomoya fujitatomoya self-assigned this Feb 18, 2026
Signed-off-by: Tomoya Fujita <Tomoya.Fujita@sony.com>
@fujitatomoya
Copy link
Collaborator Author

Pulls: #3068
Gist: https://gist.githubusercontent.com/fujitatomoya/c19e393b6ca155a3d6bf9012c60a8c2e/raw/76c8af93fb984113dd722b48638fdd6320a1b0e1/ros2.repos
BUILD args: --packages-above-and-dependencies rclcpp
TEST args: --packages-above rclcpp
ROS Distro: rolling
Job: ci_launcher
ci_launcher ran: https://ci.ros2.org/job/ci_launcher/18229

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Linux-rhel Build Status
  • Windows Build Status

@ahcorde ahcorde merged commit b6730f9 into rolling Feb 18, 2026
3 checks passed
@ahcorde ahcorde deleted the issues/3067 branch February 18, 2026 14:44
@mini-1235
Copy link
Contributor

@fujitatomoya I think this causes a regression in Nav2 (when turning intraprocess on)

backtrace:

Thread 14 "amcl" received signal SIGSEGV, Segmentation fault.                                                                                                       
[Switching to Thread 0x7fffcb7fe6c0 (LWP 983342)]
#0  0x00007ffff7dfd8b3 in std::_Hashtable<rmw_gid_s, std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo>, std::allocator<std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo> >, std::__detail::_Select1st, rclcpp::experimental::IntraProcessManager::rmw_gid_equal, rclcpp::experimental::IntraProcessManager::rmw_gid_hash, std::__detail::_Mod_range_hashing, std::__detail::_Default_ranged_hash, std::__detail::_Prime_rehash_policy, std::__detail::_Hashtable_traits<false, false, true> >::_M_find_before_node (this=0x55555565e448, __bkt=346849886, __k=..., 
    __code=<optimized out>) at /usr/include/c++/13/bits/hashtable.h:194
#1  0x00007ffff7e00b6c in std::_Hashtable<rmw_gid_s, std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo>, std::allocator<std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo> >, std::__detail::_Select1st, rclcpp::experimental::IntraProcessManager::rmw_gid_equal, rclcpp::experimental::IntraProcessManager::rmw_gid_hash, std::__detail::_Mod_range_hashing, std::__detail::_Default_ranged_hash, std::__detail::_Prime_rehash_policy, std::__detail::_Hashtable_traits<false, false, true> >::_M_find_node (__c=<optimized out>, __key=..., __bkt=<optimized out>, this=<optimized out>)
    at /usr/include/c++/13/bits/hashtable.h:815
#2  std::_Hashtable<rmw_gid_s, std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo>, std::allocator<std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo> >, std::__detail::_Select1st, rclcpp::experimental::IntraProcessManager::rmw_gid_equal, rclcpp::experimental::IntraProcessManager::rmw_gid_hash, std::__detail::_Mod_range_hashing, std--Type <RET> for more, q to quit, c to continue without paging--
::__detail::_Default_ranged_hash, std::__detail::_Prime_rehash_policy, std::__detail::_Hashtable_traits<false, false, true> >::find (__k=..., this=<optimized out>)
    at /usr/include/c++/13/bits/hashtable.h:1702
#3  std::_Hashtable<rmw_gid_s, std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo>, std::allocator<std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo> >, std::__detail::_Select1st, rclcpp::experimental::IntraProcessManager::rmw_gid_equal, rclcpp::experimental::IntraProcessManager::rmw_gid_hash, std::__detail::_Mod_range_hashing, std::__detail::_Default_ranged_hash, std::__detail::_Prime_rehash_policy, std::__detail::_Hashtable_traits<false, false, true> >::find (this=<optimized out>, __k=...) at /usr/include/c++/13/bits/hashtable.h:1687
#4  0x00007ffff7dffb50 in std::unordered_map<rmw_gid_s, rclcpp::experimental::IntraProcessManager::PublisherInfo, rclcpp::experimental::IntraProcessManager::rmw_gid_hash, rclcpp::experimental::IntraProcessManager::rmw_gid_equal, std::allocator<std::pair<rmw_gid_s const, rclcpp::experimental::IntraProcessManager::PublisherInfo> > >::find (__x=..., this=0x55555565e448) at /usr/include/c++/13/bits/unordered_map.h:88
#5  rclcpp::experimental::IntraProcessManager::matches_any_publishers (this=0x55555565e360, id=<optimized out>)
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/intra_process_manager.cpp:132
#6  0x00007ffff7ec8511 in rclcpp::SubscriptionBase::matches_any_intra_process_publishers (this=this@entry=0x7fffbc1e12f0, sender_gid=<optimized out>)
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/subscription_base.cpp:403
#7  0x00007ffff7ec86a3 in rclcpp::SubscriptionBase::take_type_erased (this=0x7fffbc1e12f0, message_out=0x7fffbc204430, message_info_out=...)
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/subscription_base.cpp:256
#8  0x00007ffff7dba2dd in operator() (__closure=<synthetic pointer>) at /usr/include/c++/13/bits/shared_ptr_base.h:1665
#9  take_and_do_error_handling<rclcpp::Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr)::<lambda()>, rclcpp::Executor::execute_subscription(rclcpp::SubscriptionBase::SharedPtr)::<lambda()> > (action_description=0x7ffff7f00226 "taking a message from topic", handle_action=..., take_action=..., 
    topic_or_service_name=0x7fffbc1e21d0 "/map") at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:522
#10 rclcpp::Executor::execute_subscription (subscription=std::shared_ptr<rclcpp::SubscriptionBase> (use count 3, weak count 4) = {...})
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:602
#11 0x00007ffff7dbb777 in rclcpp::Executor::execute_any_executable (this=this@entry=0x555555719fa0, any_exec=...)
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/executor.cpp:494
#12 0x00007ffff7de1802 in rclcpp::executors::SingleThreadedExecutor::spin (this=0x555555719fa0)
    at /root/nav2_ws/src/rclcpp/rclcpp/src/rclcpp/executors/single_threaded_executor.cpp:42
#13 0x00007ffff7a6fdb4 in ?? () from /lib/x86_64-linux-gnu/libstdc++.so.6
#14 0x00007ffff77dfaa4 in start_thread (arg=<optimized out>) at ./nptl/pthread_create.c:447
#15 0x00007ffff786cc6c in clone3 () at ../sysdeps/unix/sysv/linux/x86_64/clone3.S:78

@fujitatomoya
Copy link
Collaborator Author

@mini-1235 can you give it a shot with #3073 to see if your problem can be fixed? all rclcpp CI and tests are passing, there could be other possibility...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

Investigate performance of matches_any_publishers() when enabling intraprocess

4 participants

Comments