From 676f373ea8dded91381523a3021182d6f3733dca Mon Sep 17 00:00:00 2001 From: miyakoshi Date: Thu, 24 Oct 2024 23:38:32 +0000 Subject: [PATCH 1/6] jazzy support --- CARET_trace/CMakeLists.txt | 5 + .../include/caret_trace/data_container.hpp | 56 ++++++++++ CARET_trace/include/caret_trace/tp.h | 47 ++++++++ CARET_trace/src/data_container.cpp | 48 ++++++++ CARET_trace/src/hooked_trace_points.cpp | 105 ++++++++++++++++++ CARET_trace/src/ros_trace_points.cpp | 26 +++++ CARET_trace/src/trace_node.cpp | 5 + CARET_trace/test/test_data_container.cpp | 11 ++ CARET_trace/test/test_scenario.cpp | 21 ++++ 9 files changed, 324 insertions(+) diff --git a/CARET_trace/CMakeLists.txt b/CARET_trace/CMakeLists.txt index 5be85efd..ee259ba8 100644 --- a/CARET_trace/CMakeLists.txt +++ b/CARET_trace/CMakeLists.txt @@ -35,6 +35,11 @@ find_package(rmw_fastrtps_shared_cpp REQUIRED) find_package(LTTngUST REQUIRED) find_package(caret_msgs REQUIRED) +set(ENV_VAR_VALUE $ENV{ROS_DISTRO}) +if(ENV_VAR_VALUE STREQUAL "jazzy") + add_compile_definitions(ROS_DISTRO_JAZZY) +endif() + add_library(caret SHARED src/ros_trace_points.cpp src/hooked_trace_points.cpp diff --git a/CARET_trace/include/caret_trace/data_container.hpp b/CARET_trace/include/caret_trace/data_container.hpp index 4898fe7d..fa0f0f88 100644 --- a/CARET_trace/include/caret_trace/data_container.hpp +++ b/CARET_trace/include/caret_trace/data_container.hpp @@ -75,6 +75,14 @@ class DataContainer : public DataContainerInterface using ConstructStaticExecutor = ContainerTraits; + /// @brief ContainerTraits for callback_group_to_executor_entity_collector trace points. + using CallbackGroupToExecutorEntityCollector = + ContainerTraits; + + /// @brief ContainerTraits for executor_entity_collector_to_executor trace points. + using ExecutorEntityCollectorToExecutor = + ContainerTraits; + /// @brief ContainerTraits for rcl_init trace points. using RclInit = ContainerTraits; @@ -145,6 +153,10 @@ class DataContainer : public DataContainerInterface /// @param callback_group_add_timer Data instance for callback_group_add_timer trace point. /// @param construct_executor Data instance for construct_executor trace point. /// @param construct_static_executor Data instance for construct_static_executor trace point. + /// @param callback_group_to_executor_entity_collector Data instance for + /// callback_group_to_executor_entity_collector trace point. + /// @param executor_entity_collector_to_executor Data instance for + /// executor_entity_collector_to_executor trace point. /// @param rcl_client_init Data instance for rcl_client_init trace point. /// @param rcl_init Data instance for rcl_init trace point. /// @param rcl_node_init Data instance for rcl_node_init trace point. @@ -170,6 +182,10 @@ class DataContainer : public DataContainerInterface std::shared_ptr callback_group_add_timer, std::shared_ptr construct_executor, std::shared_ptr construct_static_executor, +#ifdef ROS_DISTRO_JAZZY + std::shared_ptr callback_group_to_executor_entity_collector, + std::shared_ptr executor_entity_collector_to_executor, +#endif std::shared_ptr rcl_client_init, std::shared_ptr rcl_init, std::shared_ptr rcl_node_init, std::shared_ptr rcl_publisher_init, @@ -281,6 +297,28 @@ class DataContainer : public DataContainerInterface return construct_static_executor_->store(args...); } + /// @brief Store data for callback_group_to_executor_entity_collector trace points. + /// @tparam ...Args Data types to be stored. + /// @param ...args Data to be stored. + /// @return True, data was stored to pending set. + /// @return False, data was stored to set. + template + bool store_callback_group_to_executor_entity_collector(Args... args) + { + return callback_group_to_executor_entity_collector_->store(args...); + } + + /// @brief Store data for executor_entity_collector_to_executor trace points. + /// @tparam ...Args Data types to be stored. + /// @param ...args Data to be stored. + /// @return True, data was stored to pending set. + /// @return False, data was stored to set. + template + bool store_executor_entity_collector_to_executor(Args... args) + { + return executor_entity_collector_to_executor_->store(args...); + } + /// @brief Store data for rcl_node_init trace points. /// @tparam ...Args Data types to be stored. /// @param ...args Data to be stored. @@ -500,6 +538,14 @@ class DataContainer : public DataContainerInterface /// @param record recording function. void assign_construct_static_executor(ConstructStaticExecutor::StdFuncT record); + /// @brief Assign recording function for callback_group_to_executor_entity_collector trace points. + /// @param record recording function. + void assign_callback_group_to_executor_entity_collector(CallbackGroupToExecutorEntityCollector::StdFuncT record); + + /// @brief Assign recording function for executor_entity_collector_to_executor trace points. + /// @param record recording function. + void assign_executor_entity_collector_to_executor(ExecutorEntityCollectorToExecutor::StdFuncT record); + /// @brief Assign recording function for rcl_client_init trace points. /// @param record recording function. void assign_rcl_client_init(RclClientInit::StdFuncT record); @@ -609,6 +655,14 @@ class DataContainer : public DataContainerInterface /// @return True if function is assigned, false otherwise. bool is_assigned_construct_static_executor() const; + /// @brief Check whether recording function for callback_group_to_executor_entity_collector trace point is assigned. + /// @return True if function is assigned, false otherwise. + bool is_assigned_callback_group_to_executor_entity_collector() const; + + /// @brief Check whether recording function for executor_entity_collector_to_executor trace point is assigned. + /// @return True if function is assigned, false otherwise. + bool is_assigned_executor_entity_collector_to_executor() const; + /// @brief Check whether recording function for rcl_client_init trace point is assigned. /// @return True if function is assigned, false otherwise. bool is_assigned_rcl_client_init() const; @@ -697,6 +751,8 @@ class DataContainer : public DataContainerInterface std::shared_ptr callback_group_add_timer_; std::shared_ptr construct_executor_; std::shared_ptr construct_static_executor_; + std::shared_ptr callback_group_to_executor_entity_collector_; + std::shared_ptr executor_entity_collector_to_executor_; std::shared_ptr rcl_client_init_; std::shared_ptr rcl_init_; std::shared_ptr rcl_node_init_; diff --git a/CARET_trace/include/caret_trace/tp.h b/CARET_trace/include/caret_trace/tp.h index 3d028f87..6a81ae91 100644 --- a/CARET_trace/include/caret_trace/tp.h +++ b/CARET_trace/include/caret_trace/tp.h @@ -43,6 +43,22 @@ TRACEPOINT_EVENT( ) ) +#ifdef ROS_DISTRO_JAZZY +TRACEPOINT_EVENT( + TRACEPOINT_PROVIDER, + dds_write, + TP_ARGS( + const void *, rmw_publisher_handle_arg, + const void *, message_arg, + int64_t, init_timestamp_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, rmw_publisher_handle, rmw_publisher_handle_arg) + ctf_integer_hex(const void *, message, message_arg) + ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) + ) +) +#else TRACEPOINT_EVENT( TRACEPOINT_PROVIDER, dds_write, @@ -53,6 +69,7 @@ TRACEPOINT_EVENT( ctf_integer_hex(const void *, message, message_arg) ) ) +#endif TRACEPOINT_EVENT( TRACEPOINT_PROVIDER, @@ -93,6 +110,36 @@ TRACEPOINT_EVENT( ) ) +TRACEPOINT_EVENT( + TRACEPOINT_PROVIDER, + callback_group_to_executor_entity_collector, + TP_ARGS( + const void *, executor_entities_collector_addr_arg, + const void *, callback_group_addr_arg, + int64_t, init_timestamp_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, executor_entities_collector_addr, executor_entities_collector_addr_arg) + ctf_integer_hex(const void *, callback_group_addr, callback_group_addr_arg) + ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) + ) +) + +TRACEPOINT_EVENT( + TRACEPOINT_PROVIDER, + executor_entity_collector_to_executor, + TP_ARGS( + const void *, executor_addr_arg, + const void *, executor_entities_collector_addr_arg, + int64_t, init_timestamp_arg + ), + TP_FIELDS( + ctf_integer_hex(const void *, executor_addr, executor_addr_arg) + ctf_integer_hex(const void *, executor_entities_collector_addr, executor_entities_collector_addr_arg) + ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) + ) +) + TRACEPOINT_EVENT( TRACEPOINT_PROVIDER, construct_executor, diff --git a/CARET_trace/src/data_container.cpp b/CARET_trace/src/data_container.cpp index e7b834cc..52818c3a 100644 --- a/CARET_trace/src/data_container.cpp +++ b/CARET_trace/src/data_container.cpp @@ -37,6 +37,10 @@ DataContainer::DataContainer() std::make_shared("callback_group_add_timer"), std::make_shared("construct_executor"), std::make_shared("construct_static_executor"), +#ifdef ROS_DISTRO_JAZZY + std::make_shared("callback_group_to_executor_entity_collector"), + std::make_shared("executor_entity_collector_to_executor"), +#endif std::make_shared("rcl_client_init"), std::make_shared("rcl_init"), std::make_shared("rcl_node_init"), @@ -66,6 +70,10 @@ DataContainer::DataContainer( std::shared_ptr callback_group_add_timer, std::shared_ptr construct_executor, std::shared_ptr construct_static_executor, +#ifdef ROS_DISTRO_JAZZY + std::shared_ptr callback_group_to_executor_entity_collector, + std::shared_ptr executor_entity_collector_to_executor, +#endif std::shared_ptr rcl_client_init, std::shared_ptr rcl_init, std::shared_ptr rcl_node_init, std::shared_ptr rcl_publisher_init, @@ -90,6 +98,10 @@ DataContainer::DataContainer( callback_group_add_timer_(callback_group_add_timer), construct_executor_(construct_executor), construct_static_executor_(construct_static_executor), +#ifdef ROS_DISTRO_JAZZY + callback_group_to_executor_entity_collector_(callback_group_to_executor_entity_collector), + executor_entity_collector_to_executor_(executor_entity_collector_to_executor), +#endif rcl_client_init_(rcl_client_init), rcl_init_(rcl_init), rcl_node_init_(rcl_node_init), @@ -134,6 +146,14 @@ DataContainer::DataContainer( if (construct_static_executor_) { recordable_data.emplace_back(construct_static_executor_); } +#ifdef ROS_DISTRO_JAZZY + if (callback_group_to_executor_entity_collector_) { + recordable_data.emplace_back(callback_group_to_executor_entity_collector_); + } + if (executor_entity_collector_to_executor_) { + recordable_data.emplace_back(executor_entity_collector_to_executor_); + } +#endif if (rcl_client_init_) { recordable_data.emplace_back(rcl_client_init_); } @@ -273,6 +293,20 @@ void DataContainer::assign_construct_static_executor(ConstructStaticExecutor::St construct_static_executor_->assign(record); } +#ifdef ROS_DISTRO_JAZZY +void DataContainer::assign_callback_group_to_executor_entity_collector(CallbackGroupToExecutorEntityCollector::StdFuncT record) +{ + assert(callback_group_to_executor_entity_collector_.get() != nullptr); + callback_group_to_executor_entity_collector_->assign(record); +} + +void DataContainer::assign_executor_entity_collector_to_executor(ExecutorEntityCollectorToExecutor::StdFuncT record) +{ + assert(executor_entity_collector_to_executor_.get() != nullptr); + executor_entity_collector_to_executor_->assign(record); +} +#endif + void DataContainer::assign_rcl_client_init(RclClientInit::StdFuncT record) { assert(rcl_client_init_.get() != nullptr); @@ -432,6 +466,20 @@ bool DataContainer::is_assigned_construct_static_executor() const return callback_group_add_client_->is_assigned(); } +#ifdef ROS_DISTRO_JAZZY +bool DataContainer::is_assigned_callback_group_to_executor_entity_collector() const +{ + assert(callback_group_to_executor_entity_collector_.get() != nullptr); + return callback_group_to_executor_entity_collector_->is_assigned(); +} + +bool DataContainer::is_assigned_executor_entity_collector_to_executor() const +{ + assert(executor_entity_collector_to_executor_.get() != nullptr); + return executor_entity_collector_to_executor_->is_assigned(); +} +#endif + bool DataContainer::is_assigned_rcl_client_init() const { assert(rcl_client_init_.get() != nullptr); diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index b9723ec5..22eaf627 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -132,6 +132,11 @@ class StaticSingleThreadedExecutorPublic : public rclcpp::Executor std::vector get_automatically_added_callback_groups_from_nodes() override; +#ifdef ROS_DISTRO_JAZZY + RCLCPP_PUBLIC + rclcpp::executors::ExecutorEntitiesCollector * get_collector_() { return &collector_; } +#endif + // protected: RCLCPP_PUBLIC bool execute_ready_executables(bool spin_once = false); @@ -145,12 +150,27 @@ class StaticSingleThreadedExecutorPublic : public rclcpp::Executor // private: // RCLCPP_DISABLE_COPY(StaticSingleThreadedExecutor) +#ifndef ROS_DISTRO_JAZZY StaticExecutorEntitiesCollector::SharedPtr entities_collector_; +#endif +}; + +#ifdef ROS_DISTRO_JAZZY +class ExecutorPublic : public rclcpp::Executor +{ +public: + RCLCPP_PUBLIC + rclcpp::executors::ExecutorEntitiesCollector * get_collector_() { return &collector_; } }; +#endif } // namespace executors } // namespace rclcpp +using CallbackGroupCollection = std::set< + rclcpp::CallbackGroup::WeakPtr, + std::owner_less>; + extern "C" { // Get symbols from the DDS shared library // The dds-related-symbol, which is set by an environment variable, cannot be obtained by dlsym. @@ -322,6 +342,87 @@ rmw_ret_t rmw_publish_serialized_message( return ret; } +#ifdef ROS_DISTRO_JAZZY +// rclcpp::executors::ExecutorEntitiesCollector::add_callback_group_to_collection( +// std::shared_ptr, +// std::set, +// std::owner_less >, +// std::allocator > >&) +void SYMBOL_CONCAT_2( + _ZN6rclcpp9executors25ExecutorEntitiesCollector32add_callback_group_to_collectionESt10shared_, + ptrINS_13CallbackGroupEERSt3setISt8weak_ptrIS3_ESt10owner_lessIS7_ESaIS7_EE)( + void * obj, const rclcpp::CallbackGroup::SharedPtr group_ptr, + const CallbackGroupCollection & collection) +{ + static void * orig_func = dlsym(RTLD_NEXT, __func__); + static auto & context = Singleton::get_instance(); + static auto & clock = context.get_clock(); + static auto & data_container = context.get_data_container(); + static auto record = [](const void * obj, const void * group_addr, int64_t init_time) { + tracepoint(TRACEPOINT_PROVIDER, callback_group_to_executor_entity_collector, obj, group_addr, init_time); + +#ifdef DEBUG_OUTPUT + //std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << std::endl; +#endif + }; + auto now = clock.now(); + using functionT = void (*)(void *, const rclcpp::CallbackGroup::SharedPtr, const CallbackGroupCollection &); + ((functionT)orig_func)(obj, group_ptr, collection); + auto group_addr = static_cast(group_ptr.get()); + + if (!context.get_controller().is_allowed_process()) { + return; + } + + const std::string executor_type_name = "single_threaded_executor"; + + if (!data_container.is_assigned_callback_group_to_executor_entity_collector()) { + data_container.assign_callback_group_to_executor_entity_collector(record); + } + + data_container.store_callback_group_to_executor_entity_collector(obj, group_addr, now); + record(obj, group_addr, now); +} + +// rclcpp::Executor::Executor(rclcpp::ExecutorOptions const&) +void _ZN6rclcpp8ExecutorC2ERKNS_15ExecutorOptionsE( + void * obj, const void * option) +{ + static void * orig_func = dlsym(RTLD_NEXT, __func__); + static auto & context = Singleton::get_instance(); + static auto & clock = context.get_clock(); + static auto & data_container = context.get_data_container(); + static auto record = [](const void * obj, const void * collector_ptr, int64_t init_time) { + tracepoint(TRACEPOINT_PROVIDER, executor_entity_collector_to_executor, obj, collector_ptr, init_time); + +#ifdef DEBUG_OUTPUT + std::cerr << "executor_entity_collector_to_executor," << obj << "," << collector_ptr << std::endl; +#endif + }; + + using ExecutorPublic = rclcpp::executors::ExecutorPublic; + auto exec_ptr = reinterpret_cast(obj); + auto collector_ptr = exec_ptr->get_collector_(); + + auto now = clock.now(); + using functionT = void (*)(void *, const void *); + ((functionT)orig_func)(obj, option); + + if (!context.get_controller().is_allowed_process()) { + return; + } + + const std::string executor_type_name = "single_threaded_executor"; + + if (!data_container.is_assigned_executor_entity_collector_to_executor()) { + data_container.assign_executor_entity_collector_to_executor(record); + } + + data_container.store_executor_entity_collector_to_executor(obj, collector_ptr, now); + record(obj, collector_ptr, now); +} +#endif + // rclcpp::executors::SingleThreadedExecutor::SingleThreadedExecutor(rclcpp::ExecutorOptions const&) void _ZN6rclcpp9executors22SingleThreadedExecutorC1ERKNS_15ExecutorOptionsE( void * obj, const void * option) @@ -431,7 +532,11 @@ void _ZN6rclcpp9executors28StaticSingleThreadedExecutorC1ERKNS_15ExecutorOptions data_container.assign_construct_static_executor(record); } +#ifdef ROS_DISTRO_JAZZY + auto entities_collector_ptr = exec_ptr->get_collector_(); +#else auto entities_collector_ptr = static_cast(exec_ptr->entities_collector_.get()); +#endif data_container.store_construct_static_executor( obj, entities_collector_ptr, "static_single_threaded_executor", now); record(obj, entities_collector_ptr, "static_single_threaded_executor", now); diff --git a/CARET_trace/src/ros_trace_points.cpp b/CARET_trace/src/ros_trace_points.cpp index d5f618be..26f192d1 100644 --- a/CARET_trace/src/ros_trace_points.cpp +++ b/CARET_trace/src/ros_trace_points.cpp @@ -1220,6 +1220,31 @@ void ros_trace_rmw_take( } } +#ifdef ROS_DISTRO_JAZZY +void ros_trace_rmw_publish( + const void * rmw_publisher_handle, + const void * message, + int64_t init_timestamp +) +{ + static auto & context = Singleton::get_instance(); + static auto & controller = context.get_controller(); + + if (!controller.is_allowed_process()) { + return; + } + + if (trace_filter_is_rcl_publish_recorded) { + tracepoint(TRACEPOINT_PROVIDER, dds_write, rmw_publisher_handle, message, init_timestamp); +#ifdef DEBUG_OUTPUT + std::cerr << "rmw_publish," << + rmw_publisher_handle << "," << + message << "," << + init_timestamp << "," << std::endl; +#endif + } +} +#else void ros_trace_rmw_publish( const void * message ) @@ -1239,6 +1264,7 @@ void ros_trace_rmw_publish( #endif } } +#endif void ros_trace_rmw_publisher_init( const void * rmw_publisher_handle, diff --git a/CARET_trace/src/trace_node.cpp b/CARET_trace/src/trace_node.cpp index eef89d0c..ccf068b1 100644 --- a/CARET_trace/src/trace_node.cpp +++ b/CARET_trace/src/trace_node.cpp @@ -136,7 +136,12 @@ void TraceNode::run_timer() debug("Started recording timer ."); timer_->reset(); if (execute_timer_on_run_) { +#ifdef ROS_DISTRO_JAZZY + auto timer_call_info_ = std::make_shared(); + timer_->execute_callback(timer_call_info_); +#else timer_->execute_callback(); +#endif } } diff --git a/CARET_trace/test/test_data_container.cpp b/CARET_trace/test/test_data_container.cpp index 1498e623..99e13266 100644 --- a/CARET_trace/test/test_data_container.cpp +++ b/CARET_trace/test/test_data_container.cpp @@ -24,10 +24,17 @@ TEST(DataContainerTest, EmptyCase) { +#ifdef ROS_DISTRO_JAZZY + DataContainer container( + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr); +#else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); +#endif bool finished; finished = container.record(); EXPECT_TRUE(finished); @@ -75,6 +82,10 @@ TEST(DataContainerTest, TracePoints) "callback_group_add_timer", "construct_executor", "construct_static_executor", +#ifdef ROS_DISTRO_JAZZY + "callback_group_to_executor_entity_collector", + "executor_entity_collector_to_executor", +#endif "rcl_client_init", "rcl_init", "rcl_node_init", diff --git a/CARET_trace/test/test_scenario.cpp b/CARET_trace/test/test_scenario.cpp index 3660f67d..499607a6 100644 --- a/CARET_trace/test/test_scenario.cpp +++ b/CARET_trace/test/test_scenario.cpp @@ -56,10 +56,17 @@ TEST(ScenarioTest, TestSingleThread) { auto keys = std::make_shared("rcl_init"); +#ifdef ROS_DISTRO_JAZZY + DataContainer container( + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr); +#else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); +#endif MockFunction rcl_init_mock; container.assign_rcl_init(rcl_init_mock.AsStdFunction()); @@ -84,10 +91,17 @@ TEST(ScenarioTest, TestMultiThread) { auto keys = std::make_shared("rcl_init"); +#ifdef ROS_DISTRO_JAZZY + DataContainer container( + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr); +#else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); +#endif MockFunction rcl_init_mock; container.assign_rcl_init(rcl_init_mock.AsStdFunction()); @@ -220,10 +234,17 @@ TEST(ScenarioTest, Record) auto keys = std::make_shared("rcl_init"); +#ifdef ROS_DISTRO_JAZZY + auto container = std::make_shared( + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr); +#else auto container = std::make_shared( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); +#endif Context context; bool pending; From 4ded1eb854873159bb7a777da9fcf2168725fed5 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 25 Oct 2024 00:02:44 +0000 Subject: [PATCH 2/6] ci(pre-commit): autofix --- .../include/caret_trace/data_container.hpp | 23 +++++++++++-------- CARET_trace/src/data_container.cpp | 15 ++++++++---- CARET_trace/src/hooked_trace_points.cpp | 23 +++++++++++-------- CARET_trace/test/test_data_container.cpp | 4 ++-- CARET_trace/test/test_scenario.cpp | 12 +++++----- 5 files changed, 45 insertions(+), 32 deletions(-) diff --git a/CARET_trace/include/caret_trace/data_container.hpp b/CARET_trace/include/caret_trace/data_container.hpp index fa0f0f88..c65907d3 100644 --- a/CARET_trace/include/caret_trace/data_container.hpp +++ b/CARET_trace/include/caret_trace/data_container.hpp @@ -80,8 +80,7 @@ class DataContainer : public DataContainerInterface ContainerTraits; /// @brief ContainerTraits for executor_entity_collector_to_executor trace points. - using ExecutorEntityCollectorToExecutor = - ContainerTraits; + using ExecutorEntityCollectorToExecutor = ContainerTraits; /// @brief ContainerTraits for rcl_init trace points. using RclInit = ContainerTraits; @@ -153,7 +152,7 @@ class DataContainer : public DataContainerInterface /// @param callback_group_add_timer Data instance for callback_group_add_timer trace point. /// @param construct_executor Data instance for construct_executor trace point. /// @param construct_static_executor Data instance for construct_static_executor trace point. - /// @param callback_group_to_executor_entity_collector Data instance for + /// @param callback_group_to_executor_entity_collector Data instance for /// callback_group_to_executor_entity_collector trace point. /// @param executor_entity_collector_to_executor Data instance for /// executor_entity_collector_to_executor trace point. @@ -183,7 +182,8 @@ class DataContainer : public DataContainerInterface std::shared_ptr construct_executor, std::shared_ptr construct_static_executor, #ifdef ROS_DISTRO_JAZZY - std::shared_ptr callback_group_to_executor_entity_collector, + std::shared_ptr + callback_group_to_executor_entity_collector, std::shared_ptr executor_entity_collector_to_executor, #endif std::shared_ptr rcl_client_init, std::shared_ptr rcl_init, @@ -540,11 +540,13 @@ class DataContainer : public DataContainerInterface /// @brief Assign recording function for callback_group_to_executor_entity_collector trace points. /// @param record recording function. - void assign_callback_group_to_executor_entity_collector(CallbackGroupToExecutorEntityCollector::StdFuncT record); + void assign_callback_group_to_executor_entity_collector( + CallbackGroupToExecutorEntityCollector::StdFuncT record); /// @brief Assign recording function for executor_entity_collector_to_executor trace points. /// @param record recording function. - void assign_executor_entity_collector_to_executor(ExecutorEntityCollectorToExecutor::StdFuncT record); + void assign_executor_entity_collector_to_executor( + ExecutorEntityCollectorToExecutor::StdFuncT record); /// @brief Assign recording function for rcl_client_init trace points. /// @param record recording function. @@ -655,11 +657,13 @@ class DataContainer : public DataContainerInterface /// @return True if function is assigned, false otherwise. bool is_assigned_construct_static_executor() const; - /// @brief Check whether recording function for callback_group_to_executor_entity_collector trace point is assigned. + /// @brief Check whether recording function for callback_group_to_executor_entity_collector trace + /// point is assigned. /// @return True if function is assigned, false otherwise. bool is_assigned_callback_group_to_executor_entity_collector() const; - /// @brief Check whether recording function for executor_entity_collector_to_executor trace point is assigned. + /// @brief Check whether recording function for executor_entity_collector_to_executor trace point + /// is assigned. /// @return True if function is assigned, false otherwise. bool is_assigned_executor_entity_collector_to_executor() const; @@ -751,7 +755,8 @@ class DataContainer : public DataContainerInterface std::shared_ptr callback_group_add_timer_; std::shared_ptr construct_executor_; std::shared_ptr construct_static_executor_; - std::shared_ptr callback_group_to_executor_entity_collector_; + std::shared_ptr + callback_group_to_executor_entity_collector_; std::shared_ptr executor_entity_collector_to_executor_; std::shared_ptr rcl_client_init_; std::shared_ptr rcl_init_; diff --git a/CARET_trace/src/data_container.cpp b/CARET_trace/src/data_container.cpp index 52818c3a..6d82e571 100644 --- a/CARET_trace/src/data_container.cpp +++ b/CARET_trace/src/data_container.cpp @@ -38,8 +38,10 @@ DataContainer::DataContainer() std::make_shared("construct_executor"), std::make_shared("construct_static_executor"), #ifdef ROS_DISTRO_JAZZY - std::make_shared("callback_group_to_executor_entity_collector"), - std::make_shared("executor_entity_collector_to_executor"), + std::make_shared( + "callback_group_to_executor_entity_collector"), + std::make_shared( + "executor_entity_collector_to_executor"), #endif std::make_shared("rcl_client_init"), std::make_shared("rcl_init"), @@ -71,7 +73,8 @@ DataContainer::DataContainer( std::shared_ptr construct_executor, std::shared_ptr construct_static_executor, #ifdef ROS_DISTRO_JAZZY - std::shared_ptr callback_group_to_executor_entity_collector, + std::shared_ptr + callback_group_to_executor_entity_collector, std::shared_ptr executor_entity_collector_to_executor, #endif std::shared_ptr rcl_client_init, std::shared_ptr rcl_init, @@ -294,13 +297,15 @@ void DataContainer::assign_construct_static_executor(ConstructStaticExecutor::St } #ifdef ROS_DISTRO_JAZZY -void DataContainer::assign_callback_group_to_executor_entity_collector(CallbackGroupToExecutorEntityCollector::StdFuncT record) +void DataContainer::assign_callback_group_to_executor_entity_collector( + CallbackGroupToExecutorEntityCollector::StdFuncT record) { assert(callback_group_to_executor_entity_collector_.get() != nullptr); callback_group_to_executor_entity_collector_->assign(record); } -void DataContainer::assign_executor_entity_collector_to_executor(ExecutorEntityCollectorToExecutor::StdFuncT record) +void DataContainer::assign_executor_entity_collector_to_executor( + ExecutorEntityCollectorToExecutor::StdFuncT record) { assert(executor_entity_collector_to_executor_.get() != nullptr); executor_entity_collector_to_executor_->assign(record); diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index 22eaf627..44b4b531 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -167,9 +167,8 @@ class ExecutorPublic : public rclcpp::Executor } // namespace executors } // namespace rclcpp -using CallbackGroupCollection = std::set< - rclcpp::CallbackGroup::WeakPtr, - std::owner_less>; +using CallbackGroupCollection = + std::set>; extern "C" { // Get symbols from the DDS shared library @@ -359,14 +358,17 @@ void SYMBOL_CONCAT_2( static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * group_addr, int64_t init_time) { - tracepoint(TRACEPOINT_PROVIDER, callback_group_to_executor_entity_collector, obj, group_addr, init_time); + tracepoint( + TRACEPOINT_PROVIDER, callback_group_to_executor_entity_collector, obj, group_addr, init_time); #ifdef DEBUG_OUTPUT - //std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << std::endl; + // std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << + // std::endl; #endif }; auto now = clock.now(); - using functionT = void (*)(void *, const rclcpp::CallbackGroup::SharedPtr, const CallbackGroupCollection &); + using functionT = + void (*)(void *, const rclcpp::CallbackGroup::SharedPtr, const CallbackGroupCollection &); ((functionT)orig_func)(obj, group_ptr, collection); auto group_addr = static_cast(group_ptr.get()); @@ -385,18 +387,19 @@ void SYMBOL_CONCAT_2( } // rclcpp::Executor::Executor(rclcpp::ExecutorOptions const&) -void _ZN6rclcpp8ExecutorC2ERKNS_15ExecutorOptionsE( - void * obj, const void * option) +void _ZN6rclcpp8ExecutorC2ERKNS_15ExecutorOptionsE(void * obj, const void * option) { static void * orig_func = dlsym(RTLD_NEXT, __func__); static auto & context = Singleton::get_instance(); static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * collector_ptr, int64_t init_time) { - tracepoint(TRACEPOINT_PROVIDER, executor_entity_collector_to_executor, obj, collector_ptr, init_time); + tracepoint( + TRACEPOINT_PROVIDER, executor_entity_collector_to_executor, obj, collector_ptr, init_time); #ifdef DEBUG_OUTPUT - std::cerr << "executor_entity_collector_to_executor," << obj << "," << collector_ptr << std::endl; + std::cerr << "executor_entity_collector_to_executor," << obj << "," << collector_ptr + << std::endl; #endif }; diff --git a/CARET_trace/test/test_data_container.cpp b/CARET_trace/test/test_data_container.cpp index 99e13266..b3520520 100644 --- a/CARET_trace/test/test_data_container.cpp +++ b/CARET_trace/test/test_data_container.cpp @@ -26,9 +26,9 @@ TEST(DataContainerTest, EmptyCase) { #ifdef ROS_DISTRO_JAZZY DataContainer container( - nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, - nullptr, nullptr, nullptr, nullptr, nullptr); + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); #else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, diff --git a/CARET_trace/test/test_scenario.cpp b/CARET_trace/test/test_scenario.cpp index 499607a6..0cae7cab 100644 --- a/CARET_trace/test/test_scenario.cpp +++ b/CARET_trace/test/test_scenario.cpp @@ -58,9 +58,9 @@ TEST(ScenarioTest, TestSingleThread) #ifdef ROS_DISTRO_JAZZY DataContainer container( - nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, - nullptr, nullptr, nullptr, nullptr); + nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); #else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, @@ -93,9 +93,9 @@ TEST(ScenarioTest, TestMultiThread) #ifdef ROS_DISTRO_JAZZY DataContainer container( - nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, - nullptr, nullptr, nullptr, nullptr); + nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); #else DataContainer container( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, @@ -236,9 +236,9 @@ TEST(ScenarioTest, Record) #ifdef ROS_DISTRO_JAZZY auto container = std::make_shared( - nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, - nullptr, nullptr, nullptr, nullptr); + nullptr, keys, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, + nullptr, nullptr, nullptr, nullptr, nullptr, nullptr); #else auto container = std::make_shared( nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, nullptr, keys, nullptr, From cfa0c267f49e2a6a21b07ec1a294428ea4c61788 Mon Sep 17 00:00:00 2001 From: miyakoshi Date: Tue, 12 Nov 2024 04:14:31 +0000 Subject: [PATCH 3/6] review results reflected --- CARET_trace/include/caret_trace/data_container.hpp | 10 ++++++++++ CARET_trace/include/caret_trace/tp.h | 4 ++-- CARET_trace/src/hooked_trace_points.cpp | 8 ++------ CARET_trace/src/ros_trace_points.cpp | 6 +++--- 4 files changed, 17 insertions(+), 11 deletions(-) diff --git a/CARET_trace/include/caret_trace/data_container.hpp b/CARET_trace/include/caret_trace/data_container.hpp index c65907d3..c97d03e2 100644 --- a/CARET_trace/include/caret_trace/data_container.hpp +++ b/CARET_trace/include/caret_trace/data_container.hpp @@ -152,10 +152,12 @@ class DataContainer : public DataContainerInterface /// @param callback_group_add_timer Data instance for callback_group_add_timer trace point. /// @param construct_executor Data instance for construct_executor trace point. /// @param construct_static_executor Data instance for construct_static_executor trace point. +#ifdef ROS_DISTRO_JAZZY /// @param callback_group_to_executor_entity_collector Data instance for /// callback_group_to_executor_entity_collector trace point. /// @param executor_entity_collector_to_executor Data instance for /// executor_entity_collector_to_executor trace point. +#endif /// @param rcl_client_init Data instance for rcl_client_init trace point. /// @param rcl_init Data instance for rcl_init trace point. /// @param rcl_node_init Data instance for rcl_node_init trace point. @@ -297,6 +299,7 @@ class DataContainer : public DataContainerInterface return construct_static_executor_->store(args...); } +#ifdef ROS_DISTRO_JAZZY /// @brief Store data for callback_group_to_executor_entity_collector trace points. /// @tparam ...Args Data types to be stored. /// @param ...args Data to be stored. @@ -318,6 +321,7 @@ class DataContainer : public DataContainerInterface { return executor_entity_collector_to_executor_->store(args...); } +#endif /// @brief Store data for rcl_node_init trace points. /// @tparam ...Args Data types to be stored. @@ -538,6 +542,7 @@ class DataContainer : public DataContainerInterface /// @param record recording function. void assign_construct_static_executor(ConstructStaticExecutor::StdFuncT record); +#ifdef ROS_DISTRO_JAZZY /// @brief Assign recording function for callback_group_to_executor_entity_collector trace points. /// @param record recording function. void assign_callback_group_to_executor_entity_collector( @@ -547,6 +552,7 @@ class DataContainer : public DataContainerInterface /// @param record recording function. void assign_executor_entity_collector_to_executor( ExecutorEntityCollectorToExecutor::StdFuncT record); +#endif /// @brief Assign recording function for rcl_client_init trace points. /// @param record recording function. @@ -657,6 +663,7 @@ class DataContainer : public DataContainerInterface /// @return True if function is assigned, false otherwise. bool is_assigned_construct_static_executor() const; +#ifdef ROS_DISTRO_JAZZY /// @brief Check whether recording function for callback_group_to_executor_entity_collector trace /// point is assigned. /// @return True if function is assigned, false otherwise. @@ -666,6 +673,7 @@ class DataContainer : public DataContainerInterface /// is assigned. /// @return True if function is assigned, false otherwise. bool is_assigned_executor_entity_collector_to_executor() const; +#endif /// @brief Check whether recording function for rcl_client_init trace point is assigned. /// @return True if function is assigned, false otherwise. @@ -755,9 +763,11 @@ class DataContainer : public DataContainerInterface std::shared_ptr callback_group_add_timer_; std::shared_ptr construct_executor_; std::shared_ptr construct_static_executor_; +#ifdef ROS_DISTRO_JAZZY std::shared_ptr callback_group_to_executor_entity_collector_; std::shared_ptr executor_entity_collector_to_executor_; +#endif std::shared_ptr rcl_client_init_; std::shared_ptr rcl_init_; std::shared_ptr rcl_node_init_; diff --git a/CARET_trace/include/caret_trace/tp.h b/CARET_trace/include/caret_trace/tp.h index 6a81ae91..711faf8e 100644 --- a/CARET_trace/include/caret_trace/tp.h +++ b/CARET_trace/include/caret_trace/tp.h @@ -50,12 +50,12 @@ TRACEPOINT_EVENT( TP_ARGS( const void *, rmw_publisher_handle_arg, const void *, message_arg, - int64_t, init_timestamp_arg + int64_t, timestamp_arg ), TP_FIELDS( ctf_integer_hex(const void *, rmw_publisher_handle, rmw_publisher_handle_arg) ctf_integer_hex(const void *, message, message_arg) - ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) + ctf_integer(const int64_t, timestamp, timestamp_arg) ) ) #else diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index 44b4b531..e4543f66 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -362,8 +362,8 @@ void SYMBOL_CONCAT_2( TRACEPOINT_PROVIDER, callback_group_to_executor_entity_collector, obj, group_addr, init_time); #ifdef DEBUG_OUTPUT - // std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << - // std::endl; + std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << + std::endl; #endif }; auto now = clock.now(); @@ -376,8 +376,6 @@ void SYMBOL_CONCAT_2( return; } - const std::string executor_type_name = "single_threaded_executor"; - if (!data_container.is_assigned_callback_group_to_executor_entity_collector()) { data_container.assign_callback_group_to_executor_entity_collector(record); } @@ -415,8 +413,6 @@ void _ZN6rclcpp8ExecutorC2ERKNS_15ExecutorOptionsE(void * obj, const void * opti return; } - const std::string executor_type_name = "single_threaded_executor"; - if (!data_container.is_assigned_executor_entity_collector_to_executor()) { data_container.assign_executor_entity_collector_to_executor(record); } diff --git a/CARET_trace/src/ros_trace_points.cpp b/CARET_trace/src/ros_trace_points.cpp index 26f192d1..bc684311 100644 --- a/CARET_trace/src/ros_trace_points.cpp +++ b/CARET_trace/src/ros_trace_points.cpp @@ -1224,7 +1224,7 @@ void ros_trace_rmw_take( void ros_trace_rmw_publish( const void * rmw_publisher_handle, const void * message, - int64_t init_timestamp + int64_t timestamp ) { static auto & context = Singleton::get_instance(); @@ -1235,12 +1235,12 @@ void ros_trace_rmw_publish( } if (trace_filter_is_rcl_publish_recorded) { - tracepoint(TRACEPOINT_PROVIDER, dds_write, rmw_publisher_handle, message, init_timestamp); + tracepoint(TRACEPOINT_PROVIDER, dds_write, rmw_publisher_handle, message, timestamp); #ifdef DEBUG_OUTPUT std::cerr << "rmw_publish," << rmw_publisher_handle << "," << message << "," << - init_timestamp << "," << std::endl; + timestamp << "," << std::endl; #endif } } From 8d5f9edcab118c5da249759643bc47988372d1a5 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Tue, 12 Nov 2024 04:15:30 +0000 Subject: [PATCH 4/6] ci(pre-commit): autofix --- CARET_trace/src/hooked_trace_points.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index e4543f66..c199b38f 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -362,8 +362,8 @@ void SYMBOL_CONCAT_2( TRACEPOINT_PROVIDER, callback_group_to_executor_entity_collector, obj, group_addr, init_time); #ifdef DEBUG_OUTPUT - std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr << - std::endl; + std::cerr << "callback_group_to_executor_entity_collector," << obj << "," << group_addr + << std::endl; #endif }; auto now = clock.now(); From 0b0d691e5ea8a89080e7f29cef61b4192671ce44 Mon Sep 17 00:00:00 2001 From: miyakoshi Date: Wed, 13 Nov 2024 01:15:36 +0000 Subject: [PATCH 5/6] ci error compatible --- CARET_trace/include/caret_trace/tp.h | 6 ++++-- CARET_trace/src/hooked_trace_points.cpp | 1 - 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/CARET_trace/include/caret_trace/tp.h b/CARET_trace/include/caret_trace/tp.h index 711faf8e..f8054617 100644 --- a/CARET_trace/include/caret_trace/tp.h +++ b/CARET_trace/include/caret_trace/tp.h @@ -119,7 +119,8 @@ TRACEPOINT_EVENT( int64_t, init_timestamp_arg ), TP_FIELDS( - ctf_integer_hex(const void *, executor_entities_collector_addr, executor_entities_collector_addr_arg) + ctf_integer_hex(const void *, executor_entities_collector_addr, + executor_entities_collector_addr_arg) ctf_integer_hex(const void *, callback_group_addr, callback_group_addr_arg) ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) ) @@ -135,7 +136,8 @@ TRACEPOINT_EVENT( ), TP_FIELDS( ctf_integer_hex(const void *, executor_addr, executor_addr_arg) - ctf_integer_hex(const void *, executor_entities_collector_addr, executor_entities_collector_addr_arg) + ctf_integer_hex(const void *, executor_entities_collector_addr, + executor_entities_collector_addr_arg) ctf_integer(const int64_t, init_timestamp, init_timestamp_arg) ) ) diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index c199b38f..42c15629 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -595,7 +595,6 @@ void SYMBOL_CONCAT_3( } auto group_addr_ = const_cast(group_addr); - auto node_addr_ = const_cast(node_addr); std::string group_type_name = "unknown"; auto group_type = group_ptr->type(); From c99c18c33e773bb4c1ef8abf859fe68090fe6ea2 Mon Sep 17 00:00:00 2001 From: miyakoshi Date: Wed, 13 Nov 2024 01:37:59 +0000 Subject: [PATCH 6/6] ci error compatible again --- CARET_trace/src/hooked_trace_points.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index 42c15629..c8188296 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -582,7 +582,6 @@ void SYMBOL_CONCAT_3( void *, rclcpp::CallbackGroup::SharedPtr, rclcpp::node_interfaces::NodeBaseInterface::SharedPtr, const void *, bool); auto group_addr = static_cast(group_ptr.get()); - auto node_addr = static_cast(node_ptr.get()); ((functionT)orig_func)(obj, group_ptr, node_ptr, weak_groups_to_nodes, notify);