Merge branch '41-support-instrumentation-link-timer-node' into 'master'
Support instrumentation for linking a timer to a node Closes #41 See merge request ros-tracing/tracetools_analysis!89
This commit is contained in:
commit
44731dfadb
5 changed files with 38 additions and 4 deletions
|
@ -100,6 +100,10 @@
|
||||||
" if owner_info is None:\n",
|
" if owner_info is None:\n",
|
||||||
" owner_info = '[unknown]'\n",
|
" owner_info = '[unknown]'\n",
|
||||||
"\n",
|
"\n",
|
||||||
|
" # Filter out internal subscriptions\n",
|
||||||
|
" if '/parameter_events' in owner_info:\n",
|
||||||
|
" continue\n",
|
||||||
|
"\n",
|
||||||
" # Duration\n",
|
" # Duration\n",
|
||||||
" duration_df = data_util.get_callback_durations(obj)\n",
|
" duration_df = data_util.get_callback_durations(obj)\n",
|
||||||
" starttime = duration_df.loc[:, 'timestamp'].iloc[0].strftime('%Y-%m-%d %H:%M')\n",
|
" starttime = duration_df.loc[:, 'timestamp'].iloc[0].strftime('%Y-%m-%d %H:%M')\n",
|
||||||
|
@ -173,6 +177,11 @@
|
||||||
"\n",
|
"\n",
|
||||||
"colour_i = 0\n",
|
"colour_i = 0\n",
|
||||||
"for obj, symbol in callback_symbols.items():\n",
|
"for obj, symbol in callback_symbols.items():\n",
|
||||||
|
" # Filter out internal subscriptions\n",
|
||||||
|
" owner_info = data_util.get_callback_owner_info(obj)\n",
|
||||||
|
" if not owner_info or '/parameter_events' in owner_info:\n",
|
||||||
|
" continue\n",
|
||||||
|
"\n",
|
||||||
" duration_df = data_util.get_callback_durations(obj)\n",
|
" duration_df = data_util.get_callback_durations(obj)\n",
|
||||||
" source = ColumnDataSource(duration_df)\n",
|
" source = ColumnDataSource(duration_df)\n",
|
||||||
" duration.title.align = 'center'\n",
|
" duration.title.align = 'center'\n",
|
||||||
|
@ -215,7 +224,7 @@
|
||||||
"name": "python",
|
"name": "python",
|
||||||
"nbconvert_exporter": "python",
|
"nbconvert_exporter": "python",
|
||||||
"pygments_lexer": "ipython3",
|
"pygments_lexer": "ipython3",
|
||||||
"version": "3.6.9"
|
"version": "3.8.5"
|
||||||
}
|
}
|
||||||
},
|
},
|
||||||
"nbformat": 4,
|
"nbformat": 4,
|
||||||
|
|
Binary file not shown.
|
@ -78,6 +78,10 @@ class Ros2DataModel(DataModel):
|
||||||
'period',
|
'period',
|
||||||
'tid'])
|
'tid'])
|
||||||
self.timers.set_index(['timer_handle'], inplace=True, drop=True)
|
self.timers.set_index(['timer_handle'], inplace=True, drop=True)
|
||||||
|
self.timer_node_links = pd.DataFrame(columns=['timer_handle',
|
||||||
|
'timestamp',
|
||||||
|
'node_handle'])
|
||||||
|
self.timer_node_links.set_index(['timer_handle'], inplace=True, drop=True)
|
||||||
|
|
||||||
self.callback_objects = pd.DataFrame(columns=['reference',
|
self.callback_objects = pd.DataFrame(columns=['reference',
|
||||||
'timestamp',
|
'timestamp',
|
||||||
|
@ -142,6 +146,11 @@ class Ros2DataModel(DataModel):
|
||||||
) -> None:
|
) -> None:
|
||||||
self.timers.loc[handle] = [timestamp, period, tid]
|
self.timers.loc[handle] = [timestamp, period, tid]
|
||||||
|
|
||||||
|
def add_timer_node_link(
|
||||||
|
self, handle, timestamp, node_handle
|
||||||
|
) -> None:
|
||||||
|
self.timer_node_links.loc[handle] = [timestamp, node_handle]
|
||||||
|
|
||||||
def add_callback_object(
|
def add_callback_object(
|
||||||
self, reference, timestamp, callback_object
|
self, reference, timestamp, callback_object
|
||||||
) -> None:
|
) -> None:
|
||||||
|
@ -205,6 +214,9 @@ class Ros2DataModel(DataModel):
|
||||||
print('Timers:')
|
print('Timers:')
|
||||||
print(self.timers.to_string())
|
print(self.timers.to_string())
|
||||||
print()
|
print()
|
||||||
|
print('Timer-node links:')
|
||||||
|
print(self.timer_node_links.to_string())
|
||||||
|
print()
|
||||||
print('Callback objects:')
|
print('Callback objects:')
|
||||||
print(self.callback_objects.to_string())
|
print(self.callback_objects.to_string())
|
||||||
print()
|
print()
|
||||||
|
@ -215,7 +227,6 @@ class Ros2DataModel(DataModel):
|
||||||
print(self.callback_instances.to_string())
|
print(self.callback_instances.to_string())
|
||||||
print()
|
print()
|
||||||
print('Lifecycle state machines:')
|
print('Lifecycle state machines:')
|
||||||
print()
|
|
||||||
print(self.lifecycle_state_machines.to_string())
|
print(self.lifecycle_state_machines.to_string())
|
||||||
print()
|
print()
|
||||||
print('Lifecycle transitions:')
|
print('Lifecycle transitions:')
|
||||||
|
|
|
@ -63,6 +63,8 @@ class Ros2Handler(EventHandler):
|
||||||
self._handle_rcl_timer_init,
|
self._handle_rcl_timer_init,
|
||||||
'ros2:rclcpp_timer_callback_added':
|
'ros2:rclcpp_timer_callback_added':
|
||||||
self._handle_rclcpp_timer_callback_added,
|
self._handle_rclcpp_timer_callback_added,
|
||||||
|
'ros2:rclcpp_timer_link_node':
|
||||||
|
self._handle_rclcpp_timer_link_node,
|
||||||
'ros2:rclcpp_callback_register':
|
'ros2:rclcpp_callback_register':
|
||||||
self._handle_rclcpp_callback_register,
|
self._handle_rclcpp_callback_register,
|
||||||
'ros2:callback_start':
|
'ros2:callback_start':
|
||||||
|
@ -198,6 +200,14 @@ class Ros2Handler(EventHandler):
|
||||||
callback_object = get_field(event, 'callback')
|
callback_object = get_field(event, 'callback')
|
||||||
self.data.add_callback_object(handle, timestamp, callback_object)
|
self.data.add_callback_object(handle, timestamp, callback_object)
|
||||||
|
|
||||||
|
def _handle_rclcpp_timer_link_node(
|
||||||
|
self, event: Dict, metadata: EventMetadata,
|
||||||
|
) -> None:
|
||||||
|
handle = get_field(event, 'timer_handle')
|
||||||
|
timestamp = metadata.timestamp
|
||||||
|
node_handle = get_field(event, 'node_handle')
|
||||||
|
self.data.add_timer_node_link(handle, timestamp, node_handle)
|
||||||
|
|
||||||
def _handle_rclcpp_callback_register(
|
def _handle_rclcpp_callback_register(
|
||||||
self, event: Dict, metadata: EventMetadata,
|
self, event: Dict, metadata: EventMetadata,
|
||||||
) -> None:
|
) -> None:
|
||||||
|
|
|
@ -228,14 +228,18 @@ class Ros2DataModelUtil(DataModelUtil):
|
||||||
:param timer_handle: the timer handle value
|
:param timer_handle: the timer handle value
|
||||||
:return: a dictionary with name:value info, or `None` if it fails
|
:return: a dictionary with name:value info, or `None` if it fails
|
||||||
"""
|
"""
|
||||||
# TODO find a way to link a timer to a specific node
|
|
||||||
if timer_handle not in self.data.timers.index:
|
if timer_handle not in self.data.timers.index:
|
||||||
return None
|
return None
|
||||||
|
|
||||||
|
node_handle = self.data.timer_node_links.loc[timer_handle, 'node_handle']
|
||||||
|
node_handle_info = self.get_node_handle_info(node_handle)
|
||||||
|
if node_handle_info is None:
|
||||||
|
return None
|
||||||
|
|
||||||
tid = self.data.timers.loc[timer_handle, 'tid']
|
tid = self.data.timers.loc[timer_handle, 'tid']
|
||||||
period_ns = self.data.timers.loc[timer_handle, 'period']
|
period_ns = self.data.timers.loc[timer_handle, 'period']
|
||||||
period_ms = period_ns / 1000000.0
|
period_ms = period_ns / 1000000.0
|
||||||
return {'tid': tid, 'period': f'{period_ms:.0f} ms'}
|
return {**node_handle_info, 'tid': tid, 'period': f'{period_ms:.0f} ms'}
|
||||||
|
|
||||||
def get_publisher_handle_info(
|
def get_publisher_handle_info(
|
||||||
self,
|
self,
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue