rosbag2 icon indicating copy to clipboard operation
rosbag2 copied to clipboard

rosbag2 playback causes memory release error when topic remap is enabled

Open zhihaoshang opened this issue 1 week ago • 0 comments

Description

Using --ros-args --remap to enable topic remapping and play messages, the program crashes during the creation of the subscription and playback process.

Expected Behavior

The program does not crash

Actual Behavior

Program crash

To Reproduce

Test Case

#include <gmock/gmock.h>
#include <chrono>
#include <future>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "rosbag2_test_common/subscription_manager.hpp"
#include "rosbag2_transport/player.hpp"
#include "test_msgs/msg/basic_types.hpp"
#include "test_msgs/message_fixtures.hpp"
#include "rosbag2_play_test_fixture.hpp"

TEST_F(RosBag2PlayTestFixture, test) {
  const std::string original_topic = "/topic_before_remap";
  const std::string remapped_topic = "/topic_after_remap";
  const int32_t test_value = 42;
  const int64_t dt_in_milliseconds = 100;
  const size_t expected_number_of_outgoing_messages = 5;
  play_options_.topic_remapping_options =
  {"--ros-args", "--remap", "topic_before_remap:=topic_after_remap"};
  auto primitive_message1 = get_messages_basic_types()[0];
  primitive_message1->int32_value = test_value;
  auto topic_types = std::vector<rosbag2_storage::TopicMetadata>{
    {1u, original_topic, "test_msgs/BasicTypes", "", {}, ""}
  };
  std::vector<std::shared_ptr<rosbag2_storage::SerializedBagMessage>> messages;
  for (auto i = 1u; i <= expected_number_of_outgoing_messages; ++i) {
    messages.push_back(
      serialize_test_message(original_topic, dt_in_milliseconds * i, primitive_message1));
  }
  auto prepared_mock_reader = std::make_unique<MockSequentialReader>();
  prepared_mock_reader->prepare(messages, topic_types);
  auto reader = std::make_unique<rosbag2_cpp::Reader>(std::move(prepared_mock_reader));
  sub_->add_subscription<test_msgs::msg::BasicTypes>(
    remapped_topic, 1u);
  auto await_received_messages = sub_->spin_subscriptions();
  auto player = std::make_shared<rosbag2_transport::Player>(
    std::move(reader), storage_options_, play_options_);
  ASSERT_TRUE(player->play());
  player->wait_for_playback_to_finish();
  await_received_messages.get();
  auto replayed_test_primitives = sub_->get_received_messages<test_msgs::msg::BasicTypes>(
    remapped_topic);
  EXPECT_FALSE(replayed_test_primitives.empty());
  EXPECT_THAT(
    replayed_test_primitives,
    Each(Pointee(Field(&test_msgs::msg::BasicTypes::int32_value, test_value))));
}

Output

[ RUN      ] RosBag2PlayTestFixture.test
=================================================================
==7736==ERROR: AddressSanitizer: new-delete-type-mismatch on 0x5060000746c0 in thread T0:
  object passed to delete has wrong type:
  size of the allocated type:   64 bytes;
  size of the deallocated type: 1 bytes.
    #0 0x78ef2dcff5e8 in operator delete(void*, unsigned long) ../../../../src/libsanitizer/asan/asan_new_delete.cpp:164
    #1 0x5b5f8faf99de in std::__new_allocator<char>::deallocate(char*, unsigned long) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3419de) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #2 0x5b5f8fb58b54 in void rclcpp::allocator::retyped_deallocate<char, std::allocator<char> >(void*, void*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3a0b54) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #3 0x78ef2af14826 in rcutils_string_map_fini (/home/shangzh/ros2_jazzy/install/rcutils/lib/librcutils.so+0x13826) (BuildId: 47470fc0f3cc7c03a11a022d1a45f220e5c43954)
    #4 0x78ef2c60b996 in rcl_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2f996) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #5 0x78ef2c60bce6 in rcl_node_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2fce6) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #6 0x78ef2c61139e in rcl_subscription_init (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x3539e) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #7 0x78ef2c33756d in rclcpp::SubscriptionBase::SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcl_subscription_options_s const&, rclcpp::SubscriptionEventCallbacks const&, bool, rclcpp::DeliveredMessageKind) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd3756d) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #8 0x78ef2c38e9bb in rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >::Subscription(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8e9bb) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #9 0x78ef2c38c2ad in void std::_Construct<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8c2ad) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #10 0x78ef2c38822c in std::_Sp_counted_ptr_inplace<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<void>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8822c) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #11 0x78ef2c3847ec in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd847ec) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #12 0x78ef2c37fc7c in std::__shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(std::_Sp_alloc_shared_tag<std::allocator<void> >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd7fc7c) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #13 0x78ef2c379bd0 in std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::shared_ptr<std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(std::_Sp_alloc_shared_tag<std::allocator<void> >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd79bd0) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #14 0x78ef2c372848 in std::shared_ptr<std::enable_if<!std::is_array<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::value, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > >::type> std::make_shared<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd72848) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #15 0x78ef2c36a5cc in std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >::make_shared<rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd6a5cc) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #16 0x78ef2c3661ff in rclcpp::create_subscription_factory<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}::operator()(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&) const (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd661ff) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #17 0x78ef2c380a5c in std::shared_ptr<rclcpp::SubscriptionBase> std::__invoke_impl<std::shared_ptr<rclcpp::SubscriptionBase>, rclcpp::create_subscription_factory<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}&, rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&>(std::__invoke_other, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::node_interfaces::NodeBaseInterface*&&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd80a5c) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #18 0x78ef2c37b2b0 in std::enable_if<is_invocable_r_v<std::shared_ptr<rclcpp::SubscriptionBase>, rclcpp::create_subscription_factory<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}&, rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&>, std::shared_ptr<rclcpp::SubscriptionBase> >::type std::__invoke_r<std::shared_ptr<rclcpp::SubscriptionBase>, rclcpp::create_subscription_factory<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}&, rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&>(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::node_interfaces::NodeBaseInterface*&&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd7b2b0) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #19 0x78ef2c374b15 in std::_Function_handler<std::shared_ptr<rclcpp::SubscriptionBase> (rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&), rclcpp::create_subscription_factory<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >(rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>)::{lambda(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)#1}>::_M_invoke(std::_Any_data const&, rclcpp::node_interfaces::NodeBaseInterface*&&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd74b15) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #20 0x78ef2c23997e in std::function<std::shared_ptr<rclcpp::SubscriptionBase> (rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&)>::operator()(rclcpp::node_interfaces::NodeBaseInterface*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&) const (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xc3997e) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #21 0x78ef2c238fcb in rclcpp::node_interfaces::NodeTopics::create_subscription(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::SubscriptionFactory const&, rclcpp::QoS const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xc38fcb) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #22 0x78ef2c360aa9 in std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > rclcpp::detail::create_subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> >(std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd60aa9) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #23 0x78ef2c35d03f in std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > rclcpp::create_subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::allocator<void>, rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface> >(std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >::SharedPtr) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd5d03f) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #24 0x78ef2c359b9b in std::shared_ptr<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > > rclcpp::AsyncParametersClient::on_parameter_event<rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, std::allocator<void> >(std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>&, rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>)::{lambda(std::shared_ptr<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> > const>)#1}&&, rclcpp::QoS const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd59b9b) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #25 0x78ef2c355f04 in rclcpp::TimeSource::NodeState::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd55f04) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #26 0x78ef2c351602 in rclcpp::TimeSource::attachNode(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd51602) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #27 0x78ef2c237fb9 in rclcpp::node_interfaces::NodeTimeSource::NodeTimeSource(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeTopicsInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeGraphInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeServicesInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeLoggingInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeClockInterface>, std::shared_ptr<rclcpp::node_interfaces::NodeParametersInterface>, rclcpp::QoS const&, bool) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xc37fb9) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #28 0x78ef2c1c1573 in rclcpp::Node::Node(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::NodeOptions const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xbc1573) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #29 0x78ef2c1c06ab in rclcpp::Node::Node(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::NodeOptions const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xbc06ab) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #30 0x5b5f8fb2c809 in void std::_Construct<rclcpp::Node, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(rclcpp::Node*, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x374809) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #31 0x5b5f8fb0ff6e in std::_Sp_counted_ptr_inplace<rclcpp::Node, std::allocator<void>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(std::allocator<void>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x357f6e) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #32 0x5b5f8faff3db in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rclcpp::Node, std::allocator<void>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(rclcpp::Node*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3473db) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #33 0x5b5f8faef7a3 in std::__shared_ptr<rclcpp::Node, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<void>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(std::_Sp_alloc_shared_tag<std::allocator<void> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3377a3) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #34 0x5b5f8fade75e in std::shared_ptr<rclcpp::Node>::shared_ptr<std::allocator<void>, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(std::_Sp_alloc_shared_tag<std::allocator<void> >, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x32675e) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #35 0x5b5f8facd143 in std::shared_ptr<std::enable_if<!std::is_array<rclcpp::Node>::value, rclcpp::Node>::type> std::make_shared<rclcpp::Node, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >, rclcpp::NodeOptions&>(std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> >&&, rclcpp::NodeOptions&) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x315143) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #36 0x5b5f8fabad29 in rosbag2_test_common::SubscriptionManager::SubscriptionManager() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x302d29) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #37 0x5b5f8fb2eb42 in void std::_Construct<rosbag2_test_common::SubscriptionManager>(rosbag2_test_common::SubscriptionManager*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x376b42) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #38 0x5b5f8fb14f13 in std::_Sp_counted_ptr_inplace<rosbag2_test_common::SubscriptionManager, std::allocator<void>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<>(std::allocator<void>) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x35cf13) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #39 0x5b5f8fb06ba2 in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rosbag2_test_common::SubscriptionManager, std::allocator<void>>(rosbag2_test_common::SubscriptionManager*&, std::_Sp_alloc_shared_tag<std::allocator<void> >) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x34eba2) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #40 0x5b5f8faf68ee in std::__shared_ptr<rosbag2_test_common::SubscriptionManager, (__gnu_cxx::_Lock_policy)2>::__shared_ptr<std::allocator<void>>(std::_Sp_alloc_shared_tag<std::allocator<void> >) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x33e8ee) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #41 0x5b5f8fae5dcd in std::shared_ptr<rosbag2_test_common::SubscriptionManager>::shared_ptr<std::allocator<void>>(std::_Sp_alloc_shared_tag<std::allocator<void> >) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x32ddcd) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #42 0x5b5f8fad313b in std::shared_ptr<std::enable_if<!std::is_array<rosbag2_test_common::SubscriptionManager>::value, rosbag2_test_common::SubscriptionManager>::type> std::make_shared<rosbag2_test_common::SubscriptionManager>() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x31b13b) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #43 0x5b5f8fac26c8 in RosBag2PlayTestFixture::RosBag2PlayTestFixture() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x30a6c8) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #44 0x5b5f8fba478b in RosBag2PlayTestFixture_test_Test::RosBag2PlayTestFixture_test_Test() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3ec78b) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #45 0x5b5f8fba47ed in testing::internal::TestFactoryImpl<RosBag2PlayTestFixture_test_Test>::CreateTest() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3ec7ed) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #46 0x5b5f8fc63d63 in testing::Test* testing::internal::HandleSehExceptionsInMethodIfSupported<testing::internal::TestFactoryBase, testing::Test*>(testing::internal::TestFactoryBase*, testing::Test* (testing::internal::TestFactoryBase::*)(), char const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x4abd63) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #47 0x5b5f8fc525c5 in testing::Test* testing::internal::HandleExceptionsInMethodIfSupported<testing::internal::TestFactoryBase, testing::Test*>(testing::internal::TestFactoryBase*, testing::Test* (testing::internal::TestFactoryBase::*)(), char const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x49a5c5) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #48 0x5b5f8fbfb645 in testing::TestInfo::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x443645) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #49 0x5b5f8fbfc9dc in testing::TestSuite::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x4449dc) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #50 0x5b5f8fc23707 in testing::internal::UnitTestImpl::RunAllTests() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x46b707) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #51 0x5b5f8fc66a26 in bool testing::internal::HandleSehExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool>(testing::internal::UnitTestImpl*, bool (testing::internal::UnitTestImpl::*)(), char const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x4aea26) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #52 0x5b5f8fc54dc6 in bool testing::internal::HandleExceptionsInMethodIfSupported<testing::internal::UnitTestImpl, bool>(testing::internal::UnitTestImpl*, bool (testing::internal::UnitTestImpl::*)(), char const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x49cdc6) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #53 0x5b5f8fc1fd11 in testing::UnitTest::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x467d11) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #54 0x5b5f8fbca1b2 in RUN_ALL_TESTS() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x4121b2) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #55 0x5b5f8fbca0fe in main (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x4120fe) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #56 0x78ef2a82a1c9 in __libc_start_call_main ../sysdeps/nptl/libc_start_call_main.h:58
    #57 0x78ef2a82a28a in __libc_start_main_impl ../csu/libc-start.c:360
    #58 0x5b5f8faa6a04 in _start (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x2eea04) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)

0x5060000746c0 is located 0 bytes inside of 64-byte region [0x5060000746c0,0x506000074700)
allocated by thread T0 here:
    #0 0x78ef2dcfe548 in operator new(unsigned long) ../../../../src/libsanitizer/asan/asan_new_delete.cpp:95
    #1 0x5b5f8fb0b1bb in std::__new_allocator<char>::allocate(unsigned long, void const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3531bb) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #2 0x5b5f8fb5899e in void* rclcpp::allocator::retyped_allocate<std::allocator<char> >(unsigned long, void*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_topic_remap+0x3a099e) (BuildId: 809aabb4c7bcc6b0169142658392faeb20b92214)
    #3 0x78ef2af14620 in rcutils_string_map_init (/home/shangzh/ros2_jazzy/install/rcutils/lib/librcutils.so+0x13620) (BuildId: 47470fc0f3cc7c03a11a022d1a45f220e5c43954)
    #4 0x78ef2c60b6bf in rcl_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2f6bf) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #5 0x78ef2c60bce6 in rcl_node_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2fce6) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #6 0x78ef2c61139e in rcl_subscription_init (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x3539e) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #7 0x78ef2c33756d in rclcpp::SubscriptionBase::SubscriptionBase(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rcl_subscription_options_s const&, rclcpp::SubscriptionEventCallbacks const&, bool, rclcpp::DeliveredMessageKind) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd3756d) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #8 0x78ef2c38e9bb in rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >::Subscription(rclcpp::node_interfaces::NodeBaseInterface*, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> >, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics>) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8e9bb) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #9 0x78ef2c38c2ad in void std::_Construct<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8c2ad) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #10 0x78ef2c38822c in std::_Sp_counted_ptr_inplace<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<void>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd8822c) (BuildId: 0ec5bbf30e14324f264f03466527d436b1f542ce)
    #11 0x78ef2c3847ec in std::__shared_count<(__gnu_cxx::_Lock_policy)2>::__shared_count<rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >, std::allocator<void>, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&>(rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void>, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > >*&, std::_Sp_alloc_shared_tag<std::allocator<void> >, rclcpp::node_interfaces::NodeBaseInterface*&, rosidl_message_type_support_t const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, rclcpp::QoS const&, rclcpp::AnySubscriptionCallback<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > const&, rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void> > const&, std::shared_ptr<rclcpp::message_memory_strategy::MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent_<std::allocator<void> >, std::allocator<void> > > const&, std::shared_ptr<rclcpp::topic_statistics::SubscriptionTopicStatistics> const&) (/home/shangzh/ros2_jazzy/install/rclcpp/lib/librclcpp.so+0xd847ec) (BuildId: 

SUMMARY: AddressSanitizer: new-delete-type-mismatch ../../../../src/libsanitizer/asan/asan_new_delete.cpp:164 in operator delete(void*, unsigned long)
==7736==HINT: if you don't care about these errors you may set ASAN_OPTIONS=new_delete_type_mismatch=0
==7736==ABORTING

System (please complete the following information)

OS: ubuntu 24.04 ROS 2 Distro: ros 2 jazzy Install Method: source Version: ros 2 jazzy build options: --mixin asan-gcc

zhihaoshang avatar Dec 20 '25 09:12 zhihaoshang