From 19e07b78751a172a189df80ba43361a977527db3 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 10:12:33 -0800 Subject: [PATCH 01/10] Add handling method for new tracepoint and update datra model --- .../tracetools_analysis/data_model/ros.py | 21 ++++++++++++++----- .../tracetools_analysis/processor/ros2.py | 20 +++++++++++++----- 2 files changed, 31 insertions(+), 10 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/data_model/ros.py b/tracetools_analysis/tracetools_analysis/data_model/ros.py index e1064db..45e6fdf 100644 --- a/tracetools_analysis/tracetools_analysis/data_model/ros.py +++ b/tracetools_analysis/tracetools_analysis/data_model/ros.py @@ -56,6 +56,10 @@ class RosDataModel(DataModel): 'topic_name', 'depth']) self.subscriptions.set_index(['subscription_handle'], inplace=True, drop=True) + self.subscriptions_objects = pd.DataFrame(columns=['subscription', + 'timestamp', + 'subscription_handle']) + self.subscriptions_objects.set_index(['subscription'], inplace=True, drop=True) self.services = pd.DataFrame(columns=['service_handle', 'timestamp', 'node_handle', @@ -74,10 +78,10 @@ class RosDataModel(DataModel): 'tid']) self.timers.set_index(['timer_handle'], inplace=True, drop=True) - self.callback_objects = pd.DataFrame(columns=['handle', + self.callback_objects = pd.DataFrame(columns=['reference', 'timestamp', 'callback_object']) - self.callback_objects.set_index(['handle'], inplace=True, drop=True) + self.callback_objects.set_index(['reference'], inplace=True, drop=True) self.callback_symbols = pd.DataFrame(columns=['callback_object', 'timestamp', 'symbol']) @@ -104,11 +108,16 @@ class RosDataModel(DataModel): ) -> None: self.publishers.loc[handle] = [timestamp, node_handle, rmw_handle, topic_name, depth] - def add_subscription( + def add_rcl_subscription( self, handle, timestamp, node_handle, rmw_handle, topic_name, depth ) -> None: self.subscriptions.loc[handle] = [timestamp, node_handle, rmw_handle, topic_name, depth] + def add_rclcpp_subscription( + self, subscription_pointer, timestamp, subscription_handle + ) -> None: + self.subscriptions_objects[subscription_pointer] = [timestamp, subscription_handle] + def add_service( self, handle, timestamp, node_handle, rmw_handle, service_name ) -> None: @@ -125,9 +134,9 @@ class RosDataModel(DataModel): self.timers.loc[handle] = [timestamp, period, tid] def add_callback_object( - self, handle, timestamp, callback_object + self, reference, timestamp, callback_object ) -> None: - self.callback_objects.loc[handle] = [timestamp, callback_object] + self.callback_objects.loc[reference] = [timestamp, callback_object] def add_callback_symbol( self, callback_object, timestamp, symbol @@ -156,6 +165,8 @@ class RosDataModel(DataModel): print() print(f'Subscriptions:\n{self.subscriptions.to_string()}') print() + print(f'Subscription objects:\n{self.subscriptions_objects.to_string()}') + print() print(f'Services:\n{self.services.to_string()}') print() print(f'Clients:\n{self.clients.to_string()}') diff --git a/tracetools_analysis/tracetools_analysis/processor/ros2.py b/tracetools_analysis/tracetools_analysis/processor/ros2.py index 914086b..7b06888 100644 --- a/tracetools_analysis/tracetools_analysis/processor/ros2.py +++ b/tracetools_analysis/tracetools_analysis/processor/ros2.py @@ -43,7 +43,9 @@ class Ros2Handler(EventHandler): 'ros2:rcl_publisher_init': self._handle_rcl_publisher_init, 'ros2:rcl_subscription_init': - self._handle_subscription_init, + self._handle_rcl_subscription_init, + 'ros2:rclcpp_subscription_init': + self._handle_rclcpp_subscription_init, 'ros2:rclcpp_subscription_callback_added': self._handle_rclcpp_subscription_callback_added, 'ros2:rcl_service_init': @@ -108,7 +110,7 @@ class Ros2Handler(EventHandler): depth = get_field(event, 'queue_depth') self.data.add_publisher(handle, timestamp, node_handle, rmw_handle, topic_name, depth) - def _handle_subscription_init( + def _handle_rcl_subscription_init( self, event: Dict, metadata: EventMetadata ) -> None: handle = get_field(event, 'subscription_handle') @@ -117,15 +119,23 @@ class Ros2Handler(EventHandler): rmw_handle = get_field(event, 'rmw_subscription_handle') topic_name = get_field(event, 'topic_name') depth = get_field(event, 'queue_depth') - self.data.add_subscription(handle, timestamp, node_handle, rmw_handle, topic_name, depth) + self.data.add_rcl_subscription(handle, timestamp, node_handle, rmw_handle, topic_name, depth) + + def _handle_rclcpp_subscription_init( + self, event: Dict, metadata: EventMetadata, + ) -> None: + subscription_pointer = get_field(event, 'subscription') + timestamp = metadata.timestamp + handle = get_field(event, 'subscription_handle') + self.data.add_rclcpp_subscription(subscription_pointer, timestamp, handle) def _handle_rclcpp_subscription_callback_added( self, event: Dict, metadata: EventMetadata ) -> None: - handle = get_field(event, 'subscription_handle') + subscription_pointer = get_field(event, 'subscription') timestamp = metadata.timestamp callback_object = get_field(event, 'callback') - self.data.add_callback_object(handle, timestamp, callback_object) + self.data.add_callback_object(subscription_pointer, timestamp, callback_object) def _handle_rcl_service_init( self, event: Dict, metadata: EventMetadata From 588e6c1afae5a9e2304f592b1ed1b7fff83e6a0e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 10:13:07 -0800 Subject: [PATCH 02/10] Add trailing comma --- .../tracetools_analysis/processor/ros2.py | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/processor/ros2.py b/tracetools_analysis/tracetools_analysis/processor/ros2.py index 7b06888..b4a890f 100644 --- a/tracetools_analysis/tracetools_analysis/processor/ros2.py +++ b/tracetools_analysis/tracetools_analysis/processor/ros2.py @@ -80,7 +80,7 @@ class Ros2Handler(EventHandler): return self._data_model def _handle_rcl_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: context_handle = get_field(event, 'context_handle') timestamp = metadata.timestamp @@ -89,7 +89,7 @@ class Ros2Handler(EventHandler): self.data.add_context(context_handle, timestamp, pid, version) def _handle_rcl_node_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'node_handle') timestamp = metadata.timestamp @@ -100,7 +100,7 @@ class Ros2Handler(EventHandler): self.data.add_node(handle, timestamp, tid, rmw_handle, name, namespace) def _handle_rcl_publisher_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'publisher_handle') timestamp = metadata.timestamp @@ -111,7 +111,7 @@ class Ros2Handler(EventHandler): self.data.add_publisher(handle, timestamp, node_handle, rmw_handle, topic_name, depth) def _handle_rcl_subscription_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'subscription_handle') timestamp = metadata.timestamp @@ -130,7 +130,7 @@ class Ros2Handler(EventHandler): self.data.add_rclcpp_subscription(subscription_pointer, timestamp, handle) def _handle_rclcpp_subscription_callback_added( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: subscription_pointer = get_field(event, 'subscription') timestamp = metadata.timestamp @@ -138,7 +138,7 @@ class Ros2Handler(EventHandler): self.data.add_callback_object(subscription_pointer, timestamp, callback_object) def _handle_rcl_service_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'service_handle') timestamp = metadata.timestamp @@ -148,7 +148,7 @@ class Ros2Handler(EventHandler): self.data.add_service(handle, timestamp, node_handle, rmw_handle, service_name) def _handle_rclcpp_service_callback_added( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'service_handle') timestamp = metadata.timestamp @@ -156,7 +156,7 @@ class Ros2Handler(EventHandler): self.data.add_callback_object(handle, timestamp, callback_object) def _handle_rcl_client_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'client_handle') timestamp = metadata.timestamp @@ -166,7 +166,7 @@ class Ros2Handler(EventHandler): self.data.add_client(handle, timestamp, node_handle, rmw_handle, service_name) def _handle_rcl_timer_init( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'timer_handle') timestamp = metadata.timestamp @@ -175,7 +175,7 @@ class Ros2Handler(EventHandler): self.data.add_timer(handle, timestamp, period, tid) def _handle_rclcpp_timer_callback_added( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: handle = get_field(event, 'timer_handle') timestamp = metadata.timestamp @@ -183,7 +183,7 @@ class Ros2Handler(EventHandler): self.data.add_callback_object(handle, timestamp, callback_object) def _handle_rclcpp_callback_register( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: callback_object = get_field(event, 'callback') timestamp = metadata.timestamp @@ -191,14 +191,14 @@ class Ros2Handler(EventHandler): self.data.add_callback_symbol(callback_object, timestamp, symbol) def _handle_callback_start( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: # Add to dict callback_addr = get_field(event, 'callback') self._callback_instances[callback_addr] = (event, metadata) def _handle_callback_end( - self, event: Dict, metadata: EventMetadata + self, event: Dict, metadata: EventMetadata, ) -> None: # Fetch from dict callback_object = get_field(event, 'callback') From 02f90abc787a26203cde49a7685d4ed206b37080 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 10:18:34 -0800 Subject: [PATCH 03/10] Fix wrong method call --- tracetools_analysis/tracetools_analysis/utils.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools_analysis/tracetools_analysis/utils.py b/tracetools_analysis/tracetools_analysis/utils.py index d977900..4392cf3 100644 --- a/tracetools_analysis/tracetools_analysis/utils.py +++ b/tracetools_analysis/tracetools_analysis/utils.py @@ -341,7 +341,7 @@ class RosDataModelUtil(DataModelUtil): info = self.get_subscription_handle_info(handle) elif handle in self.data.services.index: type_name = 'Service' - info = self.get_subscription_handle_info(handle) + info = self.get_service_handle_info(handle) elif handle in self.data.clients.index: type_name = 'Client' info = self.get_client_handle_info(handle) From 053b007a7135dd3a4413dd590571225f8c8907db Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 10:22:53 -0800 Subject: [PATCH 04/10] Update style --- .../tracetools_analysis/utils.py | 65 +++++++++++++------ 1 file changed, 46 insertions(+), 19 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/utils.py b/tracetools_analysis/tracetools_analysis/utils.py index 4392cf3..a002748 100644 --- a/tracetools_analysis/tracetools_analysis/utils.py +++ b/tracetools_analysis/tracetools_analysis/utils.py @@ -38,7 +38,10 @@ class DataModelUtil(): This class provides basic util functions. """ - def __init__(self, data_model: DataModel) -> None: + def __init__( + self, + data_model: DataModel, + ) -> None: """ Constructor. @@ -105,7 +108,10 @@ class DataModelUtil(): class ProfileDataModelUtil(DataModelUtil): """Profiling data model utility class.""" - def __init__(self, data_model: ProfileDataModel) -> None: + def __init__( + self, + data_model: ProfileDataModel, + ) -> None: """ Constructor. @@ -113,14 +119,20 @@ class ProfileDataModelUtil(DataModelUtil): """ super().__init__(data_model) - def with_tid(self, tid: int) -> DataFrame: + def with_tid( + self, + tid: int, + ) -> DataFrame: return self.data.times.loc[self.data.times['tid'] == tid] def get_tids(self) -> Set[int]: """Get the TIDs in the data model.""" return set(self.data.times['tid']) - def get_call_tree(self, tid: int) -> Dict[str, List[str]]: + def get_call_tree( + self, + tid: int, + ) -> Dict[str, List[str]]: depth_names = self.with_tid(tid)[ ['depth', 'function_name', 'parent_name'] ].drop_duplicates() @@ -136,7 +148,10 @@ class ProfileDataModelUtil(DataModelUtil): tree[parent].add(name) return dict(tree) - def get_function_duration_data(self, tid: int) -> List[Dict[str, Union[int, str, DataFrame]]]: + def get_function_duration_data( + self, + tid: int, + ) -> List[Dict[str, Union[int, str, DataFrame]]]: """Get duration data for each function.""" tid_df = self.with_tid(tid) depth_names = tid_df[['depth', 'function_name', 'parent_name']].drop_duplicates() @@ -167,7 +182,10 @@ class ProfileDataModelUtil(DataModelUtil): class CpuTimeDataModelUtil(DataModelUtil): """CPU time data model utility class.""" - def __init__(self, data_model: CpuTimeDataModel) -> None: + def __init__( + self, + data_model: CpuTimeDataModel, + ) -> None: """ Constructor. @@ -183,7 +201,10 @@ class CpuTimeDataModelUtil(DataModelUtil): class RosDataModelUtil(DataModelUtil): """ROS data model utility class.""" - def __init__(self, data_model: RosDataModel) -> None: + def __init__( + self, + data_model: RosDataModel, + ) -> None: """ Constructor. @@ -191,7 +212,10 @@ class RosDataModelUtil(DataModelUtil): """ super().__init__(data_model) - def _prettify(self, original: str) -> str: + def _prettify( + self, + original: str, + ) -> str: """ Process symbol to make it more readable. @@ -263,7 +287,7 @@ class RosDataModelUtil(DataModelUtil): } def get_callback_durations( - self, callback_obj: int + self, callback_obj: int, ) -> DataFrame: """ Get durations of callback instances for a given callback object. @@ -280,7 +304,7 @@ class RosDataModelUtil(DataModelUtil): return self.convert_time_columns(data, ['duration'], ['timestamp']) def get_node_tid_from_name( - self, node_name: str + self, node_name: str, ) -> Union[int, None]: """ Get the tid corresponding to a node. @@ -296,7 +320,7 @@ class RosDataModelUtil(DataModelUtil): return node_row.iloc[0]['tid'] if not node_row.empty else None def get_node_names_from_tid( - self, tid: str + self, tid: str, ) -> Union[List[str], None]: """ Get the list of node names corresponding to a tid. @@ -309,7 +333,7 @@ class RosDataModelUtil(DataModelUtil): ]['name'].tolist() def get_callback_owner_info( - self, callback_obj: int + self, callback_obj: int, ) -> Union[str, None]: """ Get information about the owner of a callback. @@ -351,7 +375,7 @@ class RosDataModelUtil(DataModelUtil): return info def get_timer_handle_info( - self, timer_handle: int + self, timer_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about the owner of a timer. @@ -369,7 +393,7 @@ class RosDataModelUtil(DataModelUtil): return {'tid': tid, 'period': f'{period_ms:.0f} ms'} def get_publisher_handle_info( - self, publisher_handle: int + self, publisher_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a publisher handle. @@ -387,7 +411,7 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **publisher_info} def get_subscription_handle_info( - self, subscription_handle: int + self, subscription_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a subscription handle. @@ -409,7 +433,7 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **subscription_info} def get_service_handle_info( - self, service_handle: int + self, service_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a service handle. @@ -427,7 +451,7 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **service_info} def get_client_handle_info( - self, client_handle: int + self, client_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a client handle. @@ -445,7 +469,7 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **service_info} def get_node_handle_info( - self, node_handle: int + self, node_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a node handle. @@ -460,5 +484,8 @@ class RosDataModelUtil(DataModelUtil): tid = self.data.nodes.loc[node_handle, 'tid'] return {'node': node_name, 'tid': tid} - def format_info_dict(self, info_dict: Mapping[str, Any]) -> str: + def format_info_dict( + self, + info_dict: Mapping[str, Any], + ) -> str: return ', '.join([f'{key}: {val}' for key, val in info_dict.items()]) From 3d71b93d355ab375a9f74d3343c1791db224cb60 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 11:23:02 -0800 Subject: [PATCH 05/10] Fix dataframe append --- tracetools_analysis/tracetools_analysis/data_model/ros.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tracetools_analysis/tracetools_analysis/data_model/ros.py b/tracetools_analysis/tracetools_analysis/data_model/ros.py index 45e6fdf..1598b06 100644 --- a/tracetools_analysis/tracetools_analysis/data_model/ros.py +++ b/tracetools_analysis/tracetools_analysis/data_model/ros.py @@ -116,7 +116,7 @@ class RosDataModel(DataModel): def add_rclcpp_subscription( self, subscription_pointer, timestamp, subscription_handle ) -> None: - self.subscriptions_objects[subscription_pointer] = [timestamp, subscription_handle] + self.subscriptions_objects.loc[subscription_pointer] = [timestamp, subscription_handle] def add_service( self, handle, timestamp, node_handle, rmw_handle, service_name From fecdf3580c5ef63b5735f28e4e14dfbe140f26bf Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 11:23:54 -0800 Subject: [PATCH 06/10] Rename subscriptions_objects to subscription_objects --- tracetools_analysis/tracetools_analysis/data_model/ros.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/data_model/ros.py b/tracetools_analysis/tracetools_analysis/data_model/ros.py index 1598b06..fbf2cb6 100644 --- a/tracetools_analysis/tracetools_analysis/data_model/ros.py +++ b/tracetools_analysis/tracetools_analysis/data_model/ros.py @@ -56,10 +56,10 @@ class RosDataModel(DataModel): 'topic_name', 'depth']) self.subscriptions.set_index(['subscription_handle'], inplace=True, drop=True) - self.subscriptions_objects = pd.DataFrame(columns=['subscription', + self.subscription_objects = pd.DataFrame(columns=['subscription', 'timestamp', 'subscription_handle']) - self.subscriptions_objects.set_index(['subscription'], inplace=True, drop=True) + self.subscription_objects.set_index(['subscription'], inplace=True, drop=True) self.services = pd.DataFrame(columns=['service_handle', 'timestamp', 'node_handle', @@ -116,7 +116,7 @@ class RosDataModel(DataModel): def add_rclcpp_subscription( self, subscription_pointer, timestamp, subscription_handle ) -> None: - self.subscriptions_objects.loc[subscription_pointer] = [timestamp, subscription_handle] + self.subscription_objects.loc[subscription_pointer] = [timestamp, subscription_handle] def add_service( self, handle, timestamp, node_handle, rmw_handle, service_name @@ -165,7 +165,7 @@ class RosDataModel(DataModel): print() print(f'Subscriptions:\n{self.subscriptions.to_string()}') print() - print(f'Subscription objects:\n{self.subscriptions_objects.to_string()}') + print(f'Subscription objects:\n{self.subscription_objects.to_string()}') print() print(f'Services:\n{self.services.to_string()}') print() From 80b05dc5b54fa0d88f2eab87c1bfb02efbf0af4e Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 11:59:51 -0800 Subject: [PATCH 07/10] Update get_callback_owner_info() util method --- .../tracetools_analysis/utils.py | 73 +++++++++++++------ 1 file changed, 51 insertions(+), 22 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/utils.py b/tracetools_analysis/tracetools_analysis/utils.py index a002748..7d7a79b 100644 --- a/tracetools_analysis/tracetools_analysis/utils.py +++ b/tracetools_analysis/tracetools_analysis/utils.py @@ -346,29 +346,29 @@ class RosDataModelUtil(DataModelUtil): :param callback_obj: the callback object value :return: information about the owner of the callback, or `None` if it fails """ - # Get handle corresponding to callback object - handle = self.data.callback_objects.loc[ + # Get reference corresponding to callback object + reference = self.data.callback_objects.loc[ self.data.callback_objects['callback_object'] == callback_obj ].index.values.astype(int)[0] type_name = None info = None # Check if it's a timer first (since it's slightly different than the others) - if handle in self.data.timers.index: + if reference in self.data.timers.index: type_name = 'Timer' - info = self.get_timer_handle_info(handle) - elif handle in self.data.publishers.index: + info = self.get_timer_handle_info(reference) + elif reference in self.data.publishers.index: type_name = 'Publisher' - info = self.get_publisher_handle_info(handle) - elif handle in self.data.subscriptions.index: + info = self.get_publisher_handle_info(reference) + elif reference in self.data.subscription_objects.index: type_name = 'Subscription' - info = self.get_subscription_handle_info(handle) - elif handle in self.data.services.index: + info = self.get_subscription_reference_info(reference) + elif reference in self.data.services.index: type_name = 'Service' - info = self.get_service_handle_info(handle) - elif handle in self.data.clients.index: + info = self.get_service_handle_info(reference) + elif reference in self.data.clients.index: type_name = 'Client' - info = self.get_client_handle_info(handle) + info = self.get_client_handle_info(reference) if info is not None: info = f'{type_name} -- {self.format_info_dict(info)}' @@ -410,25 +410,54 @@ class RosDataModelUtil(DataModelUtil): publisher_info = {'topic': topic_name} return {**node_handle_info, **publisher_info} - def get_subscription_handle_info( - self, subscription_handle: int, + def get_subscription_reference_info( + self, subscription_reference: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a subscription handle. - :param subscription_handle: the subscription handle value + :param subscription_reference: the subscription reference value :return: a dictionary with name:value info, or `None` if it fails """ - subscriptions_info = self.data.subscriptions.merge( - self.data.nodes, - left_on='node_handle', - right_index=True) - if subscription_handle not in self.data.subscriptions.index: + # First check that the subscription reference exists + if subscription_reference not in self.data.subscription_objects.index: return None - node_handle = subscriptions_info.loc[subscription_handle, 'node_handle'] + # To get information about a subscription reference, we need 3 dataframes + # * subscription_objects + # * subscription (reference) <--> subscription_handle + # * subscriptions + # * subscription_handle <--> topic_name + # * subscription_handle <--> node_handle + # * nodes + # * node_handle <--> (node info) + # First, drop unnecessary common columns for debugging simplicity + subscription_objects_simple = self.data.subscription_objects.drop( + columns=['timestamp'], + axis=1, + ) + subscriptions_simple = self.data.subscriptions.drop( + columns=['timestamp', 'rmw_handle'], + inplace=False, + ) + nodes_simple = self.data.nodes.drop( + columns=['timestamp', 'rmw_handle'], + inplace=False, + ) + # Then merge the 3 dataframes + subscriptions_info = subscription_objects_simple.merge( + subscriptions_simple, + left_on='subscription_handle', + right_index=True, + ).merge( + nodes_simple, + left_on='node_handle', + right_index=True, + ) + + node_handle = subscriptions_info.loc[subscription_reference, 'node_handle'] node_handle_info = self.get_node_handle_info(node_handle) - topic_name = subscriptions_info.loc[subscription_handle, 'topic_name'] + topic_name = subscriptions_info.loc[subscription_reference, 'topic_name'] subscription_info = {'topic': topic_name} return {**node_handle_info, **subscription_info} From e006f976676af9b0f95693de39275f1a72683701 Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 12:00:48 -0800 Subject: [PATCH 08/10] Update style --- .../tracetools_analysis/utils.py | 30 ++++++++++++------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/tracetools_analysis/tracetools_analysis/utils.py b/tracetools_analysis/tracetools_analysis/utils.py index 7d7a79b..c8ad1c8 100644 --- a/tracetools_analysis/tracetools_analysis/utils.py +++ b/tracetools_analysis/tracetools_analysis/utils.py @@ -287,7 +287,8 @@ class RosDataModelUtil(DataModelUtil): } def get_callback_durations( - self, callback_obj: int, + self, + callback_obj: int, ) -> DataFrame: """ Get durations of callback instances for a given callback object. @@ -304,7 +305,8 @@ class RosDataModelUtil(DataModelUtil): return self.convert_time_columns(data, ['duration'], ['timestamp']) def get_node_tid_from_name( - self, node_name: str, + self, + node_name: str, ) -> Union[int, None]: """ Get the tid corresponding to a node. @@ -320,7 +322,8 @@ class RosDataModelUtil(DataModelUtil): return node_row.iloc[0]['tid'] if not node_row.empty else None def get_node_names_from_tid( - self, tid: str, + self, + tid: str, ) -> Union[List[str], None]: """ Get the list of node names corresponding to a tid. @@ -333,7 +336,8 @@ class RosDataModelUtil(DataModelUtil): ]['name'].tolist() def get_callback_owner_info( - self, callback_obj: int, + self, + callback_obj: int, ) -> Union[str, None]: """ Get information about the owner of a callback. @@ -375,7 +379,8 @@ class RosDataModelUtil(DataModelUtil): return info def get_timer_handle_info( - self, timer_handle: int, + self, + timer_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about the owner of a timer. @@ -393,7 +398,8 @@ class RosDataModelUtil(DataModelUtil): return {'tid': tid, 'period': f'{period_ms:.0f} ms'} def get_publisher_handle_info( - self, publisher_handle: int, + self, + publisher_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a publisher handle. @@ -411,7 +417,8 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **publisher_info} def get_subscription_reference_info( - self, subscription_reference: int, + self, + subscription_reference: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a subscription handle. @@ -462,7 +469,8 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **subscription_info} def get_service_handle_info( - self, service_handle: int, + self, + service_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a service handle. @@ -480,7 +488,8 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **service_info} def get_client_handle_info( - self, client_handle: int, + self, + client_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a client handle. @@ -498,7 +507,8 @@ class RosDataModelUtil(DataModelUtil): return {**node_handle_info, **service_info} def get_node_handle_info( - self, node_handle: int, + self, + node_handle: int, ) -> Union[Mapping[str, Any], None]: """ Get information about a node handle. From 576ee13687d256f2ccf27a43e908838f1121305d Mon Sep 17 00:00:00 2001 From: Christophe Bedard Date: Sun, 17 Nov 2019 12:02:39 -0800 Subject: [PATCH 09/10] Update sample data after new tracepoint --- .../analysis/sample_data/converted_pingpong | Bin 31173 -> 41526 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/tracetools_analysis/analysis/sample_data/converted_pingpong b/tracetools_analysis/analysis/sample_data/converted_pingpong index 12b769262187ccfb77d0b94345b4311d7c11cd79..ab8f88c88d50a4f4f78b98fd022c45450112b905 100644 GIT binary patch literal 41526 zcmdU%dwdgB7ROuqZYeDk1o|m_3MycyCm1vA6quuF9)Yy%s2Af@5YH`ku zzm}bt-!EaL$b_eEG)u*<&1W+0uFw_~=TxiM=GbBN`ODe232lMQr8;Kx@$a8(Nn>{5Oab znXd*-x!m%~Enf|iNtN25NWMWEK@B>5PN+}WAU>RTgZf?7xylk6#N{t*kU&M!pyDoW zIdcEnM|=1nVtYvD$GkFcAxg_;u$CKj29J9Nk3U7TwQQA<1gKCviqNlpL6CX{&U0SXq+b zKHNSLJBo5HU^YdePgA)2;4%fQ50)a{Tw;kVlj09QL+h3H;mis?1Ami3C{~u_Iq0NF zULQ~E1G6707B=xQDeja^3hzE>w03i;(Y0ZjO4~%GwoY|@q*yJBHQw9_EnV7@)b`1N z=7mtVEJ^UZxSZBJWG$&7{A8Ob_q^abo~<|7bXH@L0kEU(x1?#%n$f-^v}kEFETkNN z>y%KjtQlZ`j6K|v)(qx#YW~7WK8Cm3AIfzK;15gd(x7c_4_<_pE^SF>`=o%H<8jLbY;AtpFZ~U2p<=Na#1-Fp zxx()iVrs@cq#d$jM1U*AigaG7UN=-tv&H)ijiKCNvU3MGkC1%bRqZEwS6&{;Eh)WB z9DXrMKFYzXK(nfDAroH>(Thxc?p44gKHw^_DZ>&p;Wb$cEm$hN!Zcp`{)8t~t6q3J z8sG0zcmb|P&!qEkpu*!$gT92i4@T0wQV>7r%-H6x4^kG6blh^U!rQnD z=WigT6^K{)$LfUI1BPxa&78Y{?Dr1;FvGKw_%BUVB$-Rgyb`^enyCB6Q*vK=J#I8@ zv5?V{dgmfZH((XAJUd5{M7f7#+(RfYpkiuP!$fW$VX*SIxw|VKSD&2+W~^;$X_2|a z>3H2{*XQJD@{A^ZZn@d0&+N!Oo#XnMlk*7oWNx&%%&IfwGojP^o|JYWnwHovqi`|+_p7(JTJjwk-TTV`?ZDLMNzWWkw}aY zK(0Gz`wd(r)E+RjQn>u1D$gwNUz#XuvOqG}uh%AM%HH?iA` zkL)}!|4;2lntRr3Z4EU2qBMW?X}`eJZ__&d_QcD6G1(S@v-=93qRX18Dkh%vfwh`i zQ(pC5Yv84(W*vVLme(o_9QO@3rPj=6R4gyjTFJ~ruP)6O3FRtR7ulqg`?A|Je0Mza zh*Fu*MVV_ER+lNup(#uKdyJ$TunJk8XrO=IN6k*Qy2w+RPbA=3VJJWasfdX(@0JP= zKvR|iy>A+?*nm~Y@{GssmU2!|vy&-Qnw`*Yk2=NWxYmemq8oo2) zK2F2!hTMCi(RM5MalpM0S)kBJ2L41vBGZ@@iO?{QzWgEKK1W0%d|f|Ch?>2hEBU_0Ay?hR@nK8oOTAvwGgU>bBoi3jadHLa!Y`raK+iv5X?ZQNCl-Ky2N zURpKSY|fz(K2CZvzxh{<+k)iHHj7tAO?h{T85vCEEw2?X6p?%a?!_>nfiS+kU`D|} z4H`ELA`}n|L*)z_42IA^7{|xWMZxf+4CO||4FjQ!F7sce!C(jtgwbwb*LmS&ljtk= zkbD}#CTny5go44KRgg`p3ht-DUg%AN3X}MUJR}QX>{j=c#@BD^ke8Vv?RXdsNMUH9$BD8o-ievUNo)hn;+Ba)9&84RI;Fs9%7 z5(R@ns~~0ETzZrSgCR5!#Va)6O`@W2Z`U&U@(LR&b7E9Bxdx$(4VQ#` zP|BdM6)0ttzpstH$Mqw)p|lA?87&^tk$g}v=pz-i{TnjA1O-EtRuL!p(s&CE2196| zO}=eC1qDNuO%Tdx_uMly7!09-b8XeKFWT`ok;t-P?jc7%k=;I=3_I?NZX_QGnR+{~ zm4DnD1%tsgpp9tnTe&nC455LB9UnCS1%tsgAQ%^38AOA@5E=+$@Z`F_;bfC8**8f( z4PleC^S4njRB08l@|z37J~#HH->bC!~PP^(v<&_EcckE}((P^DGGdF@)e zjWiexp@A?)-nAVCgF&kxn{4a*J`Dy#Xy9C1V{Nra&0K2~^tm>@?L?AEn9Q}zWTS#i zz0I}H$|s{>sB#TrBijByb{Y(Z&_Kh^+E{^t!QdK@VUuHK(O@uy2Es_mySF;za}BX8 zFZ-w`$tOs24RsH>^?|-97^<|2fKg-1qrqSZ4OB+l9V1XM7_=$~B0&cJzxTG#Ct_fredn zur&&XD%T)(<=>{ap}}AX4TQ1c;=yYnw+RBq!yg_Z`2@)(Bs37lyRE)K!C=rTXem!| zo}|HG2n~c`9P=*}3{_f14EcoX=V>q)LIdYo)@*HRmh3k{L!Pe%f3B@9UqUholk?ge z*Ow~D)Z2M&#p7#GFc@3|GVHjNbu<_Zp@D||ZQ&La3{|c{EakDa@6cc{ga*QRV9--p zykSFW69kM?b(2Uw4KdfYcP~f5V9+YaCMmO~(_k=!1}Y=!!YmXF2Caf%#N^JQ!C(jt zoonl3hK0vm>wKyg$s|k+`^l*L6l7TD8fqi@YoC577!0lfX|&5*57J;Tga#Tmxo#*5 z27_xrFkaP-puu1W4TRCRAo{6rnrmlz#gcp)Vy@jvXo`ZtpjD7Et`_#9!C(jtRK~8l zJQNHDt%6|epFMyEgCR62ex;f!7*INGZE0Rf=%(dIA4=c#j+guy9^CSv}D%T+1 z4(OM6h6aNnG|;f4&wh`Bp~^Lg3ziQ|muN5;LIYt`cUZYPLTqB`@ zFglEQ3k5@!RuRhRQoDr)gCR5!M!}1_P%uIT_<7$h749i?2p@ACh)MgqAhAP(}R`$Ne61!y@)x2a^&=K0z`p2@TX}&4^SK3?HjoZ1%tsgpt&}ws)h!GAvDminOpaxV5o8p z;)rsj_7fTmhR{G5Qb%y>Gy?^LL8~B}}0eFc?AuVN@^gTV78#0Zv+bN`I1(#3+zSEB&qF0e8pILh<@X*@G(~{H5E`h_z0))(7^+-@fDyB@hz5fpG!Vw(Dap=| z8x{d$b;lHvkHoGlHX)&bFnT_cj)I{|tB4{0_|!}q42IA^7^Q7{pkS!dDgwr=w|mlH zFoXuem|l8nbI5IiI3*Q~tR?vb$tEN;aHI};?SdjWWTXcFm#?G^zKm)MgKI!TzTd2C z3NkEn4Yez8u`+r~kTgpFEjS!<+LIYuFe@X5XPBv*)(}d*H5H?wOyeSF>gH}O%;gtSqG#Ct_ zfy#K@+5!cGL8~Ab#HGVFr|CrCaGVb~6lr%^B% zTm#bRrq;DI7!09-hD{xN76pUBH6R#QZwUFIlo6!u--q+o>BGq;osu??d{8jx*BYqp zpK;GN6buHff|N0Q;0_uLhR{Hp?CZZ91tZip`QV8?G#Ct_fpg8?>Zl@kFz4F;028y! Apa1{> literal 31173 zcmds8dvsGp9xm?!1q+BE&=L!^6qFV@YK>3}6$C0+4i;QIY)F%98)=ifd6ZT~D~LSI z5jY0jMV3WgE{IYN)Kw9VbssLQReW$jv@9Y5t}Dx9S4Ba0?%ZVV+-WA6xtZ+kS^bAY zoBY1t_x-;4&HWPUJFZ@xqW-raG%VQ3=C)T$p!`B1+%A78*v;m5RZBj< zy;=?}Po4Z{&)|i}8~X-RWv|DfzM`ui{MaVD+!di<#~Rt?3{4Hq4R)!Kygrx59SU~J zA318|DCKAV@XvZWJZ`^K>$g?f-Oeg0w7j!CXvKy%%YvO9a=-?DsiZ?-WPQigM>Twv z?SlOfGC5FQZZUKL|yhvliC)I6^O>+beACGCy#N5D7k=J&`hN4Uimqoyw|c%U%3J5V8$iFX$(_0; zd!r^{A5a6OzmvZS_eZIzbrPL`uJG-m2^JBhtMWsiYYscmiavKFM3-a!8syp1qqG=O#LQZFbTk@2&Q7Z62Dwyb1}7q1_AG@PpY41$!$UM1CE0 zvhv{<^_>KJw)&lv_mDhmbS-8@T6D-VdTWQhs;b=Xm}j#)osu)8$YpJ2?Kd^@YT$x~ zW~D4PVAv$Z1lghk8AFG^z54s)=#WX%!RD`%C8`)Hm-fUJqhZmj;CG-`jEV8X9@eID zG1h19^d#nr)5mY@zhW!8Ri9nx1RWm!#uf&7Bi6o;;F zNRAFeF;nPuu-W~dYL{aDI@&qaQ1nh*NgAMR30Py=2-endN%HS_lS2{=B=b2nEqixz zB*D)qr{r^ZUF8zP(y)B_Zd@@ALctOcX{DM*-N>7Vk1Yp@vi^qFklCYa#q*xfXJ1~ z<_nZ7hLru_u|c~!zJE_std{%1OCJ78bkkdZ%_oW=9HeL_qBPn^hY?kp3!B3pU-Sk;dU&67L{#CB!b27oA}iD8Mvf@sYHYuGEhtD}D%fcsms@csvA;Ul}-D zgwQKh0OLwtcay!S=cwA1)Fz|>9h_hPn z1&^mQJOQsmvRa2n`P<<)Sk%{+R)J@mN>7zj@{So*n43Ec{Vjy>U~stQ zLoKa_yHlR*(LaS79cW9|5#`-69d(C7Nw-AjIekpHalZK&0%2)gQRcZ7d}~=Qylp-`|N_Zvw?YyOzjN67rb5kY1Kcg#9TcYU7KT# zs_v8pgGj_d(bi4DP^cy`Swgl=edP%-zfkojbcXB`ImKYCg#}0hCWPCID{yC7^13|E z(3BLZIRitB4N01knR&JJBn8?D!g*E)#}a{~>;Uye=xEi_gte1cvEhe*YR6;x!=DY{ zE*(IIQ~#S;VRYF0$0ac~(8#Gjg3Tr1ERP(&dbNo#Q%Pp_29By@+!`W&cCL<*V1l1T zOEAyve;7M4+e5WE63j1ax>#VeN?h$MBj6kB{M9PK1dyURtn#i)eJ@iJOz62ZCWe+^+Si2pqtp!FU;wD-1Vl+N!-ByC6TA*fFe`@;`KA118i1=U zG*uq`@fRaEE3N9SienIbcw+&Ol>8F3!kAxLAn{ly(elgpkvPU8v*I9YzqpYb-c!m( zjzrKbHb+tNOARD*F3_XCe{yt)6k}pMyOgzQT#WUD zdvl0^fn+wt&_S8W5hIdcDq`q!Giq42E-S7MMY9sr;pS}CesLZ0pHa%PngRpKoL@G6 zlbswLBKc)&9T@VR(_mx@0a^UM6@qvHxO z7mAgD5Sd$88^(pme~gkfNE0(kLY_sfW$s*ENzu*mwf@ zW&Yb?7AU~9+dn>%>80nDhbpZtR{RhycYe9C-#Aq&Y#tKBi}IfT)BN(el8FX~yZ&%t ztKlYMBj8s}d5R8{fhZb!oAU0Mj=F(PJinYXGu$`@SM+%<%7(DCu2|v2dFIY9ADo-YZIG29=xAK68)>RxGc#t?7%+r zMBpK0VILqkX(I3-GPn#|H9DPE+!VuZnbS)I z9z+J$URyTjqup)ECL{0tSOgwpWNdCaLMv{HO$u*0DgqB8gUcrFqb;=Jrr2b{-eV&0 zATqf2+Tvx4n@F3Ov)5)kwEja9iJ5yXa9Ic*LKeoo_I=St8X2Y-w)6Kw@E|g{410F% zW*Ql$7-X#PVY@E|hO z(u`+D#Uzl%lSL1b|4wMW+6MJsNKVfXKwBmxg2gKMu{2z9+7={8AW zKgyl$yNSSq$WTi&+T^R8G+J?SHsK&+*E>S+7$YOMe@_}2;%ve}#zdzOJOmkxpRWyE zy1#(5i8*`i)Tf6hlSqU=uW`uopOZ&K;2~sTG;EKREwtjM81}2Izl*?QjErgDouCyr z#jv*={6YjCV`P+8Z?0%dHaX+nA_9*wG7f&QjaJ+gn>g&-Mc^?;#@Rs)wBn}Nr1GK= zJOmkxd+nwb^ZcYu%-L)6i+zhpBxdflSMT(Tz(dHwxYtI7YH7tyF>Lv_bt3Q>BjbhL z3uwi~8CHF0VtRP3dErqJcn}#}&uj0djoX-Xn{beE%LO5LjFC}3{Vp0A;%vf^LvH+d zk_bGA46Yo~KX)pvxHy||JQ$SJO%s6!k)f7m+-uJb@6kZo#GJiWx}s+jiNwskw#Rps z2t0%=jC<`LKlPy%H^s04e_s)J5E)#Cy{>Qot++VDa-3fK$_9$SV~mVb(r3q#ZW9hN zu9?vy0*^5=)?NCXR@@Yu94r4q1Ri5#ygchPt++UwaC~<0VDO9xJctanG~-^odB~2h zNt>9n*HUY@UM7(U-)kHf(YI%B6M+ZG!gVVzF4#dUZi->IY-H^nC3FML!49z+J0O%9YT zq!kxu6OJ3t{yB?8;33Fh+-o1$rst40F=wxJx_d$aiA4Bb zD{hKmoeS?4fyWpbr|&GK6*tAO=d-7az+;SzSI+mI*_Lc_zTj#Rc#M&;=1hNDad9@` zctlzE)&LQB5E)!Io+WZ7t++UwaFB6)=3o(c2r?M=TESHp%SoGt z+Qgi__H_CqJ4htL_Zo*Rzsp`A0uLbz<6c|)-Q%?4;tb0{#`r%i5`o7c8Jm~Tiko8C z+df??0*^5=Dn6au+?H&T{>LdI@E9W_W#B!u;-=W-Y;&myJjTe_JEx3RT%1ifzBiIn zJW~W7L Date: Sun, 17 Nov 2019 12:06:57 -0800 Subject: [PATCH 10/10] Fix linter error --- tracetools_analysis/tracetools_analysis/processor/ros2.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/tracetools_analysis/tracetools_analysis/processor/ros2.py b/tracetools_analysis/tracetools_analysis/processor/ros2.py index b4a890f..edec9e0 100644 --- a/tracetools_analysis/tracetools_analysis/processor/ros2.py +++ b/tracetools_analysis/tracetools_analysis/processor/ros2.py @@ -119,7 +119,9 @@ class Ros2Handler(EventHandler): rmw_handle = get_field(event, 'rmw_subscription_handle') topic_name = get_field(event, 'topic_name') depth = get_field(event, 'queue_depth') - self.data.add_rcl_subscription(handle, timestamp, node_handle, rmw_handle, topic_name, depth) + self.data.add_rcl_subscription( + handle, timestamp, node_handle, rmw_handle, topic_name, depth, + ) def _handle_rclcpp_subscription_init( self, event: Dict, metadata: EventMetadata,