From cfa0c267f49e2a6a21b07ec1a294428ea4c61788 Mon Sep 17 00:00:00 2001 From: miyakoshi Date: Tue, 12 Nov 2024 04:14:31 +0000 Subject: [PATCH] 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 } }