diff --git a/CARET_trace/include/caret_trace/data_container.hpp b/CARET_trace/include/caret_trace/data_container.hpp index c9bbb723..45c16a1d 100644 --- a/CARET_trace/include/caret_trace/data_container.hpp +++ b/CARET_trace/include/caret_trace/data_container.hpp @@ -36,7 +36,7 @@ class DataContainerInterface /// @return True if record has finished, false otherwise. virtual bool record(uint64_t loop_count = 1) = 0; - /// @brief transitionto recording state. + /// @brief transition to recording state. virtual void start_recording() = 0; /// @brief Reset recording state. @@ -48,11 +48,12 @@ class DataContainer : public DataContainerInterface { public: /// @brief for add_callback_group trace points. - using AddCallbackGroup = ContainerTraits; + using AddCallbackGroup = + ContainerTraits; /// @brief ContainerTraits for add_callback_group_static_executor trace points. using AddCallbackGroupStaticExecutor = - ContainerTraits; + ContainerTraits; /// @brief ContainerTraits for callback_group_add_client trace points. using CallbackGroupAddClient = ContainerTraits; diff --git a/CARET_trace/include/caret_trace/tracing_controller.hpp b/CARET_trace/include/caret_trace/tracing_controller.hpp index 6284ff65..345f68ba 100644 --- a/CARET_trace/include/caret_trace/tracing_controller.hpp +++ b/CARET_trace/include/caret_trace/tracing_controller.hpp @@ -21,7 +21,7 @@ /// @brief Classes that implement trace filtering functions such as CARET_SELECT_NODES. /// @details Reads the environment variables CARET_SELECT_NODES, -/// CARET_IGNORE_NODES, CARET_SELECT_TOPICS, and CARET_IGNORE_TOPICS. +/// CARET_IGNORE_NODES, CARET_SELECT_TOPICS, CARET_IGNORE_TOPICS, and CARET_IGNORE_NODES. /// Tracepoints related to the specified node name or topic name are filtered /// so that they are not recorded by LTTng. /// If both SELECT and IGNORE are specified, SELECT takes priority. @@ -53,19 +53,19 @@ class TracingController const void * node_handle, const void * rmw_subscription_handle, std::string topic_name); /// @brief Register binding information for rclcpp_subscription_init tracepoint hook. - /// @param subscription_handle Address of the subscription handle. /// @param subscription Address of subscription instance. - void add_subscription(const void * subscription_handle, const void * subscription); + /// @param subscription_handle Address of the subscription handle. + void add_subscription(const void * subscription, const void * subscription_handle); /// @brief Register binding information for rclcpp_subscription_callback_added tracepoint hook. - /// @param subscription Address of subscription instance. /// @param callback Address of callback instance. - void add_subscription_callback(const void * subscription, const void * callback); + /// @param subscription Address of subscription instance. + void add_subscription_callback(const void * callback, const void * subscription); /// @brief Register binding information for rclcpp_timer_link_node tracepoint hook. - /// @param node_handle Address of the node handle. /// @param timer_handle Address of the timer handle. - void add_timer_handle(const void * node_handle, const void * timer_handle); + /// @param node_handle Address of the node handle. + void add_timer_handle(const void * timer_handle, const void * node_handle); /// @brief Register topic name for ros_trace_rcl_publisher_init /// @param node_handle Address of the node handle. @@ -75,9 +75,9 @@ class TracingController const void * node_handle, const void * publisher_handle, std::string topic_name); /// @brief Register binding information for rclcpp_timer_callback_added tracepoint hook. + /// @param callback Address of timer callback instance. /// @param timer_handle Address of the timer handle. - /// @param callback Address of callback instance. - void add_timer_callback(const void * timer_handle, const void * callback); + void add_timer_callback(const void * timer_callback, const void * timer_handle); /// @brief Register binding information for rclcpp_buffer_to_ipb tracepoint. /// @param buffer Address of the buffer. @@ -89,6 +89,26 @@ class TracingController /// @param subscription Address of the subscription instance. void add_ipb(const void * ipb, const void * subscription); + /// @brief Register binding information for rcl_lifecycle_state_machine_init tracepoint. + /// @param state_machine Address of the lifecycle state machine. + /// @param node_handle Address of the node handle. + void add_state_machine(const void * state_machine, const void * node_handle); + + /// @brief Register binding information for rclcpp_service_callback_added tracepoint. + /// @param service_handle Address of the service handle. + /// @param node_handle Address of the node handle. + void add_service_handle(const void * service_handle, const void * node_handle); + + /// @brief Register binding information for rcl_client_init tracepoint. + /// @param client_handle Address of the client handle. + /// @param node_handle Address of the node handle. + void add_client_handle(const void * client_handle, const void * node_handle); + + /// @brief Registering acceptable and unacceptable message. + /// @param message Address of the intra original message. + /// @param is_allowed True is enabled, false otherwise. + void add_allowed_messages(const void * message, bool is_allowed); + /// @brief Check if trace point is a enabled callback /// @param callback /// @param callback Address of callback instance. @@ -105,6 +125,13 @@ class TracingController /// @return True if the publisher is enabled, false otherwise. bool is_allowed_publisher_handle(const void * publisher_handle); + /// @brief Check if trace point is a enabled publisher and set to allowed message map + /// @param publisher_handle Address of the publisher handle. + /// @param message Address of the message. + /// @return True if the publisher is enabled, false otherwise. + bool is_allowed_publisher_handle_and_add_message( + const void * publisher_handle, const void * message); + /// @brief Check if trace point is a enabled subscription /// @param subscription_handle Address of the subscription handle. /// @return True if the subscription is enabled, false otherwise. @@ -124,6 +151,36 @@ class TracingController /// @return True if the process is enabled, false otherwise. bool is_allowed_process(); + /// @brief Check if trace point is a enabled timer handle + /// @param timer_handle Address of the timer handle. + /// @return True if the timer_handle is enabled, false otherwise. + bool is_allowed_timer_handle(const void * timer_handle); + + /// @brief Check if trace point is a enabled state machine + /// @param state_machine Address of the lifecycle state machine. + /// @return True if the state_machine is enabled, false otherwise. + bool is_allowed_state_machine(const void * state_machine); + + /// @brief Check if trace point is a enabled ipb + /// @param buffer Address of the intra-process buffer. + /// @return True if the ipb is enabled, false otherwise. + bool is_allowed_ipb(const void * ipb); + + /// @brief Check if trace point is a enabled service handle + /// @param service_handle Address of the service handle. + /// @return True if the service_handle is enabled, false otherwise. + bool is_allowed_service_handle(const void * service_handle); + + /// @brief Check if trace point is a enabled client handle + /// @param client_handle Address of the client handle. + /// @return True if the client_handle is enabled, false otherwise. + bool is_allowed_client_handle(const void * client_handle); + + /// @brief Check if trace point is a enabled publisher + /// @param message Address of the message. + /// @return True if the message is enabled, false otherwise. + bool is_allowed_message(const void * message); + private: void debug(std::string message) const; void info(std::string message) const; @@ -149,6 +206,7 @@ class TracingController std::unordered_map subscription_handle_to_topic_names_; std::unordered_map subscription_to_subscription_handles_; std::unordered_map callback_to_subscriptions_; + std::unordered_map subscription_to_callbacks_; std::unordered_map rmw_subscription_handle_to_node_handles_; std::unordered_map rmw_subscription_handle_to_topic_names_; @@ -158,6 +216,7 @@ class TracingController std::unordered_map callback_to_timer_handles_; std::unordered_map timer_handle_to_node_handles_; std::unordered_map allowed_callbacks_; + std::unordered_map allowed_timer_handles_; std::unordered_map publisher_handle_to_node_handles_; std::unordered_map publisher_handle_to_topic_names_; @@ -166,6 +225,17 @@ class TracingController std::unordered_map buffer_to_ipbs_; std::unordered_map ipb_to_subscriptions_; std::unordered_map allowed_buffers_; + std::unordered_map allowed_ipbs_; + + std::unordered_map state_machine_to_node_handles_; + std::unordered_map allowed_state_machines_; + + std::unordered_map service_handle_to_node_handles_; + std::unordered_map allowed_service_handles_; + std::unordered_map client_handle_to_node_handles_; + std::unordered_map allowed_client_handles_; + + std::unordered_map allowed_messages_; }; #endif // CARET_TRACE__TRACING_CONTROLLER_HPP_ diff --git a/CARET_trace/src/hooked_trace_points.cpp b/CARET_trace/src/hooked_trace_points.cpp index 68ab4477..9530c88c 100644 --- a/CARET_trace/src/hooked_trace_points.cpp +++ b/CARET_trace/src/hooked_trace_points.cpp @@ -262,11 +262,12 @@ int dds_writecdr_impl(void * wr, void * xp, struct ddsi_serdata * dinp, bool flu return dds_return; } - if (context.is_recording_allowed()) { + if (context.is_recording_allowed() && trace_filter_is_rcl_publish_recorded) { tracepoint( TRACEPOINT_PROVIDER, dds_bind_addr_to_stamp, serialized_message_addr, dinp->timestamp.v); #ifdef DEBUG_OUTPUT - std::cerr << "dds_bind_addr_to_stamp," << data << "," << tstamp << std::endl; + std::cerr << "dds_bind_addr_to_stamp," << serialized_message_addr << "," << dinp->timestamp.v + << std::endl; #endif } return dds_return; @@ -278,7 +279,6 @@ void _ZN8eprosima8fastrtps4rtps13WriterHistory13set_fragmentsEPNS1_13CacheChange void * obj, eprosima::fastrtps::rtps::CacheChange_t * change) { static auto & context = Singleton::get_instance(); - using functionT = void (*)(void *, eprosima::fastrtps::rtps::CacheChange_t *); if (FASTDDS::SET_FRAGMENTS == nullptr) { update_dds_function_addr(); @@ -289,7 +289,7 @@ void _ZN8eprosima8fastrtps4rtps13WriterHistory13set_fragmentsEPNS1_13CacheChange return; } - if (context.is_recording_allowed()) { + if (context.is_recording_allowed() && trace_filter_is_rcl_publish_recorded) { tracepoint( TRACEPOINT_PROVIDER, dds_bind_addr_to_stamp, nullptr, change->sourceTimestamp.to_ns()); #ifdef DEBUG_OUTPUT @@ -421,7 +421,7 @@ void _ZN6rclcpp9executors28StaticSingleThreadedExecutorC1ERKNS_15ExecutorOptions } auto entities_collector_ptr = static_cast(exec_ptr->entities_collector_.get()); - data_container.store_add_callback_group_static_executor( + 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); } @@ -439,28 +439,35 @@ void SYMBOL_CONCAT_3( _ZN6rclcpp8Executor25add_callback_group_to_map, ESt10shared_ptrINS_13CallbackGroupEES1_INS_15node_interfaces17NodeBaseInterface, EERSt3mapISt8weak_ptrIS2_ES8_IS5_ESt10owner_lessIS9_ESaISt4pairIKS9_SA_EEEb)( - void * obj, rclcpp::CallbackGroup::SharedPtr group_ptr, const void * node_ptr, - const void * weak_groups_to_nodes, bool notify) + void * obj, rclcpp::CallbackGroup::SharedPtr group_ptr, + rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, const void * weak_groups_to_nodes, + bool notify) { 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, const char * group_type_name, int64_t init_time) { - tracepoint( - TRACEPOINT_PROVIDER, add_callback_group, obj, group_addr, group_type_name, init_time); + static auto record = []( + const void * obj, const void * group_addr, const char * group_type_name, + const void * node_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_node(node_handle)) { + return; + } + tracepoint( + TRACEPOINT_PROVIDER, add_callback_group, obj, group_addr, group_type_name, init_time); #ifdef DEBUG_OUTPUT - std::cerr << "add_callback_group," << obj << "," << group_addr << "," << group_type_name - << std::endl; + std::cerr << "add_callback_group," << obj << "," << group_addr << "," << group_type_name + << std::endl; #endif - }; + }; auto now = clock.now(); - using functionT = - void (*)(void *, rclcpp::CallbackGroup::SharedPtr, const void *, const void *, bool); + using functionT = void (*)( + 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); @@ -474,8 +481,8 @@ void SYMBOL_CONCAT_3( static KeysSet recorded_args; - auto node_ptr_ = const_cast(node_ptr); 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(); @@ -485,11 +492,13 @@ void SYMBOL_CONCAT_3( group_type_name = "reentrant"; } - data_container.store_add_callback_group(obj, group_addr, group_type_name.c_str(), now); - if (!recorded_args.has(obj, group_addr_, node_ptr_)) { - recorded_args.insert(obj, group_addr_, node_ptr_); + auto node_handle = static_cast(node_ptr->get_rcl_node_handle()); + data_container.store_add_callback_group( + obj, group_addr, group_type_name.c_str(), node_handle, now); + if (!recorded_args.has(obj, group_addr_, node_addr_)) { + recorded_args.insert(obj, group_addr_, node_addr_); - record(obj, group_addr, group_type_name.c_str(), now); + record(obj, group_addr, group_type_name.c_str(), node_handle, now); } } @@ -508,17 +517,21 @@ bool SYMBOL_CONCAT_3( 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, const char * group_type_name, int64_t init_time) { - tracepoint( - TRACEPOINT_PROVIDER, add_callback_group_static_executor, obj, group_addr, group_type_name, - init_time); + static auto record = []( + const void * obj, const void * group_addr, const char * group_type_name, + const void * node_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_node(node_handle)) { + return; + } + tracepoint( + TRACEPOINT_PROVIDER, add_callback_group_static_executor, obj, group_addr, group_type_name, + init_time); #ifdef DEBUG_OUTPUT - std::cerr << "add_callback_group_static_executor," << obj << "," << group_addr << "," - << group_type_name << std::endl; + std::cerr << "add_callback_group_static_executor," << obj << "," << group_addr << "," + << group_type_name << std::endl; #endif - }; + }; auto now = clock.now(); auto group_addr = static_cast(group_ptr.get()); @@ -540,9 +553,10 @@ bool SYMBOL_CONCAT_3( data_container.assign_add_callback_group_static_executor(record); } + auto node_handle = node_ptr->get_rcl_node_handle(); data_container.store_add_callback_group_static_executor( - obj, group_addr, group_type_name.c_str(), now); - record(obj, group_addr, group_type_name.c_str(), now); + obj, group_addr, group_type_name.c_str(), node_handle, now); + record(obj, group_addr, group_type_name.c_str(), node_handle, now); return ret; } @@ -558,6 +572,9 @@ void _ZN6rclcpp13CallbackGroup9add_timerESt10shared_ptrINS_9TimerBaseEE( static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * timer_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_timer_handle(timer_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, callback_group_add_timer, obj, timer_handle, init_time); #ifdef DEBUG_OUTPUT @@ -591,6 +608,9 @@ void _ZN6rclcpp13CallbackGroup16add_subscriptionESt10shared_ptrINS_16Subscriptio static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * subscription_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_subscription_handle(subscription_handle)) { + return; + } tracepoint( TRACEPOINT_PROVIDER, callback_group_add_subscription, obj, subscription_handle, init_time); @@ -627,6 +647,9 @@ void _ZN6rclcpp13CallbackGroup11add_serviceESt10shared_ptrINS_11ServiceBaseEE( static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * service_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_service_handle(service_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, callback_group_add_service, obj, service_handle, init_time); #ifdef DEBUG_OUTPUT @@ -660,6 +683,9 @@ void _ZN6rclcpp13CallbackGroup10add_clientESt10shared_ptrINS_10ClientBaseEE( static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * obj, const void * client_handle, int64_t init_time) { + if (!context.get_controller().is_allowed_client_handle(client_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, callback_group_add_client, obj, client_handle, init_time); #ifdef DEBUG_OUTPUT diff --git a/CARET_trace/src/ros_trace_points.cpp b/CARET_trace/src/ros_trace_points.cpp index c323bbde..7d91346f 100644 --- a/CARET_trace/src/ros_trace_points.cpp +++ b/CARET_trace/src/ros_trace_points.cpp @@ -378,7 +378,7 @@ void ros_trace_rclcpp_subscription_init( auto now = clock.now(); check_and_run_trace_node(); - controller.add_subscription(subscription_handle, subscription); + controller.add_subscription(subscription, subscription_handle); if (!data_container.is_assigned_rclcpp_subscription_init()) { data_container.assign_rclcpp_subscription_init(record); @@ -422,7 +422,7 @@ void ros_trace_rclcpp_subscription_callback_added( auto now = clock.now(); check_and_run_trace_node(); - controller.add_subscription_callback(subscription, callback); + controller.add_subscription_callback(callback, subscription); if (!data_container.is_assigned_rclcpp_subscription_callback_added()) { data_container.assign_rclcpp_subscription_callback_added(record); @@ -445,9 +445,9 @@ void ros_trace_rclcpp_timer_callback_added(const void * timer_handle, const void const void * callback, int64_t init_time ) { - if (!controller.is_allowed_callback(callback)) { - return; - } + if (!controller.is_allowed_timer_handle(timer_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_timer_callback_added, timer_handle, callback, init_time); #ifdef DEBUG_OUTPUT std::cerr << "rclcpp_timer_callback_added," << @@ -463,7 +463,7 @@ void ros_trace_rclcpp_timer_callback_added(const void * timer_handle, const void auto now = clock.now(); check_and_run_trace_node(); - controller.add_timer_callback(timer_handle, callback); + controller.add_timer_callback(callback, timer_handle); if (!data_container.is_assigned_rclcpp_timer_callback_added()) { data_container.assign_rclcpp_timer_callback_added(record); @@ -484,9 +484,9 @@ void ros_trace_rclcpp_timer_link_node(const void * timer_handle, const void * no const void * node_handle, int64_t init_time ) { - if (!controller.is_allowed_node(node_handle)) { - return; - } + if (!controller.is_allowed_node(node_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_timer_link_node, timer_handle, node_handle, init_time); #ifdef DEBUG_OUTPUT std::cerr << "rclcpp_timer_link_node," << @@ -502,7 +502,7 @@ void ros_trace_rclcpp_timer_link_node(const void * timer_handle, const void * no auto now = clock.now(); check_and_run_trace_node(); - controller.add_timer_handle(node_handle, timer_handle); + controller.add_timer_handle(timer_handle, node_handle); if (!data_container.is_assigned_rclcpp_timer_link_node()) { data_container.assign_rclcpp_timer_link_node(record); @@ -660,9 +660,8 @@ void ros_trace_rclcpp_intra_publish( return; } - if (controller.is_allowed_publisher_handle(publisher_handle) && - context.is_recording_allowed()) - { + if (controller.is_allowed_publisher_handle_and_add_message(publisher_handle, message) && + context.is_recording_allowed()) { ((functionT) orig_func)(publisher_handle, message); #ifdef DEBUG_OUTPUT std::cerr << "rclcpp_intra_publish," << @@ -686,6 +685,9 @@ void ros_trace_rcl_timer_init( } static auto record = [](const void * timer_handle, int64_t period, int64_t init_time) { + if (!context.get_controller().is_allowed_timer_handle(timer_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rcl_timer_init, timer_handle, period, init_time); }; @@ -737,7 +739,6 @@ void ros_trace_rcl_init( #endif } - void ros_trace_rcl_publisher_init( const void * publisher_handle, const void * node_handle, @@ -758,6 +759,9 @@ void ros_trace_rcl_publisher_init( const size_t queue_depth, int64_t init_time ) { + if (!controller.is_allowed_publisher_handle(publisher_handle)){ + return; + } tracepoint(TRACEPOINT_PROVIDER, rcl_publisher_init, publisher_handle, node_handle, rmw_publisher_handle, topic_name, queue_depth, init_time); }; @@ -838,6 +842,9 @@ void ros_trace_rcl_service_init( const void * rmw_service_handle, const char * service_name, int64_t init_time) { + if (!context.get_controller().is_allowed_service_handle(service_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rcl_service_init, service_handle, node_handle, rmw_service_handle, service_name, init_time); @@ -856,6 +863,8 @@ void ros_trace_rcl_service_init( auto now = clock.now(); + context.get_controller().add_service_handle(service_handle, node_handle); + if (!data_container.is_assigned_rcl_service_init()) { data_container.assign_rcl_service_init(record); } @@ -875,6 +884,9 @@ void ros_trace_rclcpp_service_callback_added( static auto & clock = context.get_clock(); static auto & data_container = context.get_data_container(); static auto record = [](const void * service_handle, const char * callback, int64_t init_time) { + if (!context.get_controller().is_allowed_service_handle(service_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_service_callback_added, service_handle, callback, init_time); @@ -915,6 +927,9 @@ void ros_trace_rcl_client_init( const void * rmw_client_handle, const char * service_name, int64_t init_time) { + if (!context.get_controller().is_allowed_client_handle(client_handle)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rcl_client_init, client_handle, node_handle, rmw_client_handle, service_name, init_time); @@ -933,6 +948,8 @@ void ros_trace_rcl_client_init( auto now = clock.now(); + context.get_controller().add_client_handle(client_handle, node_handle); + if (!data_container.is_assigned_rcl_client_init()) { data_container.assign_rcl_client_init(record); } @@ -1050,14 +1067,15 @@ void ros_trace_rcl_lifecycle_state_machine_init( const void * node_handle, const void * state_machine, int64_t init_time) { - tracepoint(TRACEPOINT_PROVIDER, rcl_lifecycle_state_machine_init, - node_handle, state_machine, init_time); - + if (context.get_controller().is_allowed_state_machine(state_machine)) { + tracepoint(TRACEPOINT_PROVIDER, rcl_lifecycle_state_machine_init, + node_handle, state_machine, init_time); #ifdef DEBUG_OUTPUT std::cerr << "rcl_lifecycle_state_machine_init," << node_handle << "," << state_machine << std::endl; #endif + } }; if (!context.get_controller().is_allowed_process()) { @@ -1066,6 +1084,8 @@ void ros_trace_rcl_lifecycle_state_machine_init( auto now = clock.now(); + context.get_controller().add_state_machine(state_machine, node_handle); + check_and_run_trace_node(); record(node_handle, state_machine, now); @@ -1084,9 +1104,11 @@ void ros_trace_rcl_lifecycle_transition( return; } - if (context.is_recording_allowed()) { + if (context.get_controller().is_allowed_state_machine(state_machine) && + context.is_recording_allowed()) { ((functionT) orig_func)(state_machine, start_label, goal_label); + #ifdef DEBUG_OUTPUT std::cerr << "rcl_lifecycle_transition," << state_machine << "," << @@ -1101,14 +1123,15 @@ void ros_trace_message_construct( const void * constructed_message) { static auto & context = Singleton::get_instance(); + static auto & controller = context.get_controller(); static void * orig_func = dlsym(RTLD_NEXT, __func__); using functionT = void (*)(const void *, const void *); - if (!context.get_controller().is_allowed_process()) { + if (!controller.is_allowed_process()) { return; } - if (context.is_recording_allowed()) { + if (controller.is_allowed_message(original_message) && context.is_recording_allowed()) { ((functionT) orig_func)(original_message, constructed_message); #ifdef DEBUG_OUTPUT @@ -1262,6 +1285,9 @@ void ros_trace_rclcpp_buffer_to_ipb( const void * ipb, int64_t init_timestamp ){ + if (!controller.is_allowed_buffer(buffer)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_buffer_to_ipb, buffer, ipb, init_timestamp); @@ -1303,6 +1329,9 @@ void ros_trace_rclcpp_ipb_to_subscription( const void * subscription, int64_t init_timestamp ){ + if (!controller.is_allowed_ipb(ipb)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_ipb_to_subscription, ipb, subscription, init_timestamp); @@ -1338,6 +1367,9 @@ void ros_trace_rclcpp_construct_ring_buffer( uint64_t capacity, int64_t init_timestamp ){ + if (!context.get_controller().is_allowed_buffer(buffer)) { + return; + } tracepoint(TRACEPOINT_PROVIDER, rclcpp_construct_ring_buffer, buffer, capacity, init_timestamp); diff --git a/CARET_trace/src/tracing_controller.cpp b/CARET_trace/src/tracing_controller.cpp index 2af0fdc4..f5396ea6 100644 --- a/CARET_trace/src/tracing_controller.cpp +++ b/CARET_trace/src/tracing_controller.cpp @@ -116,6 +116,15 @@ void check_condition_set(std::unordered_set conditions, bool use_lo } } +bool is_iron_or_later() +{ + const char * ros_distro = std::getenv("ROS_DISTRO"); + if (ros_distro[0] >= "iron"[0]) { + return true; + } + return false; +} + TracingController::TracingController(bool use_log) : selected_node_names_(get_env_vars(SELECT_NODES_ENV_NAME)), ignored_node_names_(get_env_vars(IGNORE_NODES_ENV_NAME)), @@ -192,24 +201,28 @@ bool TracingController::is_allowed_callback(const void * callback) auto node_name = to_node_name(callback); auto topic_name = to_topic_name(callback); + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_callbacks_[callback] = true; + return true; + } + if (select_enabled_) { auto is_selected_topic = partial_match(selected_topic_names_, topic_name); auto is_selected_node = partial_match(selected_node_names_, node_name); if (selected_topic_names_.size() > 0 && is_selected_topic) { - allowed_callbacks_.insert(std::make_pair(callback, true)); + allowed_callbacks_[callback] = true; return true; } if (selected_node_names_.size() > 0 && is_selected_node) { - allowed_callbacks_.insert(std::make_pair(callback, true)); + allowed_callbacks_[callback] = true; return true; } if (selected_node_names_.size() == 0 && topic_name == "") { // allow timer callback - allowed_callbacks_.insert(std::make_pair(callback, true)); + allowed_callbacks_[callback] = true; return true; } - - allowed_callbacks_.insert(std::make_pair(callback, false)); + allowed_callbacks_[callback] = false; return false; } if (ignore_enabled_) { @@ -217,17 +230,17 @@ bool TracingController::is_allowed_callback(const void * callback) auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); if (ignored_node_names_.size() > 0 && is_ignored_node) { - allowed_callbacks_.insert(std::make_pair(callback, false)); + allowed_callbacks_[callback] = false; return false; } if (ignored_topic_names_.size() > 0 && is_ignored_topic) { - allowed_callbacks_.insert(std::make_pair(callback, false)); + allowed_callbacks_[callback] = false; return false; } - allowed_callbacks_.insert(std::make_pair(callback, true)); + allowed_callbacks_[callback] = true; return true; } - allowed_callbacks_.insert(std::make_pair(callback, true)); + allowed_callbacks_[callback] = true; return true; } } @@ -236,6 +249,9 @@ bool TracingController::is_allowed_node(const void * node_handle) { std::lock_guard lock(mutex_); auto node_name = node_handle_to_node_names_[node_handle]; + if (node_name.size() == 0) { + return true; + } if (select_enabled_ && selected_node_names_.size() > 0) { auto is_selected_node = partial_match(selected_node_names_, node_name); return is_selected_node; @@ -253,6 +269,10 @@ bool TracingController::is_allowed_subscription_handle(const void * subscription auto node_name = node_handle_to_node_names_[node_handle]; auto topic_name = subscription_handle_to_topic_names_[subscription_handle]; + if (node_name.size() == 0 || topic_name.size() == 0) { + return true; + } + if (select_enabled_) { auto is_selected_node = partial_match(selected_node_names_, node_name); auto is_selected_topic = partial_match(selected_topic_names_, topic_name); @@ -296,20 +316,24 @@ bool TracingController::is_allowed_rmw_subscription_handle(const void * rmw_subs auto node_name = node_handle_to_node_names_[node_handle]; auto topic_name = rmw_subscription_handle_to_topic_names_[rmw_subscription_handle]; + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_rmw_subscription_handles_[rmw_subscription_handle] = true; + return true; + } + if (select_enabled_) { auto is_selected_topic = partial_match(selected_topic_names_, topic_name); auto is_selected_node = partial_match(selected_node_names_, node_name); if (selected_topic_names_.size() > 0 && is_selected_topic) { - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, true)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = true; return true; } if (selected_node_names_.size() > 0 && is_selected_node) { - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, true)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = true; return true; } - - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, false)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = false; return false; } if (ignore_enabled_) { @@ -317,17 +341,17 @@ bool TracingController::is_allowed_rmw_subscription_handle(const void * rmw_subs auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); if (ignored_node_names_.size() > 0 && is_ignored_node) { - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, false)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = false; return false; } if (ignored_topic_names_.size() > 0 && is_ignored_topic) { - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, false)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = false; return false; } - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, true)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = true; return true; } - allowed_rmw_subscription_handles_.insert(std::make_pair(rmw_subscription_handle, true)); + allowed_rmw_subscription_handles_[rmw_subscription_handle] = true; return true; } } @@ -347,44 +371,117 @@ bool TracingController::is_allowed_publisher_handle(const void * publisher_handl auto node_handle = publisher_handle_to_node_handles_[publisher_handle]; auto node_name = node_handle_to_node_names_[node_handle]; auto topic_name = publisher_handle_to_topic_names_[publisher_handle]; - auto is_unregistered_publisher_handle = (node_name == ""); - if (is_unregistered_publisher_handle) { - allowed_publishers_.insert(std::make_pair(publisher_handle, false)); - return false; + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_publishers_[publisher_handle] = true; + if (is_iron_or_later()) { + // omit "/rosout" output. (after iron version) + return false; + } + return true; } if (select_enabled_) { auto is_selected_node = partial_match(selected_node_names_, node_name); auto is_selected_topic = partial_match(selected_topic_names_, topic_name); + if (is_selected_topic && selected_topic_names_.size() > 0) { + allowed_publishers_[publisher_handle] = true; + return true; + } if (is_selected_node && selected_node_names_.size() > 0) { - allowed_publishers_.insert(std::make_pair(publisher_handle, true)); + allowed_publishers_[publisher_handle] = true; return true; } + allowed_publishers_[publisher_handle] = false; + return false; + } else if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); + + if (is_ignored_node && ignored_node_names_.size() > 0) { + allowed_publishers_[publisher_handle] = false; + return false; + } + if (is_ignored_topic && ignored_topic_names_.size() > 0) { + allowed_publishers_[publisher_handle] = false; + return false; + } + allowed_publishers_[publisher_handle] = true; + return true; + } + allowed_publishers_[publisher_handle] = true; + return true; + } +} + +bool TracingController::is_allowed_publisher_handle_and_add_message( + const void * publisher_handle, const void * message) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_publishers_.find(publisher_handle); + if (is_allowed_it != allowed_publishers_.end()) { + add_allowed_messages(message, is_allowed_it->second); + return is_allowed_it->second; + } + } + { + std::lock_guard lock(mutex_); + auto node_handle = publisher_handle_to_node_handles_[publisher_handle]; + auto node_name = node_handle_to_node_names_[node_handle]; + auto topic_name = publisher_handle_to_topic_names_[publisher_handle]; + + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_publishers_[publisher_handle] = true; + if (is_iron_or_later()) { + // omit "/rosout" output. (after iron version) + add_allowed_messages(message, false); + return false; + } + add_allowed_messages(message, true); + return true; + } + + if (select_enabled_) { + auto is_selected_node = partial_match(selected_node_names_, node_name); + auto is_selected_topic = partial_match(selected_topic_names_, topic_name); + if (is_selected_topic && selected_topic_names_.size() > 0) { - allowed_publishers_.insert(std::make_pair(publisher_handle, true)); + allowed_publishers_[publisher_handle] = true; + add_allowed_messages(message, true); return true; } - - allowed_publishers_.insert(std::make_pair(publisher_handle, false)); + if (is_selected_node && selected_node_names_.size() > 0) { + allowed_publishers_[publisher_handle] = true; + add_allowed_messages(message, true); + return true; + } + allowed_publishers_[publisher_handle] = false; + add_allowed_messages(message, false); return false; } else if (ignore_enabled_) { auto is_ignored_node = partial_match(ignored_node_names_, node_name); auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); if (is_ignored_node && ignored_node_names_.size() > 0) { - allowed_publishers_.insert(std::make_pair(publisher_handle, false)); + allowed_publishers_[publisher_handle] = false; + add_allowed_messages(message, false); return false; } if (is_ignored_topic && ignored_topic_names_.size() > 0) { - allowed_publishers_.insert(std::make_pair(publisher_handle, false)); + allowed_publishers_[publisher_handle] = false; + add_allowed_messages(message, false); return false; } - allowed_publishers_.insert(std::make_pair(publisher_handle, true)); + allowed_publishers_[publisher_handle] = true; + add_allowed_messages(message, true); + allowed_messages_[message] = true; return true; } - allowed_publishers_.insert(std::make_pair(publisher_handle, true)); + allowed_publishers_[publisher_handle] = true; + add_allowed_messages(message, true); return true; } } @@ -407,22 +504,31 @@ bool TracingController::is_allowed_buffer(const void * buffer) auto subscription_handle = subscription_to_subscription_handles_[subscription]; auto node_handle = subscription_handle_to_node_handles_[subscription_handle]; auto node_name = node_handle_to_node_names_[node_handle]; + if (node_name.size() == 0) { + auto callback = subscription_to_callbacks_[subscription]; + node_name = to_node_name(callback); + } auto topic_name = subscription_handle_to_topic_names_[subscription_handle]; + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_buffers_[buffer] = true; + return true; + } + if (select_enabled_) { auto is_selected_topic = partial_match(selected_topic_names_, topic_name); auto is_selected_node = partial_match(selected_node_names_, node_name); if (selected_topic_names_.size() > 0 && is_selected_topic) { - allowed_buffers_.insert(std::make_pair(buffer, true)); + allowed_buffers_[buffer] = true; return true; } if (selected_node_names_.size() > 0 && is_selected_node) { - allowed_buffers_.insert(std::make_pair(buffer, true)); + allowed_buffers_[buffer] = true; return true; } - allowed_buffers_.insert(std::make_pair(buffer, false)); + allowed_buffers_[buffer] = false; return false; } if (ignore_enabled_) { @@ -430,17 +536,17 @@ bool TracingController::is_allowed_buffer(const void * buffer) auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); if (ignored_node_names_.size() > 0 && is_ignored_node) { - allowed_buffers_.insert(std::make_pair(buffer, false)); + allowed_buffers_[buffer] = false; return false; } if (ignored_topic_names_.size() > 0 && is_ignored_topic) { - allowed_buffers_.insert(std::make_pair(buffer, false)); + allowed_buffers_[buffer] = false; return false; } - allowed_buffers_.insert(std::make_pair(buffer, true)); + allowed_buffers_[buffer] = true; return true; } - allowed_buffers_.insert(std::make_pair(buffer, true)); + allowed_buffers_[buffer] = true; return true; } } @@ -450,6 +556,260 @@ bool TracingController::is_allowed_process() return !is_ignored_process_; } +bool TracingController::is_allowed_timer_handle(const void * timer_handle) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_timer_handles_.find(timer_handle); + if (is_allowed_it != allowed_timer_handles_.end()) { + return is_allowed_it->second; + } + } + + { + std::shared_lock lock(mutex_); + auto node_handle = timer_handle_to_node_handles_[timer_handle]; + auto node_name = node_handle_to_node_names_[node_handle]; + + if (node_name.size() == 0) { + allowed_timer_handles_[timer_handle] = true; + return true; + } + + if (select_enabled_) { + auto is_selected_node = partial_match(selected_node_names_, node_name); + if (is_selected_node && selected_node_names_.size() > 0) { + allowed_timer_handles_[timer_handle] = true; + return true; + } + allowed_timer_handles_[timer_handle] = false; + return false; + } + if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + if (is_ignored_node && ignored_node_names_.size() > 0) { + allowed_timer_handles_[timer_handle] = false; + return false; + } + allowed_timer_handles_[timer_handle] = true; + return true; + } + allowed_timer_handles_[timer_handle] = true; + return true; + } +} + +bool TracingController::is_allowed_state_machine(const void * state_machine) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_state_machines_.find(state_machine); + if (is_allowed_it != allowed_state_machines_.end()) { + return is_allowed_it->second; + } + } + + { + std::shared_lock lock(mutex_); + auto node_handle = state_machine_to_node_handles_[state_machine]; + auto node_name = node_handle_to_node_names_[node_handle]; + + if (node_name.size() == 0) { + allowed_state_machines_[state_machine] = true; + return true; + } + + if (select_enabled_) { + auto is_selected_node = partial_match(selected_node_names_, node_name); + if (is_selected_node && selected_node_names_.size() > 0) { + allowed_state_machines_[state_machine] = true; + return true; + } + allowed_state_machines_[state_machine] = false; + return false; + } + if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + if (is_ignored_node && ignored_node_names_.size() > 0) { + allowed_state_machines_[state_machine] = false; + return false; + } + allowed_state_machines_[state_machine] = true; + return true; + } + allowed_state_machines_[state_machine] = true; + return true; + } +} + +bool TracingController::is_allowed_ipb(const void * ipb) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_ipbs_.find(ipb); + if (is_allowed_it != allowed_ipbs_.end()) { + return is_allowed_it->second; + } + } + + { + std::lock_guard lock(mutex_); + auto subscription = ipb_to_subscriptions_[ipb]; + auto subscription_handle = subscription_to_subscription_handles_[subscription]; + auto node_handle = subscription_handle_to_node_handles_[subscription_handle]; + auto node_name = node_handle_to_node_names_[node_handle]; + if (node_name.size() == 0) { + auto callback = subscription_to_callbacks_[subscription]; + node_name = to_node_name(callback); + } + auto topic_name = subscription_handle_to_topic_names_[subscription_handle]; + + if (node_name.size() == 0 || topic_name.size() == 0) { + allowed_ipbs_[ipb] = true; + return true; + } + + if (select_enabled_) { + auto is_selected_topic = partial_match(selected_topic_names_, topic_name); + auto is_selected_node = partial_match(selected_node_names_, node_name); + + if (selected_topic_names_.size() > 0 && is_selected_topic) { + allowed_ipbs_[ipb] = true; + return true; + } + if (selected_node_names_.size() > 0 && is_selected_node) { + allowed_ipbs_[ipb] = true; + return true; + } + allowed_ipbs_[ipb] = false; + return false; + } + if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + auto is_ignored_topic = partial_match(ignored_topic_names_, topic_name); + + if (ignored_node_names_.size() > 0 && is_ignored_node) { + allowed_ipbs_[ipb] = false; + return false; + } + if (ignored_topic_names_.size() > 0 && is_ignored_topic) { + allowed_ipbs_[ipb] = false; + return false; + } + allowed_ipbs_[ipb] = true; + return true; + } + allowed_ipbs_[ipb] = true; + return true; + } +} + +bool TracingController::is_allowed_service_handle(const void * service_handle) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_service_handles_.find(service_handle); + if (is_allowed_it != allowed_service_handles_.end()) { + return is_allowed_it->second; + } + } + + { + std::lock_guard lock(mutex_); + auto node_handle = service_handle_to_node_handles_[service_handle]; + auto node_name = node_handle_to_node_names_[node_handle]; + + if (node_name.size() == 0) { + allowed_service_handles_[service_handle] = true; + return true; + } + + if (select_enabled_) { + auto is_selected_node = partial_match(selected_node_names_, node_name); + + if (is_selected_node && selected_node_names_.size() > 0) { + allowed_service_handles_[service_handle] = true; + return true; + } + allowed_service_handles_[service_handle] = false; + return false; + } else if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + + if (is_ignored_node && ignored_node_names_.size() > 0) { + allowed_service_handles_[service_handle] = false; + return false; + } + allowed_service_handles_[service_handle] = true; + return true; + } + allowed_service_handles_[service_handle] = true; + return true; + } +} + +bool TracingController::is_allowed_client_handle(const void * client_handle) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_client_handles_.find(client_handle); + if (is_allowed_it != allowed_client_handles_.end()) { + return is_allowed_it->second; + } + } + + { + std::lock_guard lock(mutex_); + auto node_handle = client_handle_to_node_handles_[client_handle]; + auto node_name = node_handle_to_node_names_[node_handle]; + + if (node_name.size() == 0) { + allowed_client_handles_[client_handle] = true; + return true; + } + + if (select_enabled_) { + auto is_selected_node = partial_match(selected_node_names_, node_name); + + if (is_selected_node && selected_node_names_.size() > 0) { + allowed_client_handles_[client_handle] = true; + return true; + } + allowed_client_handles_[client_handle] = false; + return false; + } else if (ignore_enabled_) { + auto is_ignored_node = partial_match(ignored_node_names_, node_name); + + if (is_ignored_node && ignored_node_names_.size() > 0) { + allowed_client_handles_[client_handle] = false; + return false; + } + allowed_client_handles_[client_handle] = true; + return true; + } + allowed_client_handles_[client_handle] = true; + return true; + } +} + +bool TracingController::is_allowed_message(const void * message) +{ + std::unordered_map::iterator is_allowed_it; + { + std::shared_lock lock(mutex_); + is_allowed_it = allowed_messages_.find(message); + if (is_allowed_it != allowed_messages_.end()) { + return is_allowed_it->second; + } + return true; + } +} + std::string TracingController::to_node_name(const void * callback) { do { @@ -526,72 +886,133 @@ std::string TracingController::to_topic_name(const void * callback) void TracingController::add_node(const void * node_handle, std::string node_name) { std::lock_guard lock(mutex_); - - node_handle_to_node_names_.insert(std::make_pair(node_handle, node_name)); + node_handle_to_node_names_[node_handle] = node_name; + + allowed_rmw_subscription_handles_.clear(); + allowed_publishers_.clear(); + allowed_buffers_.clear(); + allowed_timer_handles_.clear(); + allowed_state_machines_.clear(); + allowed_ipbs_.clear(); + allowed_service_handles_.clear(); + allowed_client_handles_.clear(); + allowed_callbacks_.clear(); } void TracingController::add_subscription_handle( const void * node_handle, const void * subscription_handle, std::string topic_name) { std::lock_guard lock(mutex_); - subscription_handle_to_node_handles_.insert(std::make_pair(subscription_handle, node_handle)); - subscription_handle_to_topic_names_.insert(std::make_pair(subscription_handle, topic_name)); + subscription_handle_to_node_handles_[subscription_handle] = node_handle; + subscription_handle_to_topic_names_[subscription_handle] = topic_name; + + allowed_buffers_.clear(); + allowed_ipbs_.clear(); + allowed_callbacks_.clear(); } void TracingController::add_rmw_subscription_handle( const void * node_handle, const void * rmw_subscription_handle, std::string topic_name) { std::lock_guard lock(mutex_); - rmw_subscription_handle_to_node_handles_.insert( - std::make_pair(rmw_subscription_handle, node_handle)); - rmw_subscription_handle_to_topic_names_.insert( - std::make_pair(rmw_subscription_handle, topic_name)); + rmw_subscription_handle_to_node_handles_[rmw_subscription_handle] = node_handle; + allowed_rmw_subscription_handles_.erase(rmw_subscription_handle); + rmw_subscription_handle_to_topic_names_[rmw_subscription_handle] = topic_name; } void TracingController::add_subscription( - const void * subscription_handle, const void * subscription) + const void * subscription, const void * subscription_handle) { std::lock_guard lock(mutex_); - subscription_to_subscription_handles_.insert(std::make_pair(subscription, subscription_handle)); + subscription_to_subscription_handles_[subscription] = subscription_handle; + + allowed_buffers_.clear(); + allowed_ipbs_.clear(); + allowed_callbacks_.clear(); } -void TracingController::add_subscription_callback(const void * subscription, const void * callback) +void TracingController::add_subscription_callback(const void * callback, const void * subscription) { std::lock_guard lock(mutex_); - callback_to_subscriptions_.insert(std::make_pair(callback, subscription)); + callback_to_subscriptions_[callback] = subscription; + subscription_to_callbacks_[subscription] = callback; + allowed_callbacks_.erase(callback); } -void TracingController::add_timer_handle(const void * node_handle, const void * timer_handle) +void TracingController::add_timer_handle(const void * timer_handle, const void * node_handle) { std::lock_guard lock(mutex_); - timer_handle_to_node_handles_.insert(std::make_pair(node_handle, timer_handle)); + timer_handle_to_node_handles_[timer_handle] = node_handle; + allowed_timer_handles_.erase(timer_handle); + + allowed_callbacks_.clear(); } -void TracingController::add_timer_callback(const void * timer_handle, const void * callback) +void TracingController::add_timer_callback(const void * timer_callback, const void * timer_handle) { std::lock_guard lock(mutex_); - callback_to_timer_handles_.insert(std::make_pair(callback, timer_handle)); + callback_to_timer_handles_[timer_callback] = timer_handle; + allowed_timer_handles_.erase(timer_handle); + allowed_callbacks_.erase(timer_callback); } void TracingController::add_publisher_handle( const void * node_handle, const void * publisher_handle, std::string topic_name) { std::lock_guard lock(mutex_); - publisher_handle_to_node_handles_.insert(std::make_pair(publisher_handle, node_handle)); - publisher_handle_to_topic_names_.insert(std::make_pair(publisher_handle, topic_name)); + publisher_handle_to_node_handles_[publisher_handle] = node_handle; + allowed_publishers_.erase(publisher_handle); + publisher_handle_to_topic_names_[publisher_handle] = topic_name; + + allowed_messages_.clear(); } void TracingController::add_buffer(const void * buffer, const void * ipb) { std::lock_guard lock(mutex_); - buffer_to_ipbs_.insert(std::make_pair(buffer, ipb)); + buffer_to_ipbs_[buffer] = ipb; + allowed_buffers_.erase(buffer); } void TracingController::add_ipb(const void * ipb, const void * subscription) { std::lock_guard lock(mutex_); - ipb_to_subscriptions_.insert(std::make_pair(ipb, subscription)); + ipb_to_subscriptions_[ipb] = subscription; + allowed_ipbs_.erase(ipb); + + allowed_buffers_.clear(); +} + +void TracingController::add_state_machine(const void * state_machine, const void * node_handle) +{ + std::lock_guard lock(mutex_); + state_machine_to_node_handles_[state_machine] = node_handle; + allowed_state_machines_.erase(state_machine); +} + +void TracingController::add_service_handle(const void * service_handle, const void * node_handle) +{ + std::lock_guard lock(mutex_); + service_handle_to_node_handles_[service_handle] = node_handle; + allowed_service_handles_.erase(service_handle); +} + +void TracingController::add_client_handle(const void * client_handle, const void * node_handle) +{ + std::lock_guard lock(mutex_); + client_handle_to_node_handles_[client_handle] = node_handle; + allowed_client_handles_.erase(client_handle); +} + +void TracingController::add_allowed_messages(const void * message, bool is_allowed) +{ + // Be sure to call with "mutex_" locked. + static const int max_sz = 256; + if (allowed_messages_.size() > max_sz) { + allowed_messages_.clear(); + } + allowed_messages_[message] = is_allowed; }