167 lines
4.8 KiB
Text
167 lines
4.8 KiB
Text
{
|
|
"cells": [
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"# Lifecycle node states\n",
|
|
"#\n",
|
|
"# Get trace data using the provided launch file:\n",
|
|
"# $ ros2 launch tracetools_analysis lifecycle_states.launch.py"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"path = '~/.ros/tracing/lifecycle-node-state/'"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"import sys\n",
|
|
"# Add paths to tracetools_analysis and tracetools_read.\n",
|
|
"# There are two options:\n",
|
|
"# 1. from source, assuming a workspace with:\n",
|
|
"# src/tracetools_analysis/\n",
|
|
"# src/ros-tracing/ros2_tracing/tracetools_read/\n",
|
|
"sys.path.insert(0, '../')\n",
|
|
"sys.path.insert(0, '../../../ros-tracing/ros2_tracing/tracetools_read/')\n",
|
|
"# 2. from Debian packages, setting the right ROS 2 distro:\n",
|
|
"#ROS_DISTRO = 'rolling'\n",
|
|
"#sys.path.insert(0, f'/opt/ros/{ROS_DISTRO}/lib/python3.8/site-packages')\n",
|
|
"import datetime as dt\n",
|
|
"\n",
|
|
"from bokeh.palettes import Category10\n",
|
|
"from bokeh.plotting import figure\n",
|
|
"from bokeh.plotting import output_notebook\n",
|
|
"from bokeh.io import show\n",
|
|
"from bokeh.layouts import row\n",
|
|
"from bokeh.models import ColumnDataSource\n",
|
|
"from bokeh.models import DatetimeTickFormatter\n",
|
|
"from bokeh.models import PrintfTickFormatter\n",
|
|
"import numpy as np\n",
|
|
"import pandas as pd\n",
|
|
"\n",
|
|
"from tracetools_analysis.loading import load_file\n",
|
|
"from tracetools_analysis.processor.ros2 import Ros2Handler\n",
|
|
"from tracetools_analysis.utils.ros2 import Ros2DataModelUtil"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"# Process\n",
|
|
"events = load_file(path)\n",
|
|
"handler = Ros2Handler.process(events)\n",
|
|
"#handler.data.print_data()"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"data_util = Ros2DataModelUtil(handler.data)\n",
|
|
"\n",
|
|
"state_intervals = data_util.get_lifecycle_node_state_intervals()\n",
|
|
"for handle, states in state_intervals.items():\n",
|
|
" print(handle)\n",
|
|
" print(states.to_string())\n",
|
|
"\n",
|
|
"output_notebook()\n",
|
|
"psize = 450"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": [
|
|
"# Plot\n",
|
|
"colors = Category10[10]\n",
|
|
"\n",
|
|
"lifecycle_node_names = {\n",
|
|
" handle: data_util.get_lifecycle_node_handle_info(handle)['lifecycle node'] for handle in state_intervals.keys()\n",
|
|
"}\n",
|
|
"states_labels = []\n",
|
|
"start_times = []\n",
|
|
"\n",
|
|
"fig = figure(\n",
|
|
" y_range=list(lifecycle_node_names.values()),\n",
|
|
" title='Lifecycle states over time',\n",
|
|
" y_axis_label='node',\n",
|
|
" plot_width=psize*2, plot_height=psize,\n",
|
|
")\n",
|
|
"\n",
|
|
"for lifecycle_node_handle, states in state_intervals.items():\n",
|
|
" lifecycle_node_name = lifecycle_node_names[lifecycle_node_handle]\n",
|
|
"\n",
|
|
" start_times.append(states['start_timestamp'].iloc[0])\n",
|
|
" for index, row in states.iterrows():\n",
|
|
" # TODO fix end\n",
|
|
" if index == max(states.index):\n",
|
|
" continue\n",
|
|
" start = row['start_timestamp']\n",
|
|
" end = row['end_timestamp']\n",
|
|
" state = row['state']\n",
|
|
" if state not in states_labels:\n",
|
|
" states_labels.append(state)\n",
|
|
" state_index = states_labels.index(state)\n",
|
|
" fig.line(\n",
|
|
" x=[start, end],\n",
|
|
" y=[lifecycle_node_name]*2,\n",
|
|
" line_width=10.0,\n",
|
|
" line_color=colors[state_index],\n",
|
|
" legend_label=state,\n",
|
|
" )\n",
|
|
"\n",
|
|
"fig.title.align = 'center'\n",
|
|
"fig.xaxis[0].formatter = DatetimeTickFormatter(seconds=['%Ss'])\n",
|
|
"fig.xaxis[0].axis_label = 'time (' + min(start_times).strftime('%Y-%m-%d %H:%M') + ')'\n",
|
|
"show(fig)"
|
|
]
|
|
},
|
|
{
|
|
"cell_type": "code",
|
|
"execution_count": null,
|
|
"metadata": {},
|
|
"outputs": [],
|
|
"source": []
|
|
}
|
|
],
|
|
"metadata": {
|
|
"kernelspec": {
|
|
"display_name": "Python 3",
|
|
"language": "python",
|
|
"name": "python3"
|
|
},
|
|
"language_info": {
|
|
"codemirror_mode": {
|
|
"name": "ipython",
|
|
"version": 3
|
|
},
|
|
"file_extension": ".py",
|
|
"mimetype": "text/x-python",
|
|
"name": "python",
|
|
"nbconvert_exporter": "python",
|
|
"pygments_lexer": "ipython3",
|
|
"version": "3.8.10"
|
|
}
|
|
},
|
|
"nbformat": 4,
|
|
"nbformat_minor": 2
|
|
}
|