rosbag2 icon indicating copy to clipboard operation
rosbag2 copied to clipboard

Creating a subscription triggers a crash when clock_publish_frequency is enabled

Open zhihaoshang opened this issue 1 week ago • 0 comments

Description

Set play_options_.clock_publish_frequency = 20 and call run_test(), it crashes immediately during execution.

Expected Behavior

no crash

Actual Behavior

crash

To Reproduce

Test Case

#include <gmock/gmock.h>
#include <memory>
#include <utility>
#include <vector>
#include <rclcpp/executors.hpp>
#include "rosbag2_transport/player.hpp"
#include "rosgraph_msgs/msg/clock.hpp"
#include "test_msgs/message_fixtures.hpp"
#include "mock_player.hpp"
#include "rosbag2_play_test_fixture.hpp"

using namespace ::testing;  // NOLINT

namespace
{
rcutils_duration_value_t period_for_frequency(double frequency)
{
  return static_cast<rcutils_duration_value_t>(RCUTILS_S_TO_NS(1) / frequency);
}
}  // namespace

class ClockPublishFixture : public RosBag2PlayTestFixture
{
public:
  void run_test()
  {
    auto topic_types = std::vector<rosbag2_storage::TopicMetadata>{
        {1u, "topic1", "test_msgs/BasicTypes", "", {}, ""},
    };
    std::vector<std::shared_ptr<rosbag2_storage::SerializedBagMessage>> messages;
    for (size_t i = 0; i < messages_to_play_; i++) {
      auto message = get_messages_basic_types()[0];
      message->int32_value = static_cast<int32_t>(i);
      messages.push_back(
          serialize_test_message("topic1", milliseconds_between_messages_ * i, message));
    }
    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));
    auto player = std::make_shared<MockPlayer>(std::move(reader), storage_options_, play_options_);
    rclcpp::executors::SingleThreadedExecutor exec;
    exec.add_node(player);
    auto spin_thread = std::thread(
        [&exec]() {
          exec.spin();
        });
    sub_->add_subscription<test_msgs::msg::BasicTypes>("/topic1", messages.size());
    sub_->add_subscription<rosgraph_msgs::msg::Clock>(
        "/clock", expected_clock_messages_, rclcpp::ClockQoS());
    ASSERT_TRUE(
        sub_->spin_and_wait_for_matched(player->get_list_of_publishers(), std::chrono::seconds(30)));

    auto await_received_messages = sub_->spin_subscriptions();
    
    // Modify play to catch exceptions and verify playback starts correctly
    try {
      player->play();
      player->wait_for_playback_to_start();  // Ensure playback starts correctly
    } catch (const std::exception &e) {
      FAIL() << "Exception during playback start: " << e.what();
    }
    
    // Modify to ensure wait_for_playback_to_finish doesn't block indefinitely
    ASSERT_TRUE(player->wait_for_playback_to_finish(std::chrono::seconds(30)));
    
    await_received_messages.get();
    exec.cancel();
    spin_thread.join();
    
    auto received_clock = sub_->get_received_messages<rosgraph_msgs::msg::Clock>("/clock");
    ASSERT_THAT(received_clock, SizeIs(Ge(expected_clock_messages_)));
    if (play_options_.clock_publish_frequency > 0.f) {
      const auto expect_clock_delta =
          period_for_frequency(play_options_.clock_publish_frequency) * play_options_.rate;
      const auto allowed_error = static_cast<rcutils_duration_value_t>(
          expect_clock_delta * error_tolerance_);
      const auto start_message = 2;
      for (size_t i = start_message; i < expected_clock_messages_ - 1; i++) {
        auto current = rclcpp::Time(received_clock[i]->clock).nanoseconds();
        auto next = rclcpp::Time(received_clock[i + 1]->clock).nanoseconds();
        auto delta = next - current;
        auto error = std::abs(delta - expect_clock_delta);
        EXPECT_LE(error, allowed_error) << "Message was too far from next: " << i;
      }
    }
  }

  size_t messages_to_play_ = 10;
  const int64_t milliseconds_between_messages_ = 50;
  const double error_tolerance_ = 0.3;
  size_t expected_clock_messages_ = 6;
};

TEST_F(ClockPublishFixture, test)
{
  play_options_.clock_publish_frequency = 20;
  run_test();
}

Output

[ RUN      ] ClockPublishFixture.test
=================================================================
==9036==ERROR: AddressSanitizer: new-delete-type-mismatch on 0x506000074720 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 0x76fe2e6ff5e8 in operator delete(void*, unsigned long) ../../../../src/libsanitizer/asan/asan_new_delete.cpp:164
    #1 0x64643f10b4da in std::__new_allocator<char>::deallocate(char*, unsigned long) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x4634da) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #2 0x64643f17ef6c in void rclcpp::allocator::retyped_deallocate<char, std::allocator<char> >(void*, void*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x4d6f6c) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #3 0x76fe2b8cf826 in rcutils_string_map_fini (/home/shangzh/ros2_jazzy/install/rcutils/lib/librcutils.so+0x13826) (BuildId: 47470fc0f3cc7c03a11a022d1a45f220e5c43954)
    #4 0x76fe2bfd3996 in rcl_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2f996) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #5 0x76fe2bfd3ce6 in rcl_node_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2fce6) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #6 0x76fe2bfd939e in rcl_subscription_init (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x3539e) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #7 0x76fe2cd3756d 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 0x76fe2cd8e9bb 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 0x76fe2cd8c2ad 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 0x76fe2cd8822c 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 0x76fe2cd847ec 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 0x76fe2cd7fc7c 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 0x76fe2cd79bd0 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 0x76fe2cd72848 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 0x76fe2cd6a5cc 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 0x76fe2cd661ff 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 0x76fe2cd80a5c 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 0x76fe2cd7b2b0 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 0x76fe2cd74b15 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 0x76fe2cc3997e 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 0x76fe2cc38fcb 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 0x76fe2cd60aa9 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 0x76fe2cd5d03f 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 0x76fe2cd59b9b 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 0x76fe2cd55f04 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 0x76fe2cd51602 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 0x76fe2cc37fb9 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 0x76fe2cbc1573 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 0x76fe2cbc06ab 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 0x64643f144409 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_publish_clock+0x49c409) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #31 0x64643f125c0e 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_publish_clock+0x47dc0e) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #32 0x64643f11345b 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_publish_clock+0x46b45b) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #33 0x64643f101b8b 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_publish_clock+0x459b8b) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #34 0x64643f0efb52 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_publish_clock+0x447b52) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #35 0x64643f0dd36d 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_publish_clock+0x43536d) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #36 0x64643f0c531d in rosbag2_test_common::SubscriptionManager::SubscriptionManager() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x41d31d) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #37 0x64643f146372 in void std::_Construct<rosbag2_test_common::SubscriptionManager>(rosbag2_test_common::SubscriptionManager*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x49e372) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #38 0x64643f1299f9 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_publish_clock+0x4819f9) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #39 0x64643f118ca6 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_publish_clock+0x470ca6) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #40 0x64643f106ba6 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_publish_clock+0x45eba6) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #41 0x64643f0f49dd 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_publish_clock+0x44c9dd) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #42 0x64643f0e08a1 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_publish_clock+0x4388a1) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #43 0x64643f0cbf1e in RosBag2PlayTestFixture::RosBag2PlayTestFixture() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x423f1e) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #44 0x64643f1f0321 in ClockPublishFixture::ClockPublishFixture() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x548321) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #45 0x64643f1f044d in ClockPublishFixture_test_Test::ClockPublishFixture_test_Test() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x54844d) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #46 0x64643f1f04af in testing::internal::TestFactoryImpl<ClockPublishFixture_test_Test>::CreateTest() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x5484af) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #47 0x64643f2c51f1 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_publish_clock+0x61d1f1) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #48 0x64643f2b3aab 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_publish_clock+0x60baab) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #49 0x64643f25d483 in testing::TestInfo::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x5b5483) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #50 0x64643f25e81a in testing::TestSuite::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x5b681a) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #51 0x64643f285545 in testing::internal::UnitTestImpl::RunAllTests() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x5dd545) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #52 0x64643f2c7eb4 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_publish_clock+0x61feb4) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #53 0x64643f2b62ac 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_publish_clock+0x60e2ac) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #54 0x64643f281b4f in testing::UnitTest::Run() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x5d9b4f) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #55 0x64643f22bff0 in RUN_ALL_TESTS() (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x583ff0) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #56 0x64643f22bf3c in main (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x583f3c) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #57 0x76fe2b22a1c9 in __libc_start_call_main ../sysdeps/nptl/libc_start_call_main.h:58
    #58 0x76fe2b22a28a in __libc_start_main_impl ../csu/libc-start.c:360
    #59 0x64643f0b1b44 in _start (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x409b44) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)

0x506000074720 is located 0 bytes inside of 64-byte region [0x506000074720,0x506000074760)
allocated by thread T0 here:
    #0 0x76fe2e6fe548 in operator new(unsigned long) ../../../../src/libsanitizer/asan/asan_new_delete.cpp:95
    #1 0x64643f11fb53 in std::__new_allocator<char>::allocate(unsigned long, void const*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x477b53) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #2 0x64643f17edb6 in void* rclcpp::allocator::retyped_allocate<std::allocator<char> >(unsigned long, void*) (/home/shangzh/rosbag2_ws/build/rosbag2_transport/test_play_publish_clock+0x4d6db6) (BuildId: 5c22c35083d790700521103fba96b7beefed9d79)
    #3 0x76fe2b8cf620 in rcutils_string_map_init (/home/shangzh/ros2_jazzy/install/rcutils/lib/librcutils.so+0x13620) (BuildId: 47470fc0f3cc7c03a11a022d1a45f220e5c43954)
    #4 0x76fe2bfd36bf in rcl_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2f6bf) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #5 0x76fe2bfd3ce6 in rcl_node_resolve_name (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x2fce6) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #6 0x76fe2bfd939e in rcl_subscription_init (/home/shangzh/ros2_jazzy/install/rcl/lib/librcl.so+0x3539e) (BuildId: c46bfb353f53d2e0123ebceb30f6dcdaca2f9f87)
    #7 0x76fe2cd3756d 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, 

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