diff --git a/.github/workflows/pypi-publish.yml b/.github/workflows/pypi-publish.yml index fdd4b79..8ff93c6 100644 --- a/.github/workflows/pypi-publish.yml +++ b/.github/workflows/pypi-publish.yml @@ -21,10 +21,10 @@ jobs: - name: Install dependencies run: | python -m pip install --upgrade pip - pip install setuptools wheel pipenv + pip install setuptools wheel pipenv build setuptools_scm - name: Build run: | - python setup.py sdist bdist_wheel + python3 -m build - name: Publish a Python distribution to PyPI uses: pypa/gh-action-pypi-publish@release/v1 with: diff --git a/.github/workflows/python-app.yml b/.github/workflows/python-app.yml index 4c5c8b5..7598b25 100644 --- a/.github/workflows/python-app.yml +++ b/.github/workflows/python-app.yml @@ -40,7 +40,7 @@ jobs: flake8 . --count --exit-zero --max-complexity=10 --max-line-length=127 --statistics - name: Lint with pylint run: | - pylint ./dear_ros_node_viewer --disable=E0401 + pylint ./src/dear_ros_node_viewer --disable=E0401 - name: Test with pytest run: | - pytest --doctest-modules -v --cov=./dear_ros_node_viewer + pytest --doctest-modules -v --cov=./src/dear_ros_node_viewer diff --git a/.pylintrc b/.pylintrc index 7eb2aa0..2dea7eb 100644 --- a/.pylintrc +++ b/.pylintrc @@ -1,2 +1,4 @@ [MAIN] disable=too-many-public-methods +indent-string=' ' +indent-after-paren=2 diff --git a/README.md b/README.md index 06262b3..42c3c2c 100644 --- a/README.md +++ b/README.md @@ -1,54 +1,52 @@

- Dear RosNodeViewer logo + Dear RosNodeViewer logo

https://user-images.githubusercontent.com/105265012/177068238-eaf4fed9-12c0-4c5b-ac7f-9597483c4c3c.mp4 -[![Python application](https://github.com/takeshi-iwanari/dear_ros_node_viewer/actions/workflows/python-app.yml/badge.svg)](https://github.com/takeshi-iwanari/dear_ros_node_viewer/actions/workflows/python-app.yml) -[![PyPI Publish](https://github.com/takeshi-iwanari/dear_ros_node_viewer/actions/workflows/pypi-publish.yml/badge.svg)](https://pypi.org/project/dear-ros-node-viewer/) - +[![Python application](https://github.com/iwatake2222/dear_ros_node_viewer/actions/workflows/python-app.yml/badge.svg)](https://github.com/iwatake2222/dear_ros_node_viewer/actions/workflows/python-app.yml) +[![PyPI Publish](https://github.com/iwatake2222/dear_ros_node_viewer/actions/workflows/pypi-publish.yml/badge.svg)](https://pypi.org/project/dear-ros-node-viewer/) # Dear RosNodeViewer ## About - Visualize ROS2 node diagram - Support the following sources: - - *architecture.yaml* generated by [CARET](https://github.com/tier4/caret) - - *rosgraph.dot* generated by rqt_graph - - running ROS graph analysis - + - *architecture.yaml* generated by [CARET](https://github.com/tier4/caret) + - *rosgraph.dot* generated by rqt_graph + - running ROS graph analysis ## Requirements -- Ubuntu 20.04 (Not tested in Windows / Mac) - - graphviz is required -- optional: ROS 2 Galactic if you need runtime ROS graph analysis - +- Ubuntu 20.04 or 22.04 + - graphviz is required +- optional: ROS 2 Galactic or Humble if you need runtime ROS graph analysis +- Not tested in Windows / Mac ## Get Started ```sh # Install requirements -sudo apt install graphviz graphviz-dev +sudo apt install graphviz # Install Dear RosNodeViewer pip install dear-ros-node-viewer # Download sample graph -wget https://raw.githubusercontent.com/takeshi-iwanari/dear_ros_node_viewer/main/sample/architecture_autoware.yaml +wget https://raw.githubusercontent.com/iwatake2222/dear_ros_node_viewer/main/sample/architecture_autoware.yaml # Run Dear RosNodeViewer dear_ros_node_viewer architecture_autoware.yaml ``` - Quick operation guide: - - Middle button drag: move graph area - - Mouse scroll: zoom in/out (zoom function is tentative) + - Middle button drag: move graph area + - Mouse scroll: zoom in/out (zoom function is tentative) ## How to Use -[See WiKi](https://github.com/takeshi-iwanari/dear_ros_node_viewer/wiki/01.-How-to-Use) +[See WiKi](https://github.com/iwatake2222/dear_ros_node_viewer/wiki/01.-How-to-Use) # Acknowledgements - Dear RosNodeViewer utilizes [Dear PyGui](https://github.com/hoffstadt/DearPyGui) - - *Dear RosNodeViewer* is named in honor of Dear PyGui + - *Dear RosNodeViewer* is named in honor of Dear PyGui - Dear RosNodeViewer contains [Roboto font](https://fonts.google.com/specimen/Roboto) - - licensed under the Apache License, Version 2.0. + - licensed under the Apache License, Version 2.0. diff --git a/dear_ros_node_viewer/__init__.py b/dear_ros_node_viewer/__init__.py deleted file mode 100644 index 1b0afa8..0000000 --- a/dear_ros_node_viewer/__init__.py +++ /dev/null @@ -1,45 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -""" -__init__ -""" - -from dear_ros_node_viewer.dear_ros_node_viewer import main -from dear_ros_node_viewer.caret2networkx import caret2networkx -from dear_ros_node_viewer.dot2networkx import dot2networkx -from dear_ros_node_viewer.ros2networkx import Ros2Networkx -from dear_ros_node_viewer.graph_layout import place_node_by_group, align_layout -from dear_ros_node_viewer.graph_manager import GraphManager -from dear_ros_node_viewer.graph_view import GraphView - - -__copyright__ = 'Copyright 2022 Tier IV, Inc.' -__version__ = '0.1.3' -__license__ = 'Apache License 2.0' -__author__ = 'takeshi-iwanari' -__author_email__ = 'takeshi.iwanari@tier4.jp' -__url__ = 'https://github.com/takeshi-iwanari/dear_ros_node_viewer' -__all__ = [ - 'main', - 'caret2networkx', - 'dot2networkx', - 'Ros2Networkx', - 'place_node_by_group', - 'align_layout', - 'GraphManager', - 'GraphView' -] - -print('Dear ROS Node Viewer version ' + __version__) diff --git a/dear_ros_node_viewer/caret2networkx.py b/dear_ros_node_viewer/caret2networkx.py deleted file mode 100644 index 189acdd..0000000 --- a/dear_ros_node_viewer/caret2networkx.py +++ /dev/null @@ -1,157 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Function to create NetworkX object from CARET architecture.yaml -""" - -from __future__ import annotations -import networkx as nx -import matplotlib.pyplot as plt -import yaml -from dear_ros_node_viewer.logger_factory import LoggerFactory - -logger = LoggerFactory.create(__name__) - - -def quote_name(name: str) -> str: - """ - Quote name, because pydot requires. https://github.com/pydot/pydot/issues/258 - - Parameters - ---------- - name : str - original name - - Returns - ------- - modified_name : str - name with '"' - """ - modified_name = '"' + name + '"' - return modified_name - - -def parse_all_graph(yml, node_name_list, topic_pub_dict, topic_sub_dict): - """Parse architecture file""" - nodes = yml['nodes'] - for node in nodes: - node_name = quote_name(node['node_name']) - node_name_list.append(node_name) - if 'publishes' in node: - publishes = node['publishes'] - for publish in publishes: - if publish['topic_name'] in topic_pub_dict: - topic_pub_dict[publish['topic_name']].append(node_name) - else: - topic_pub_dict[publish['topic_name']] = [node_name] - if 'subscribes' in node: - subscribes = node['subscribes'] - for subscribe in subscribes: - if subscribe['topic_name'] in topic_sub_dict: - topic_sub_dict[subscribe['topic_name']].append(node_name) - else: - topic_sub_dict[subscribe['topic_name']] = [node_name] - - -def parse_target_path(yml, node_name_list, topic_pub_dict, topic_sub_dict): - """Parse architecture file""" - named_paths = yml['named_paths'] - if len(named_paths) > 0: - for named_path in named_paths: - node_chain = named_path['node_chain'] - for node in node_chain: - node_name = quote_name(node['node_name']) - node_name_list.append(node_name) - if node['publish_topic_name'] != 'UNDEFINED': - topic_pub_dict[node['publish_topic_name']] = [node_name] - if node['subscribe_topic_name'] != 'UNDEFINED': - topic_sub_dict[node['subscribe_topic_name']] = [node_name] - else: - logger.warning('named_paths not found') - - -def make_graph_from_topic_association(topic_pub_dict: dict[str, list[str]], - topic_sub_dict: dict[str, list[str]]): - """make graph from topic association""" - graph = nx.DiGraph() - for topic, node_pub_list in topic_pub_dict.items(): - if topic in topic_sub_dict: - node_sub_list = topic_sub_dict[topic] - else: - # node_sub_list = ["none:" + topic] - continue - for node_pub in node_pub_list: - for node_sub in node_sub_list: - # logger.debug(topic, node_pub, node_sub) - graph.add_edge(node_pub, node_sub, label=topic) - - return graph - - -def caret2networkx(filename: str, target_path: str = 'all_graph', - ignore_unconnected=True) -> nx.classes.digraph.DiGraph: - """ - Create NetworkX Graph from architecture.yaml generated by CARET - - Parameters - ---------- - filename : str - path to architecture file (e.g. '/home/abc/architecture.yaml') - target_path : str, default all_graph - 'all_graph': create a graph including all node and path - 'all_targets': create a graph including all paths in named_paths - path name: create a graph including path name in named_paths - - Returns - ------- - graph : nx.classes.digraph.DiGraph - NetworkX Graph - """ - - node_name_list: list[str] = [] - - # "/topic_0": ["/node_0", ], <- publishers of /topic_0 are ["/node_0", ] # - topic_pub_dict: dict[str, list[str]] = {} - - # "/topic_0": ["/node_1", ], <- subscribers of /topic_0 are ["/node_1", ] # - topic_sub_dict: dict[str, list[str]] = {} - - with open(filename, encoding='UTF-8') as file: - yml = yaml.safe_load(file) - if target_path == 'all_graph': - parse_all_graph(yml, node_name_list, topic_pub_dict, topic_sub_dict) - else: - parse_target_path(yml, node_name_list, topic_pub_dict, topic_sub_dict) - - graph = make_graph_from_topic_association(topic_pub_dict, topic_sub_dict) - - if not ignore_unconnected: - graph.add_nodes_from(node_name_list) - - logger.info('len(connected_nodes) = %d, len(nodes) = %d', - len(graph.nodes), len(node_name_list)) - - return graph - - -if __name__ == '__main__': - def local_main(): - """main function for this file""" - graph = caret2networkx('architecture.yaml') - pos = nx.spring_layout(graph) - # pos = nx.circular_layout(graph) - nx.draw_networkx(graph, pos) - plt.show() - - local_main() diff --git a/dear_ros_node_viewer/caret_extend_callback_group.py b/dear_ros_node_viewer/caret_extend_callback_group.py deleted file mode 100644 index 055d70c..0000000 --- a/dear_ros_node_viewer/caret_extend_callback_group.py +++ /dev/null @@ -1,162 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Function for additional information from CARET -""" - -from __future__ import annotations -import random -import networkx as nx -import yaml -from dear_ros_node_viewer.caret2networkx import quote_name -from dear_ros_node_viewer.logger_factory import LoggerFactory - -logger = LoggerFactory.create(__name__) - - -def create_dict_cbgroup2executor(yml: yaml) -> tuple[dict, dict]: - """Create dictionary of CallbackGroupName->Executor, CallbackGroupName->Color""" - dict_cbgroup2executor = {} - dict_cbgroup2color = {} - executors = yml['executors'] - for executor in executors: - executor_name = executor['executor_name'] - executor_type = executor['executor_type'] - callback_group_names = executor['callback_group_names'] - color = [255, 255, 255] - if len(callback_group_names) > 1: - color = [random.randint(96, 255), random.randint(96, 255), random.randint(0, 128)] - for callback_group_name in callback_group_names: - dict_cbgroup2executor[callback_group_name] = executor_name + ', ' + executor_type[:6] - dict_cbgroup2color[callback_group_name] = color - return dict_cbgroup2executor, dict_cbgroup2color - - -def create_callback_detail(callbacks: list[dict], callback_name: str) -> dict: - """ - Create detail information of callback - - Note - --- - example: - { - "callback_name": "callback_name", - "callback_type": "subscription_callback", - "description": "/topic_sub3pub1" - } - """ - callback_detail = {} - for callback in callbacks: - callback_type = callback['callback_type'] - if callback_name == callback['callback_name']: - callback_detail = {} - callback_detail['callback_name'] = callback_name - if callback_type == 'subscription_callback': - callback_detail['callback_type'] = 'sub' - callback_detail['description'] = callback['topic_name'] - elif callback_type == 'timer_callback': - callback_detail['callback_type'] = 'timer' - period_ms = float(callback['period_ns']) / 1e6 - callback_detail['description'] = str(period_ms) + 'ms' - else: - logger.warning("unexpected callback type") - callback_detail['callback_type'] = callback_type - callback_detail['description'] = '' - return callback_detail - logger.error('callback_name not found: %s', callback_name) - return None - - -def create_callback_group_list(node, dict_cbgroup2executor, dict_cbgroup2color): - """ - Create information of callback group for a node - - Note - --- - example: - [ - { - "callback_group_name": "callback_group_name", - "callback_group_type": "callback_group_type", - "executor_name": "executor_name", - "color": [255, 0, 0], - "callback_detail_list": [ - { - "callback_name": "callback_name", - "callback_type": "subscription_callback", - "description": "/topic_sub3pub1" - }, - ] - } - ] - """ - - callback_group_list = [] - if 'callback_groups' not in node or 'callbacks' not in node: - return callback_group_list - - callback_groups = node['callback_groups'] - callbacks = node['callbacks'] - for callback_group in callback_groups: - callback_group_info = {} - callback_group_name = callback_group['callback_group_name'] - callback_group_type = callback_group['callback_group_type'] - callback_names = callback_group['callback_names'] - callback_group_info['callback_group_name'] = callback_group_name - callback_group_info['callback_group_type'] = callback_group_type - callback_group_info['executor_name'] = dict_cbgroup2executor[callback_group_name] - callback_group_info['color'] = dict_cbgroup2color[callback_group_name] - callback_group_info['callback_detail_list'] = [] - for callback_name in callback_names: - callback_detail = create_callback_detail(callbacks, callback_name) - if callback_detail: - callback_group_info['callback_detail_list'].append(callback_detail) - callback_group_list.append(callback_group_info) - return callback_group_list - - -def create_dict_node_callbackgroup(yml): - """ - Create dictionary Node->CallbackGroupInfo - - Note - --- - example: - { - "node_name": [callback_group_list] - } - """ - dict_cbgroup2executor, dict_cbgroup2color = create_dict_cbgroup2executor(yml) - dict_node_cbgroup = {} - nodes = yml['nodes'] - for node in nodes: - node_name = quote_name(node['node_name']) - callback_group_list = create_callback_group_list(node, dict_cbgroup2executor, - dict_cbgroup2color) - dict_node_cbgroup[node_name] = callback_group_list - return dict_node_cbgroup - - -def extend_callback_group(filename: str, - graph: nx.classes.digraph.DiGraph) -> nx.classes.digraph.DiGraph: - """Add callback group info to a graph""" - with open(filename, encoding='UTF-8') as file: - yml = yaml.safe_load(file) - dict_node_cbgroup = create_dict_node_callbackgroup(yml) - # import json - # with open('caret_executor.json', encoding='UTF-8', mode='w') as f_caret_executor: - # json.dump(dict_node_cbgroup, f_caret_executor, ensure_ascii=True, indent=4) - for node_name in graph.nodes: - graph.nodes[node_name]['callback_group_list'] = dict_node_cbgroup[node_name] - return graph diff --git a/dear_ros_node_viewer/dear_ros_node_viewer.py b/dear_ros_node_viewer/dear_ros_node_viewer.py deleted file mode 100644 index 554e606..0000000 --- a/dear_ros_node_viewer/dear_ros_node_viewer.py +++ /dev/null @@ -1,100 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Main function for Dear ROS Node Viewer -""" - -from __future__ import annotations -import os -import argparse -import json -from dear_ros_node_viewer.logger_factory import LoggerFactory -from dear_ros_node_viewer.graph_view import GraphView - -logger = LoggerFactory.create(__name__) - - -def get_font_path(font_name: str) -> str: - """find font_path from font_name""" - if font_name[:4] == 'font': - font_path = os.path.dirname(__file__) + '/' + font_name - return font_path - return font_name - - -def load_setting_json(graph_file): - """ - Load JSON setting file - Set default values if the file doesn't exist - """ - if os.path.dirname(graph_file): - setting_file = os.path.dirname(graph_file) + '/setting.json' - else: - setting_file = './setting.json' - if not os.path.isfile(setting_file): - logger.info('Unable to find %s. Use default setting', setting_file) - setting_file = os.path.dirname(__file__) + '/setting.json' - - if os.path.isfile(setting_file): - with open(setting_file, encoding='UTF-8') as f_setting: - setting = json.load(f_setting) - app_setting = setting['app_setting'] - group_setting = setting['group_setting'] - else: - # Incase, default setting file was not found, too - logger.info('Unable to find %s. Use fixed default setting', setting_file) - app_setting = { - "window_size": [1920, 1080], - "font": "font/roboto/Roboto-Medium.ttf", - "ignore_unconnected_nodes": True, - } - group_setting = { - "__others__": { - "direction": "horizontal", - "offset": [-0.5, -0.5, 1.0, 1.0], - "color": [16, 64, 96] - } - } - - app_setting['font'] = get_font_path(app_setting['font']) - - return app_setting, group_setting - - -def parse_args(): - """ Parse arguments """ - parser = argparse.ArgumentParser( - description='Dear RosNodeViewer: Visualize ROS2 Node Graph') - parser.add_argument( - 'graph_file', type=str, nargs='?', default='architecture.yaml', - help='Graph file path. e.g. architecture.yaml(CARET) or rosgraph.dot(rqt_graph).\ - default=architecture.yaml') - args = parser.parse_args() - - logger.debug('args.graph_file = %s', args.graph_file) - - return args - - -def main(): - """ - Main function for Dear ROS Node Viewer - """ - args = parse_args() - - app_setting, group_setting = load_setting_json(args.graph_file) - graph_filename = args.graph_file - - dpg = GraphView(app_setting, group_setting) - dpg.start(graph_filename, app_setting['window_size'][0], app_setting['window_size'][1]) diff --git a/dear_ros_node_viewer/dot2networkx.py b/dear_ros_node_viewer/dot2networkx.py deleted file mode 100644 index a30df1f..0000000 --- a/dear_ros_node_viewer/dot2networkx.py +++ /dev/null @@ -1,113 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Function to create NetworkX object from dot graph file (rosgraph.dot) -""" - -from __future__ import annotations -import networkx as nx -import matplotlib.pyplot as plt - -from dear_ros_node_viewer.logger_factory import LoggerFactory -from dear_ros_node_viewer.caret2networkx import make_graph_from_topic_association - -logger = LoggerFactory.create(__name__) - - -def dot2networkx_nodeonly(graph_org: nx.classes.digraph.DiGraph, - ignore_unconnected=True) -> nx.classes.digraph.DiGraph: - """Create NetworkX Object from dot graph file (nodes only) by rqt_graph""" - graph = nx.DiGraph() - for node_org in graph_org.nodes: - if 'label' not in graph_org.nodes[node_org]: - continue - label = graph_org.nodes[node_org]['label'] - if not ignore_unconnected: - graph.add_node(label) - - for edge in graph_org.edges: - node_pub = graph_org.nodes[edge[0]]['label'] - node_sub = graph_org.nodes[edge[1]]['label'] - label = graph_org.edges[edge]['label'] - graph.add_edge(node_pub, node_sub, label=label) - - return graph - - -def dot2networkx_nodetopic(graph_org: nx.classes.digraph.DiGraph) -> nx.classes.digraph.DiGraph: - """Create NetworkX Object from dot graph file (nodes / topics) by rqt_graph""" - - # "/topic_0": ["/node_0", ], <- publishers of /topic_0 are ["/node_0", ] # - topic_pub_dict: dict[str, list[str]] = {} - - # "/topic_0": ["/node_1", ], <- subscribers of /topic_0 are ["/node_1", ] # - topic_sub_dict: dict[str, list[str]] = {} - - for edge in graph_org.edges: - src = graph_org.nodes[edge[0]] - dst = graph_org.nodes[edge[1]] - if not ('label' in src and 'label' in dst and 'shape' in src and 'shape' in dst): - continue - src_name = src['label'] - dst_name = dst['label'] - src_is_node = bool(src['shape'] == 'ellipse') - dst_is_node = bool(dst['shape'] == 'ellipse') - - if src_is_node is True and dst_is_node is False: - if dst_name in topic_pub_dict: - topic_pub_dict[dst_name].append(src_name) - else: - topic_pub_dict[dst_name] = [src_name] - elif src_is_node is False and dst_is_node is True: - if src_name in topic_sub_dict: - topic_sub_dict[src_name].append(dst_name) - else: - topic_sub_dict[src_name] = [dst_name] - - graph = make_graph_from_topic_association(topic_pub_dict, topic_sub_dict) - - return graph - - -def dot2networkx(filename: str, ignore_unconnected=True) -> nx.classes.digraph.DiGraph: - """Function to create NetworkX object from dot graph file (rosgraph.dot)""" - graph_org = nx.DiGraph(nx.nx_pydot.read_dot(filename)) - - is_node_only = True - for node_org in graph_org.nodes: - if 'shape' in graph_org.nodes[node_org]: - if graph_org.nodes[node_org]['shape'] == 'box': - is_node_only = False - break - - if is_node_only: - graph = dot2networkx_nodeonly(graph_org, ignore_unconnected) - else: - graph = dot2networkx_nodetopic(graph_org) - - logger.info('len(connected_nodes) = %d', len(graph.nodes)) - - return graph - - -if __name__ == '__main__': - def local_main(): - """main function for this file""" - graph = dot2networkx('rosgraph_nodeonly.dot') - pos = nx.spring_layout(graph) - # pos = nx.circular_layout(graph) - nx.draw_networkx(graph, pos) - plt.show() - - local_main() diff --git a/dear_ros_node_viewer/graph_layout.py b/dear_ros_node_viewer/graph_layout.py deleted file mode 100644 index 5359c59..0000000 --- a/dear_ros_node_viewer/graph_layout.py +++ /dev/null @@ -1,159 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" Function to layout node in graph (NetworkX) """ -from __future__ import annotations -import numpy as np -import networkx as nx - -from dear_ros_node_viewer.logger_factory import LoggerFactory - -logger = LoggerFactory.create(__name__) - - -def place_node_by_group(graph, group_setting): - """ - Place all nodes - Nodes belonging to the same group are placed in the same area. - The area is specified in group_setting.group_setting - """ - - # for node_name in graph.nodes: - # graph.nodes[node_name]['pos'] = [0, 0] - # graph.nodes[node_name]['color'] = [128, 128, 128] - - # Add "__other__" if a node doesn't belong to any group to make process easier # - mapping_list = {} - for node_name in graph.nodes: - is_other_node = True - for group_name in group_setting.keys(): - if group_name in node_name: - is_other_node = False - if is_other_node: - mapping_list[node_name] = '"' + '__others__' + node_name.strip('"') + '"' - else: - mapping_list[node_name] = node_name - graph = nx.relabel_nodes(graph, mapping_list) - - # Place nodes and add properties into graph # - for group_name, graph_property in group_setting.items(): - layout = place_node(graph, group_name) - direction = graph_property['direction'] - offset = graph_property['offset'] - color = graph_property['color'] - - for node_name in graph.nodes: - if group_name in node_name: - pos = layout[node_name] - pos[1] = 1 - pos[1] # 0.0 is top, 1.0 is bottom - if direction == 'horizontal': - graph.nodes[node_name]['pos'] = \ - [offset[0] + pos[1] * offset[2], offset[1] + pos[0] * offset[3]] - else: - graph.nodes[node_name]['pos'] = \ - [offset[0] + pos[0] * offset[2], offset[1] + pos[1] * offset[3]] - graph.nodes[node_name]['color'] = color - - # Remove "__other__" # - mapping_list_swap = {v: k for k, v in mapping_list.items()} - graph = nx.relabel_nodes(graph, mapping_list_swap) - - return graph - - -def place_node(graph: nx.classes.digraph.DiGraph, group_name: str, prog: str = 'dot'): - """ - Place nodes belonging to group. - Normalized position [x, y] is set to graph.nodes[node]['pos'] - - Parameters - ---------- - graph: nx.classes.digraph.DiGraph - NetworkX Graph - group_name: str - group name - prog: str (default: 'dot') - Name of the GraphViz command to use for layout. - Options depend on GraphViz version but may include: - 'dot', 'twopi', 'fdp', 'sfdp', 'circo' - - Returns - ------- - layout: dict[str,tuple[int,int]] - Dictionary of normalized positions keyed by node. - """ - - graph_modified = nx.DiGraph() - for node_name in graph.nodes: - if group_name in node_name: - graph_modified.add_node(node_name) - for edge in graph.edges: - if group_name in edge[0] and group_name in edge[1]: - graph_modified.add_edge(edge[0], edge[1]) - layout = nx.nx_pydot.pydot_layout(graph_modified, prog=prog) - layout = normalize_layout(layout) - return layout - - -def normalize_layout(layout: dict[str, tuple[int, int]]): - """ - Normalize positions to [0.0, 1.0] (left-top = (0, 0)) - - Parameters - ---------- - layout: dict[str,tuple[int,int]] - Dictionary of positions keyed by node. - - Returns - ------- - layout: dict[str,tuple[int,int]] - Dictionary of normalized positions keyed by node. - """ - - if len(layout) == 0: - return layout - for key, val in layout.items(): - layout[key] = list(val) - layout_np = np.array(list(layout.values())) - layout_min, layout_max = layout_np.min(0), layout_np.max(0) - norm_w = max((layout_max[0] - layout_min[0]), 1) - norm_h = max((layout_max[1] - layout_min[1]), 1) - if norm_w == 0 or norm_h == 0: - return layout - for pos in layout.values(): - pos[0] = (pos[0] - layout_min[0]) / norm_w - pos[1] = (pos[1] - layout_min[1]) / norm_h - return layout - - -def align_layout(graph): - """ - Set (max+min) / 2 as origin(0, 0) - - Note: - This logis is not mandatory. I added this just to make zoom a little better - Without this, zoom in/out is processed based on (0,0)=left-top - When Dear PyGui support zoomable node editor, this logic is not needed - """ - layout_np = np.array(list(map(lambda val: val['pos'], graph.nodes.values()))) - layout_min, layout_max = layout_np.min(0), layout_np.max(0) - offset_x = (layout_max[0] + layout_min[0]) / 2 - offset_y = (layout_max[1] + layout_min[1]) / 2 - # offset_x -= 2 / (layout_max[0] - layout_min[0]) - # offset_y -= 2 / (layout_max[1] - layout_min[1]) - if offset_x == 0 or offset_y == 0: - return graph - for node_name in graph.nodes: - graph.nodes[node_name]['pos'][0] -= offset_x - graph.nodes[node_name]['pos'][1] -= offset_y - return graph diff --git a/dear_ros_node_viewer/graph_manager.py b/dear_ros_node_viewer/graph_manager.py deleted file mode 100644 index f59740b..0000000 --- a/dear_ros_node_viewer/graph_manager.py +++ /dev/null @@ -1,108 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -"""Class to manage graph (NetworkX)""" -from __future__ import annotations -import os -import re -import networkx as nx -from dear_ros_node_viewer.logger_factory import LoggerFactory -from dear_ros_node_viewer.caret2networkx import caret2networkx -from dear_ros_node_viewer.caret_extend_callback_group import extend_callback_group -from dear_ros_node_viewer.caret_extend_path import get_path_dict -from dear_ros_node_viewer.dot2networkx import dot2networkx -from dear_ros_node_viewer.ros2networkx import Ros2Networkx -from dear_ros_node_viewer.graph_layout import place_node_by_group, align_layout - -logger = LoggerFactory.create(__name__) - - -class GraphManager: - """Class to manage graph (NetworkX)""" - def __init__(self, app_setting, group_setting): - self.app_setting = app_setting - self.group_setting = group_setting - self.dir = './' - self.graph: nx.DiGraph = nx.DiGraph() - self.caret_path_dict: dict = {} - - def load_graph_from_caret(self, filename: str, target_path: str = 'all_graph'): - """ load_graph_from_caret """ - self.graph = caret2networkx(filename, target_path, - self.app_setting['ignore_unconnected_nodes']) - self.graph = extend_callback_group(filename, self.graph) - self.load_graph_postprocess(filename) - self.caret_path_dict.update(get_path_dict(filename)) - - def load_graph_from_dot(self, filename: str): - """ load_graph_from_dot """ - self.graph = dot2networkx(filename, self.app_setting['ignore_unconnected_nodes']) - self.load_graph_postprocess(filename) - - def load_graph_from_running_ros(self): - """ load_graph_from_running_ros """ - ros2networkx = Ros2Networkx(node_name='temp') - ros2networkx.save_graph('./temp.dot') - ros2networkx.shutdown() - self.load_graph_from_dot('./temp.dot') - # for node in self.graph.nodes: - # if '"/temp"' == node: - # node_observer = node - # break - # self.graph.remove_node(node_observer) - # self.reset_internl_status() - - def load_graph_postprocess(self, filename): - """ Common process after loading graph """ - self.dir = os.path.dirname(filename) + '/' if os.path.dirname(filename) != '' else './' - self.clear_caret_path_dict() - self.filter_topic() # delete topic before node - self.filter_node() - if len(self.graph.nodes): - self.graph = place_node_by_group(self.graph, self.group_setting) - self.graph = align_layout(self.graph) - - def filter_node(self): - """Remove nodes which match filter setting""" - remove_node_list = [] - for node_name in self.graph.nodes: - node_name_org = node_name.strip('"') - for pattern in self.app_setting['ignore_node_list']: - if re.fullmatch(pattern, node_name_org): - remove_node_list.append(node_name) - break - self.graph.remove_nodes_from(remove_node_list) - logger.info('%s nodes are removed by filter', len(remove_node_list)) - - def filter_topic(self): - """Remove topics which match filter setting""" - remove_edge_list = [] - for edge in self.graph.edges: - topic_name = self.graph.edges[edge]['label'] - topic_name = topic_name.strip('"') - for pattern in self.app_setting['ignore_topic_list']: - if re.fullmatch(pattern, topic_name): - remove_edge_list.append(edge) - break - self.graph.remove_edges_from(remove_edge_list) - logger.info('%s topics are removed by filter', len(remove_edge_list)) - - if self.app_setting['ignore_unconnected_nodes']: - isolated_node_list = list(nx.isolates(self.graph)) - logger.info('%s nodes are removed due to isolated', len(isolated_node_list)) - self.graph.remove_nodes_from(isolated_node_list) - - def clear_caret_path_dict(self): - """ Clear CARET path dict """ - self.caret_path_dict.clear() - self.caret_path_dict['<< CLEAR >>'] = [] diff --git a/dear_ros_node_viewer/graph_view.py b/dear_ros_node_viewer/graph_view.py deleted file mode 100644 index 997a900..0000000 --- a/dear_ros_node_viewer/graph_view.py +++ /dev/null @@ -1,381 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -"""Class to display node graph""" -from __future__ import annotations -import networkx as nx -import dearpygui.dearpygui as dpg -from dear_ros_node_viewer.logger_factory import LoggerFactory -from dear_ros_node_viewer.graph_viewmodel import GraphViewModel - -logger = LoggerFactory.create(__name__) - - -class GraphView: - """Class to display node graph""" - # Color definitions - COLOR_NODE_SELECTED = [0, 0, 64] - COLOR_NODE_BAR = [32, 32, 32] - COLOR_NODE_BACK = [64, 64, 64] - - def __init__( - self, - app_setting: dict, - group_setting: dict - ): - - self.app_setting: dict = app_setting - self.graph_viewmodel = GraphViewModel(app_setting, group_setting) - self.font_size: int = 15 - self.font_list: dict[int, int] = {} - self.dpg_window_id: int = -1 - self.dpg_id_editor: int = -1 - self.dpg_id_caret_path: int = -1 - - def start(self, graph_filename: str, window_width: int = 1920, window_height: int = 1080): - """ Start Dear PyGui context """ - dpg.create_context() - self._make_font_table(self.app_setting['font']) - with dpg.handler_registry(): - dpg.add_mouse_wheel_handler(callback=self._cb_wheel) - dpg.add_key_press_handler(callback=self._cb_key_press) - - with dpg.window( - width=window_width, height=window_height, - no_collapse=True, no_title_bar=True, no_move=True, - no_resize=True) as self.dpg_window_id: - - self.add_menu_in_dpg() - - self.graph_viewmodel.load_graph(graph_filename) - self.update_node_editor() - - # Update node position and font according to the default graph size and font size - self._cb_wheel(0, 0) - self._cb_menu_font_size(None, self.font_size, None) - - # Dear PyGui stuffs - dpg.create_viewport( - title='Dear RosNodeViewer', width=window_width, height=window_height,) - dpg.set_viewport_resize_callback(self._cb_resize) - dpg.setup_dearpygui() - dpg.show_viewport() - dpg.start_dearpygui() - dpg.destroy_context() - - def update_node_editor(self): - """Update node editor""" - if self.dpg_id_editor != -1: - dpg.delete_item(self.dpg_id_editor) - - with dpg.window(tag=self.dpg_window_id): - with dpg.node_editor( - menubar=False, minimap=True, - minimap_location=dpg.mvNodeMiniMap_Location_BottomLeft) as self.dpg_id_editor: - self.add_node_in_dpg() - self.add_link_in_dpg() - self.graph_viewmodel.load_layout() - - # Add CARET path - for path_name, _ in self.graph_viewmodel.graph_manager.caret_path_dict.items(): - dpg.add_menu_item(label=path_name, callback=self._cb_menu_caret_path, - parent=self.dpg_id_caret_path) - - def add_menu_in_dpg(self): - """ Add menu bar """ - with dpg.menu_bar(): - with dpg.menu(label="Layout"): - dpg.add_menu_item(label="Reset", callback=self._cb_menu_layout_reset) - dpg.add_menu_item(label="Save", callback=self._cb_menu_layout_save, shortcut='(s)') - dpg.add_menu_item(label="Load", callback=self._cb_menu_layout_load, shortcut='(l)') - - dpg.add_menu_item(label="Copy", callback=self._cb_menu_copy, shortcut='(c)') - - with dpg.menu(label="ROS"): - dpg.add_menu_item(label="Load Current Gaph", - callback=self._cb_menu_graph_current) - - with dpg.menu(label="Font"): - dpg.add_slider_int(label="Font Size", - default_value=self.font_size, min_value=8, max_value=40, - callback=self._cb_menu_font_size) - - with dpg.menu(label="NodeName"): - dpg.add_menu_item(label="Full", callback=self._cb_menu_nodename_full) - dpg.add_menu_item(label="First + Last", callback=self._cb_menu_nodename_firstlast) - dpg.add_menu_item(label="Last Only", callback=self._cb_menu_nodename_last) - - with dpg.menu(label="EdgeName"): - dpg.add_menu_item(label="Full", callback=self._cb_menu_edgename_full) - dpg.add_menu_item(label="First + Last", callback=self._cb_menu_edgename_firstlast) - dpg.add_menu_item(label="Last Only", callback=self._cb_menu_edgename_last) - - with dpg.menu(label="CARET"): - dpg.add_menu_item(label="Show Callback", callback=self._cb_menu_caret_callbackbroup) - with dpg.menu(label="PATH") as self.dpg_id_caret_path: - pass - - def add_node_in_dpg(self): - """ Add nodes and attributes """ - graph = self.graph_viewmodel.get_graph() - for node_name in graph.nodes: - # Calculate position in window - pos = graph.nodes[node_name]['pos'] - pos = [ - pos[0] * self.graph_viewmodel.graph_size[0], - pos[1] * self.graph_viewmodel.graph_size[1]] - - # Allocate node - with dpg.node(label=node_name, pos=pos) as node_id: - # Save node id - self.graph_viewmodel.add_dpg_node_id(node_name, node_id) - - # Set color - with dpg.theme() as theme_id: - with dpg.theme_component(dpg.mvNode): - dpg.add_theme_color( - dpg.mvNodeCol_TitleBar, - graph.nodes[node_name]['color'] - if 'color' in graph.nodes[node_name] - else self.COLOR_NODE_BAR, - category=dpg.mvThemeCat_Nodes) - dpg.add_theme_color( - dpg.mvNodeCol_NodeBackgroundSelected, - self.COLOR_NODE_SELECTED, - category=dpg.mvThemeCat_Nodes) - theme_color = dpg.add_theme_color( - dpg.mvNodeCol_NodeBackground, - self.COLOR_NODE_BACK, - category=dpg.mvThemeCat_Nodes) - # Set color value - self.graph_viewmodel.add_dpg_node_color(node_name, theme_color) - dpg.bind_item_theme(node_id, theme_id) - - # Set callback - with dpg.item_handler_registry() as node_select_handler: - dpg.add_item_clicked_handler(callback=self._cb_node_clicked) - dpg.bind_item_handler_registry(node_id, node_select_handler) - - # Add text for node I/O(topics) - self.add_node_attr_in_dpg(node_name) - - self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.LAST) - self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.LAST) - - def add_node_attr_in_dpg(self, node_name): - """ Add attributes in node """ - graph = self.graph_viewmodel.get_graph() - edge_list_pub = [] - edge_list_sub = [] - for edge in graph.edges: - if edge[0] == node_name: - label = graph.edges[edge]['label'] if 'label' in graph.edges[edge] else 'out' - if label in edge_list_pub: - continue - edge_list_pub.append(label) - if edge[1] == node_name: - label = graph.edges[edge]['label'] if 'label' in graph.edges[edge] else 'in' - if label in edge_list_sub: - continue - edge_list_sub.append(label) - - for edge in edge_list_sub: - with dpg.node_attribute(attribute_type=dpg.mvNode_Attr_Input) as attr_id: - text_id = dpg.add_text(default_value=edge) - self.graph_viewmodel.add_dpg_nodeedge_idtext(node_name, edge, attr_id, text_id) - for edge in edge_list_pub: - with dpg.node_attribute(attribute_type=dpg.mvNode_Attr_Output) as attr_id: - text_id = dpg.add_text(default_value=edge) - self.graph_viewmodel.add_dpg_nodeedge_idtext(node_name, edge, - attr_id, text_id) - - # Add text for executor/callbackgroups - self.add_node_callbackgroup_in_dpg(node_name) - # Hide by default - self.graph_viewmodel.display_callbackgroup(False) - - def add_node_callbackgroup_in_dpg(self, node_name): - """ Add callback group information """ - graph = self.graph_viewmodel.get_graph() - if 'callback_group_list' in graph.nodes[node_name]: - callback_group_list = graph.nodes[node_name]['callback_group_list'] - for callback_group in callback_group_list: - executor_name = callback_group['executor_name'] - callback_group_name = callback_group['callback_group_name'] - # callback_group_type = callback_group['callback_group_type'] - callback_group_name = self.graph_viewmodel.omit_name( - callback_group_name, GraphViewModel.OmitType.LAST) - callback_detail_list = callback_group['callback_detail_list'] - color = callback_group['color'] - with dpg.node_attribute() as attr_id: - dpg.add_text('=== Callback Group [' + executor_name + '] ===', color=color) - for callback_detail in callback_detail_list: - # callback_name = callback_detail['callback_name'] - callback_type = callback_detail['callback_type'] - description = callback_detail['description'] - description = self.graph_viewmodel.omit_name( - description, GraphViewModel.OmitType.LAST) - dpg.add_text(default_value='cb_' + callback_type + ': ' + description, - color=color) - self.graph_viewmodel.add_dpg_callbackgroup_id( - callback_group['callback_group_name'], attr_id) - - def add_link_in_dpg(self): - """ Add links between node I/O """ - graph = self.graph_viewmodel.get_graph() - for edge in graph.edges: - if 'label' in graph.edges[edge]: - label = graph.edges[edge]['label'] - edge_id = dpg.add_node_link( - self.graph_viewmodel.get_dpg_nodeedge_id(edge[0], label), - self.graph_viewmodel.get_dpg_nodeedge_id(edge[1], label)) - self.graph_viewmodel.add_dpg_id_edge(label, edge_id) - else: - edge_id = dpg.add_node_link( - self.graph_viewmodel.get_dpg_nodeedge_id(edge[0], 'out'), - self.graph_viewmodel.get_dpg_nodeedge_id(edge[1], 'in')) - - # Set color. color is the same color as publisher - with dpg.theme() as theme_id: - with dpg.theme_component(dpg.mvNodeLink): - theme_color = dpg.add_theme_color( - dpg.mvNodeCol_Link, - graph.nodes[edge[0]]['color'], - category=dpg.mvThemeCat_Nodes) - self.graph_viewmodel.add_dpg_edge_color(edge, theme_color) - dpg.bind_item_theme(edge_id, theme_id) - - def _cb_resize(self, sender, app_data): - """ - callback function for window resized (Dear PyGui) - change node editer size - """ - window_width = app_data[2] - window_height = app_data[3] - dpg.set_item_width(self.dpg_window_id, window_width) - dpg.set_item_height(self.dpg_window_id, window_height) - - def _cb_node_clicked(self, sender, app_data): - """ - change connedted node color - restore node color when re-clicked - """ - node_id = app_data[1] - self.graph_viewmodel.high_light_node(node_id) - - def _cb_wheel(self, sender, app_data): - """ - callback function for mouse wheel in node editor(Dear PyGui) - zoom in/out graph according to wheel direction - """ - self.graph_viewmodel.zoom_inout(app_data > 0) - - def _cb_key_press(self, sender, app_data): - """callback function for key press""" - if app_data == ord('S'): - self._cb_menu_layout_save() - elif app_data == ord('L'): - self._cb_menu_layout_load() - elif app_data == ord('C'): - self._cb_menu_copy() - - def _cb_menu_layout_reset(self): - """ Reset layout """ - self.graph_viewmodel.reset_layout() - - def _cb_menu_layout_save(self): - """ Save current layout """ - self.graph_viewmodel.save_layout() - - def _cb_menu_layout_load(self): - """ Load layout from file """ - self.graph_viewmodel.load_layout() - - def _cb_menu_copy(self): - self.graph_viewmodel.copy_selected_node_name(self.dpg_id_editor) - - def _cb_menu_graph_current(self): - """ Update graph using current ROS status """ - self.graph_viewmodel.load_running_graph() - self.update_node_editor() - - def _cb_menu_font_size(self, sender, app_data, user_data): - """ Change font size """ - self.font_size = app_data - if self.font_size in self.font_list: - self.graph_viewmodel.update_font(self.font_list[self.font_size]) - - def _cb_menu_nodename_full(self): - """ Display full name """ - self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.FULL) - - def _cb_menu_nodename_firstlast(self): - """ Display omitted name """ - self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.FIRST_LAST) - - def _cb_menu_nodename_last(self): - """ Display omitted name """ - self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.LAST) - - def _cb_menu_edgename_full(self): - """ Display full name """ - self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.FULL) - - def _cb_menu_edgename_firstlast(self): - """ Display omitted name """ - self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.FIRST_LAST) - - def _cb_menu_edgename_last(self): - """ Display omitted name """ - self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.LAST) - - def _cb_menu_caret_callbackbroup(self, sender, app_data, user_data): - """ Show callback group info """ - if dpg.get_item_label(sender) == 'Show Callback': - self.graph_viewmodel.display_callbackgroup(True) - dpg.set_item_label(sender, 'Hide Callback') - else: - self.graph_viewmodel.display_callbackgroup(False) - dpg.set_item_label(sender, 'Show Callback') - - def _cb_menu_caret_path(self, sender, app_data, user_data): - """ High light selected CARET path """ - path_name = dpg.get_item_label(sender) - self.graph_viewmodel.high_light_caret_path(path_name) - - def _make_font_table(self, font_path): - """Make font table""" - with dpg.font_registry(): - for i in range(8, 40): - try: - self.font_list[i] = dpg.add_font(font_path, i) - except SystemError: - logger.error('Failed to load font: %s', font_path) - - -if __name__ == '__main__': - def local_main(): - """main function for this file""" - graph = nx.DiGraph() - nx.add_path(graph, ['3', '5', '4', '1', '0', '2']) - nx.add_path(graph, ['3', '0', '4', '2', '1', '5']) - layout = nx.spring_layout(graph) - for key, val in layout.items(): - graph.nodes[key]['pos'] = list(val) - graph.nodes[key]['color'] = [128, 128, 128] - app_setting = { - "font": "/usr/share/fonts/truetype/ubuntu/Ubuntu-C.ttf" - } - GraphView(app_setting, graph) - - local_main() diff --git a/dear_ros_node_viewer/graph_viewmodel.py b/dear_ros_node_viewer/graph_viewmodel.py deleted file mode 100644 index 87077f5..0000000 --- a/dear_ros_node_viewer/graph_viewmodel.py +++ /dev/null @@ -1,340 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -"""Class to bind graph and GUI components""" -from __future__ import annotations -import os -from enum import Enum -import textwrap -import json -import networkx as nx -import dearpygui.dearpygui as dpg -from dear_ros_node_viewer.graph_manager import GraphManager -from dear_ros_node_viewer.logger_factory import LoggerFactory - -logger = LoggerFactory.create(__name__) - - -class GraphViewModel: - """Class to bind graph and GUI components""" - # Color definitions - COLOR_HIGHLIGHT_SELECTED = [0, 0, 64] - COLOR_HIGHLIGHT_PUB = [0, 64, 0] - COLOR_HIGHLIGHT_SUB = [64, 0, 0] - COLOR_HIGHLIGHT_CARET_PATH = [0, 96, 0] - COLOR_HIGHLIGHT_DEF = [64, 64, 64] - COLOR_HIGHLIGHT_EDGE = [196, 196, 196] - - class OmitType(Enum): - """Name omission type""" - FULL = 1 - FIRST_LAST = 2 - LAST = 3 - - def __init__(self, - app_setting: dict, - group_setting: dict): - self.graph_size: list[int] = [1920, 1080] - self.graph_manager = GraphManager(app_setting, group_setting) - self.node_selected_dict: dict[str, bool] = {} # [node_name, is_selected] - - # bind list to components in PyGui - self.dpg_bind = { - 'node_id': {}, # {"node_name": id} - 'node_color': {}, # {"node_name": color_id} - 'nodeedge_id': {}, # {"nodename_edgename": attr_id} - 'nodeedge_text': {}, # {"nodename_edgename": text_id} - 'id_edge': {}, # {id: "edge_name"} - 'edge_color': {}, # {edge_obj: color_id} - 'callbackgroup_id': {}, # {"callback_group_name": attr_id} - } - - def get_graph(self) -> nx.DiGraph: - """Graph getter""" - return self.graph_manager.graph - - def load_running_graph(self): - """Load running ROS Graph""" - self.graph_manager.load_graph_from_running_ros() - self._reset_internl_status() - - def load_graph(self, graph_filename: str): - """Load Graph from file""" - if '.yaml' in graph_filename: - try: - self.graph_manager.load_graph_from_caret(graph_filename) - except FileNotFoundError as err: - logger.error(err) - elif '.dot' in graph_filename: - try: - self.graph_manager.load_graph_from_dot(graph_filename) - except FileNotFoundError as err: - logger.error(err) - else: - logger.error('Graph is not loaded. Unknown file format: %s', graph_filename) - # return # keep going - self._reset_internl_status() - - def _reset_internl_status(self): - """ Reset internal status """ - self.dpg_bind['node_id'].clear() - self.dpg_bind['node_color'].clear() - self.dpg_bind['nodeedge_id'].clear() - self.dpg_bind['nodeedge_text'].clear() - self.dpg_bind['id_edge'].clear() - self.dpg_bind['edge_color'].clear() - self.dpg_bind['callbackgroup_id'].clear() - self.node_selected_dict.clear() - for node_name in self.get_graph().nodes: - self.node_selected_dict[node_name] = False - - def add_dpg_node_id(self, node_name, dpg_id): - """ Add association b/w node_name and dpg_id """ - self.dpg_bind['node_id'][node_name] = dpg_id - - def add_dpg_node_color(self, node_name, dpg_id): - """ Add association b/w node_name and dpg_id """ - self.dpg_bind['node_color'][node_name] = dpg_id - - def add_dpg_nodeedge_idtext(self, node_name, edge_name, attr_id, text_id): - """ Add association b/w node_attr and dpg_id """ - key = self._make_nodeedge_key(node_name, edge_name) - self.dpg_bind['nodeedge_id'][key] = attr_id - self.dpg_bind['nodeedge_text'][key] = text_id - - def add_dpg_id_edge(self, edge_name, edge_id): - """ Add association b/w edge and dpg_id """ - self.dpg_bind['id_edge'][edge_id] = edge_name - - def add_dpg_edge_color(self, edge_name, edge_id): - """ Add association b/w edge and dpg_id """ - self.dpg_bind['edge_color'][edge_name] = edge_id - - def add_dpg_callbackgroup_id(self, callback_group_name, dpg_id): - """ Add association b/w callback_group_name and dpg_id """ - self.dpg_bind['callbackgroup_id'][callback_group_name] = dpg_id - - def get_dpg_nodeedge_id(self, node_name, edge_name): - """ Get association for a selected name """ - key = self._make_nodeedge_key(node_name, edge_name) - return self.dpg_bind['nodeedge_id'][key] - - def _make_nodeedge_key(self, node_name, edge_name): - """create dictionary key for topic attribute in node""" - return node_name + '###' + edge_name - - def high_light_node(self, dpg_id_node): - """ High light the selected node and connected nodes """ - graph = self.get_graph() - selected_node_name = [k for k, v in self.dpg_bind['node_id'].items() if v == dpg_id_node][0] - is_re_clicked = self.node_selected_dict[selected_node_name] - for node_name, _ in self.node_selected_dict.items(): - publishing_edge_list = [e for e in graph.edges if node_name in e[0]] - publishing_edge_subscribing_node_name_list = \ - [e[1] for e in graph.edges if e[0] == node_name] - subscribing_edge_list = [e for e in graph.edges if node_name in e[1]] - subscribing_edge_publishing_node_name_list = \ - [e[0] for e in graph.edges if e[1] == node_name] - if self.node_selected_dict[node_name]: - # Disable highlight for all the other nodes# - self.node_selected_dict[node_name] = False - dpg.set_value( - self.dpg_bind['node_color'][node_name], - self.COLOR_HIGHLIGHT_DEF) - for edge_name in publishing_edge_list: - dpg.set_value( - self.dpg_bind['edge_color'][edge_name], - graph.nodes[node_name]['color']) - for pub_node_name in publishing_edge_subscribing_node_name_list: - dpg.set_value( - self.dpg_bind['node_color'][pub_node_name], - self.COLOR_HIGHLIGHT_DEF) - for edge_name in subscribing_edge_list: - dpg.set_value( - self.dpg_bind['edge_color'][edge_name], - graph.nodes[node_name]['color']) # todo. incorrect color - for sub_node_name in subscribing_edge_publishing_node_name_list: - dpg.set_value( - self.dpg_bind['node_color'][sub_node_name], - self.COLOR_HIGHLIGHT_DEF) - break - - if not is_re_clicked: - # Enable highlight for the selected node # - publishing_edge_list = [e for e in graph.edges if selected_node_name in e[0]] - publishing_edge_subscribing_node_name_list = \ - [e[1] for e in graph.edges if e[0] == selected_node_name] - subscribing_edge_list = [e for e in graph.edges if selected_node_name in e[1]] - subscribing_edge_publishing_node_name_list = \ - [e[0] for e in graph.edges if e[1] == selected_node_name] - self.node_selected_dict[selected_node_name] = True - dpg.set_value( - self.dpg_bind['node_color'][selected_node_name], - self.COLOR_HIGHLIGHT_SELECTED) - for edge_name in publishing_edge_list: - dpg.set_value( - self.dpg_bind['edge_color'][edge_name], - self.COLOR_HIGHLIGHT_EDGE) - for pub_node_name in publishing_edge_subscribing_node_name_list: - dpg.set_value( - self.dpg_bind['node_color'][pub_node_name], - self.COLOR_HIGHLIGHT_PUB) - for edge_name in subscribing_edge_list: - dpg.set_value( - self.dpg_bind['edge_color'][edge_name], - self.COLOR_HIGHLIGHT_EDGE) - for sub_node_name in subscribing_edge_publishing_node_name_list: - dpg.set_value( - self.dpg_bind['node_color'][sub_node_name], - self.COLOR_HIGHLIGHT_SUB) - - def zoom_inout(self, is_zoom_in): - """ Zoom in/out """ - previous_graph_size = self.graph_size - if is_zoom_in: - self.graph_size = list(map(lambda val: val * 1.1, self.graph_size)) - else: - self.graph_size = list(map(lambda val: val * 0.9, self.graph_size)) - scale = (self.graph_size[0] / previous_graph_size[0], - self.graph_size[1] / previous_graph_size[1]) - - for _, node_id in self.dpg_bind['node_id'].items(): - pos = dpg.get_item_pos(node_id) - pos = (pos[0] * scale[0], pos[1] * scale[1]) - dpg.set_item_pos(node_id, pos) - - def reset_layout(self): - """ Reset node layout """ - for node_name, node_id in self.dpg_bind['node_id'].items(): - pos = self.get_graph().nodes[node_name]['pos'] - pos = (pos[0] * self.graph_size[0], pos[1] * self.graph_size[1]) - dpg.set_item_pos(node_id, pos) - - def load_layout(self): - """ Load node layout """ - graph = self.get_graph() - filename = self.graph_manager.dir + 'layout.json' - if not os.path.exists(filename): - logger.info('%s does not exist. Use auto layout', filename) - return - with open(filename, encoding='UTF-8') as f_layout: - pos_dict = json.load(f_layout) - for node_name, pos in pos_dict.items(): - if node_name in graph.nodes: - graph.nodes[node_name]['pos'] = pos - self.reset_layout() - - def save_layout(self): - """ Save node layout """ - pos_dict = {} - for node_name, node_id in self.dpg_bind['node_id'].items(): - pos = dpg.get_item_pos(node_id) - pos = (pos[0] / self.graph_size[0], pos[1] / self.graph_size[1]) - pos_dict[node_name] = pos - - filename = self.graph_manager.dir + '/layout.json' - with open(filename, encoding='UTF-8', mode='w') as f_layout: - json.dump(pos_dict, f_layout, ensure_ascii=True, indent=4) - - def update_font(self, font): - """ Update font used in all nodes according to current font size """ - for node_id in self.dpg_bind['node_id'].values(): - dpg.bind_item_font(node_id, font) - - def update_nodename(self, omit_type: OmitType): - """ Update node name """ - for node_name, node_id in self.dpg_bind['node_id'].items(): - dpg.set_item_label(node_id, self.omit_name(node_name, omit_type)) - - def update_edgename(self, omit_type: OmitType): - """ Update edge name """ - for nodeedge_name, text_id in self.dpg_bind['nodeedge_text'].items(): - edgename = nodeedge_name.split('###')[-1] - dpg.set_value(text_id, value=self.omit_name(edgename, omit_type)) - - def omit_name(self, name: str, omit_type: OmitType) -> str: - """ replace an original name to a name to be displayed """ - display_name = name.strip('"') - if omit_type == self.OmitType.FULL: - display_name = textwrap.fill(display_name, 60) - elif omit_type == self.OmitType.FIRST_LAST: - display_name = display_name.split('/') - if '' in display_name: - display_name.remove('') - if len(display_name) > 1: - display_name = '/' + display_name[0] + '/' + display_name[-1] - else: - display_name = '/' + display_name[0] - display_name = textwrap.fill(display_name, 50) - else: - display_name = display_name.split('/') - display_name = '/' + display_name[-1] - display_name = textwrap.fill(display_name, 40) - - return display_name - - def copy_selected_node_name(self, dpg_id_nodeeditor): - """Copy selected node names to clipboard""" - def get_key(dic, val): - for key, value in dic.items(): - if val == value: - return key - return None - - copied_str = '' - selected_nodes = dpg.get_selected_nodes(dpg_id_nodeeditor) - selected_links = dpg.get_selected_links(dpg_id_nodeeditor) - if len(selected_nodes) == 1: - copied_str = get_key(self.dpg_bind['node_id'], selected_nodes[0]) - copied_str = copied_str.strip('"') - print(copied_str) - elif len(selected_links) == 1: - copied_str = self.dpg_bind['id_edge'][selected_links[0]] - copied_str = copied_str.strip('"') - print(copied_str) - elif len(selected_nodes) > 1: - for node_id in selected_nodes: - node_name = get_key(self.dpg_bind['node_id'], node_id) - node_name = node_name.strip('"') - copied_str += '"' + node_name + '",\n' - print(node_name) - print('---') - dpg.set_clipboard_text(copied_str) - - def display_callbackgroup(self, onoff: bool): - """Switch visibility of callback group in a node""" - callbackgroup_id = self.dpg_bind['callbackgroup_id'] - for _, value in callbackgroup_id.items(): - if onoff: - dpg.show_item(value) - else: - dpg.hide_item(value) - - def high_light_caret_path(self, path_name): - """ High light the selected CARET path """ - # Disable high light for all nodes - graph = self.get_graph() - for node_name in graph.nodes: - dpg.set_value( - self.dpg_bind['node_color'][node_name], - self.COLOR_HIGHLIGHT_DEF) - - # Then, high light nodes in the path - node_list = self.graph_manager.caret_path_dict[path_name] - for node_name in node_list: - if node_name in self.dpg_bind['node_color']: - dpg.set_value( - self.dpg_bind['node_color'][node_name], - self.COLOR_HIGHLIGHT_CARET_PATH) - else: - logger.error('%s is not included in the current graph', node_name) diff --git a/dear_ros_node_viewer/logger_factory.py b/dear_ros_node_viewer/logger_factory.py deleted file mode 100644 index e511abb..0000000 --- a/dear_ros_node_viewer/logger_factory.py +++ /dev/null @@ -1,48 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Logger Factory -""" -import logging - - -class LoggerFactory(): - '''Logger Factory''' - level: int = logging.DEBUG - log_filename: str = None - - @classmethod - def create(cls, name) -> logging.Logger: - '''Create logger''' - logger = logging.getLogger(name) - logger.setLevel(cls.level) - stream_handler = logging .StreamHandler() - stream_handler.setLevel(cls.level) - handler_format = logging.Formatter('[%(levelname)-7s][%(filename)s:%(lineno)s] %(message)s') - stream_handler.setFormatter(handler_format) - logger.addHandler(stream_handler) - if cls.log_filename: - file_handler = logging.FileHandler(cls.log_filename) - file_handler.setLevel(cls.level) - handler_format = logging.Formatter( - '[%(asctime)s][%(levelname)-7s][%(filename)s:%(lineno)s] %(message)s') - file_handler.setFormatter(handler_format) - logger.addHandler(file_handler) - return logger - - @classmethod - def config(cls, level, log_filename) -> None: - '''Config''' - LoggerFactory.level = level - LoggerFactory.log_filename = log_filename diff --git a/dear_ros_node_viewer/ros2networkx.py b/dear_ros_node_viewer/ros2networkx.py deleted file mode 100644 index 428d3c3..0000000 --- a/dear_ros_node_viewer/ros2networkx.py +++ /dev/null @@ -1,122 +0,0 @@ -# Copyright 2022 Tier IV, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. -""" -Utility class for polling ROS statistics from running ROS graph - -Note ----- -Reference: /opt/ros/galactic/lib/python3.8/site-packages/rqt_graph/rosgraph2_impl.py -""" - -import threading -import time -import networkx as nx -import matplotlib.pyplot as plt -from dear_ros_node_viewer.logger_factory import LoggerFactory - -# Note: Use try-except to avoid error at pytest in GitHub Actions (todo) -try: - import rclpy - from rclpy.executors import MultiThreadedExecutor - from rqt_graph.rosgraph2_impl import Graph - from rqt_graph.dotcode import RosGraphDotcodeGenerator - from qt_dotgraph.pydotfactory import PydotFactory -except ImportError: - pass - -logger = LoggerFactory.create(__name__) - - -class Ros2Networkx(): - """Utility class for polling ROS statistics from running ROS graph""" - def __init__(self, node_name='Ros2Networkx'): - rclpy.init() - self.node_name_ = node_name - self.node_ = rclpy.create_node(node_name) - self.executor_ = MultiThreadedExecutor() - self.executor_.add_node(self.node_) - self.thread_ = threading.Thread(target=self.node_loop) - self.thread_.start() - - def node_loop(self): - """thread main function""" - while rclpy.ok(): - logger.info('Analyzing...') - self.executor_.spin_once(timeout_sec=1.0) - - def save_graph(self, filename: str = None) -> str: - """save dot graph""" - time.sleep(5) - graph = Graph(self.node_) - graph.set_node_stale(5.0) - graph.update() - - dotcode_generator = RosGraphDotcodeGenerator(self.node_) - dotcode = dotcode_generator.generate_dotcode( - rosgraphinst=graph, - ns_filter='', - topic_filter='', - # graph_mode='node_topic', - graph_mode='node_node', - hide_single_connection_topics=True, - hide_dead_end_topics=True, - cluster_namespaces_level=0, - # accumulate_actions=accumulate_actions, - dotcode_factory=PydotFactory(), - # orientation=orientation, - quiet=True, - unreachable=True, - group_tf_nodes=True, - hide_tf_nodes=True, - # group_image_nodes=group_image_nodes, - hide_dynamic_reconfigure=True - ) - - if filename: - with open(filename, encoding='UTF8', mode='w') as dot_file: - dot_file.write(dotcode) - - return dotcode - - def get_graph(self) -> nx.classes.digraph.DiGraph: - """get graph as NetworkX""" - _ = self.save_graph('temp.dot') - graph = nx.DiGraph(nx.nx_pydot.read_dot('temp.dot')) - for node in graph.nodes: - if self.node_name_ in graph.nodes[node]['label']: - node_observer = node - break - graph.remove_node(node_observer) - return graph - - def shutdown(self): - """shutdown thread""" - self.node_.destroy_node() - rclpy.shutdown() - - -def main(): - """test code""" - node_name = 'Ros2Networkx' - ros2networkx = Ros2Networkx(node_name=node_name) - graph = ros2networkx.get_graph() - ros2networkx.shutdown() - - pos = nx.spring_layout(graph) - nx.draw_networkx(graph, pos) - plt.show() - - -if __name__ == '__main__': - main() diff --git a/dear_ros_node_viewer/setting.json b/dear_ros_node_viewer/setting.json deleted file mode 100644 index cdd5416..0000000 --- a/dear_ros_node_viewer/setting.json +++ /dev/null @@ -1,49 +0,0 @@ -{ - "app_setting": { - "window_size": [1920, 1080], - "font": "font/roboto/Roboto-Medium.ttf", - "ignore_unconnected_nodes": true, - "ignore_node_list": [ - "/node_name/to_be_ignored/in_regularexpression", - "/wild_card/is/.*" - ], - "ignore_topic_list": [ - "/topic_name/to_be_ignored/in_regularexpression", - "/tf", - "/tf_static", - "/diagnostics" - ] - }, - "group_setting": { - "/sensing": { - "direction": "horizontal", - "offset": [0.0, 1.0, 2.5, 2.0], - "color": [128, 0, 128] - }, - "/localization": { - "direction": "horizontal", - "offset": [0.0, 3.5, 2.5, 2.0], - "color": [0, 0, 128] - }, - "/perception": { - "direction": "horizontal", - "offset": [3.0, 3.5, 4.0, 4.0], - "color": [0, 128, 0] - }, - "/planning": { - "direction": "horizontal", - "offset": [7.0, 0.0, 4.0, 4.0], - "color": [128, 128, 0] - }, - "/control": { - "direction": "horizontal", - "offset": [3.0, -0.8, 3.0, 1.5], - "color": [196, 64, 0] - }, - "__others__": { - "direction": "horizontal", - "offset": [-0.5, -0.5, 1.0, 1.0], - "color": [16, 64, 96] - } - } -} \ No newline at end of file diff --git a/main.py b/main.py index cccc867..5a8ba51 100644 --- a/main.py +++ b/main.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -11,12 +11,8 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. -""" -Entry point -""" - -from dear_ros_node_viewer import main +from src.dear_ros_node_viewer import main if __name__ == '__main__': - main() + main() diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 0000000..dd8e9eb --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,73 @@ +[project] +name = "dear_ros_node_viewer" +# version = "0.0.0" +dynamic = ["version"] +description = "dear_ros_node_viewer" +readme = "README.md" +requires-python = ">=3.7" +license = {file = "LICENSE.txt"} +keywords = ["ros", "ros2", "tool", "rqt_graph", "dearpygui", "node-editor"] + +authors = [ + {name = "iwatake2222", email = "take.iwiw2222@gmail.com" } +] + +maintainers = [ + {name = "iwatake2222", email = "take.iwiw2222@gmail.com" } +] + +classifiers = [ + "Development Status :: 3 - Alpha", + + "Intended Audience :: Developers", + + "Topic :: Utilities", + "Topic :: Scientific/Engineering :: Visualization", + "Framework :: Robot Framework :: Tool", + + "License :: OSI Approved :: Apache Software License", + + "Programming Language :: Python :: 3", + "Programming Language :: Python :: 3.7", + "Programming Language :: Python :: 3.8", + "Programming Language :: Python :: 3.9", + "Programming Language :: Python :: 3.10", + "Programming Language :: Python :: 3.11", + "Programming Language :: Python :: 3 :: Only", +] + +dependencies = [ + "dearpygui>=1.10.1", + "graphviz", + "matplotlib", + "networkx", + "numpy", + "pydot", + "pygraphviz", + "pyyaml", +] + +[project.optional-dependencies] +dev = ["check-manifest"] +test = ["coverage"] + +[project.urls] +"Homepage" = "https://github.com/iwatake2222/dear_ros_node_viewer" +"Bug Reports" = "https://github.com/iwatake2222/dear_ros_node_viewer/issues" +"Source" = "https://github.com/iwatake2222/dear_ros_node_viewer" + +[project.scripts] +dear_ros_node_viewer = "dear_ros_node_viewer.__main__:main" + +[tool.setuptools] +package-data = {"dear_ros_node_viewer" = ["setting.json", "font/*/*.ttf"]} + +[build-system] +requires = ["setuptools>=64", "wheel", "setuptools_scm>=8"] +build-backend = "setuptools.build_meta" + +[tool.setuptools_scm] +version_file = "src/dear_ros_node_viewer/_version.py" +# version_scheme= "no-guess-dev" +local_scheme = "no-local-version" +fallback_version = "0.0.0" diff --git a/requirements.txt b/requirements.txt index 741f2b8..200a773 100644 --- a/requirements.txt +++ b/requirements.txt @@ -2,12 +2,9 @@ pytest pytest-cov pylint -numpy +dearpygui>=1.10.1 matplotlib -pydot networkx -dearpygui -graphviz -pygraphviz +numpy +pydot pyyaml - diff --git a/setting.json b/setting.json index cdd5416..3dd7676 100644 --- a/setting.json +++ b/setting.json @@ -1,49 +1,49 @@ { - "app_setting": { - "window_size": [1920, 1080], - "font": "font/roboto/Roboto-Medium.ttf", - "ignore_unconnected_nodes": true, - "ignore_node_list": [ - "/node_name/to_be_ignored/in_regularexpression", - "/wild_card/is/.*" - ], - "ignore_topic_list": [ - "/topic_name/to_be_ignored/in_regularexpression", - "/tf", - "/tf_static", - "/diagnostics" - ] + "app_setting": { + "window_size": [1920, 1080], + "font": "font/roboto/Roboto-Medium.ttf", + "ignore_unconnected_nodes": true, + "ignore_node_list": [ + "/node_name/to_be_ignored/in_regularexpression", + "/wild_card/is/.*" + ], + "ignore_topic_list": [ + "/topic_name/to_be_ignored/in_regularexpression", + "/tf", + "/tf_static", + "/diagnostics" + ] + }, + "group_setting": { + "/sensing": { + "direction": "horizontal", + "offset": [0.0, 1.0, 2.5, 2.0], + "color": [128, 0, 128] }, - "group_setting": { - "/sensing": { - "direction": "horizontal", - "offset": [0.0, 1.0, 2.5, 2.0], - "color": [128, 0, 128] - }, - "/localization": { - "direction": "horizontal", - "offset": [0.0, 3.5, 2.5, 2.0], - "color": [0, 0, 128] - }, - "/perception": { - "direction": "horizontal", - "offset": [3.0, 3.5, 4.0, 4.0], - "color": [0, 128, 0] - }, - "/planning": { - "direction": "horizontal", - "offset": [7.0, 0.0, 4.0, 4.0], - "color": [128, 128, 0] - }, - "/control": { - "direction": "horizontal", - "offset": [3.0, -0.8, 3.0, 1.5], - "color": [196, 64, 0] - }, - "__others__": { - "direction": "horizontal", - "offset": [-0.5, -0.5, 1.0, 1.0], - "color": [16, 64, 96] - } + "/localization": { + "direction": "horizontal", + "offset": [0.0, 3.5, 2.5, 2.0], + "color": [0, 0, 128] + }, + "/perception": { + "direction": "horizontal", + "offset": [3.0, 3.5, 4.0, 4.0], + "color": [0, 128, 0] + }, + "/planning": { + "direction": "horizontal", + "offset": [7.0, 0.0, 4.0, 4.0], + "color": [128, 128, 0] + }, + "/control": { + "direction": "horizontal", + "offset": [3.0, -0.8, 3.0, 1.5], + "color": [196, 64, 0] + }, + "__others__": { + "direction": "horizontal", + "offset": [-0.5, -0.5, 1.0, 1.0], + "color": [16, 64, 96] } + } } \ No newline at end of file diff --git a/setup.py b/setup.py deleted file mode 100644 index 3739474..0000000 --- a/setup.py +++ /dev/null @@ -1,71 +0,0 @@ -"""setup script""" -from setuptools import setup, find_packages -from os import path -import re - -package_name = 'dear_ros_node_viewer' -root_dir = path.abspath(path.dirname(__file__)) - -with open(path.join(root_dir, package_name, '__init__.py')) as f: - init_text = f.read() - version = re.search(r'__version__\s*=\s*[\'\"](.+?)[\'\"]', init_text).group(1) - license = re.search(r'__license__\s*=\s*[\'\"](.+?)[\'\"]', init_text).group(1) - author = re.search(r'__author__\s*=\s*[\'\"](.+?)[\'\"]', init_text).group(1) - author_email = re.search(r'__author_email__\s*=\s*[\'\"](.+?)[\'\"]', init_text).group(1) - url = re.search(r'__url__\s*=\s*[\'\"](.+?)[\'\"]', init_text).group(1) - -assert version -assert license -assert author -assert author_email -assert url - -with open("README.md", encoding='utf8') as f: - long_description = f.read() - -setup( - name="dear_ros_node_viewer", - version=version, - description='ROS2 node viewer using Dear PyGui ', - long_description=long_description, - long_description_content_type="text/markdown", - keywords='ros ros2 rqt_graph node-editor dearpygui', - author=author, - author_email=author_email, - url=url, - project_urls={ - "Source": - "https://github.com/takeshi-iwanari/dear_ros_node_viewer", - "Tracker": - "https://github.com/takeshi-iwanari/dear_ros_node_viewer/issues", - }, - classifiers=[ - 'Development Status :: 2 - Pre-Alpha', - 'License :: OSI Approved :: Apache Software License', - 'Programming Language :: Python', - 'Programming Language :: Python :: 3', - 'Topic :: Utilities', - 'Topic :: Scientific/Engineering :: Visualization', - 'Framework :: Robot Framework :: Tool', - ], - license=license, - python_requires=">=3.7", - install_requires=[ - "numpy", - "matplotlib", - "pydot", - "networkx", - "dearpygui", - "graphviz", - "pygraphviz", - "pyyaml", - ], - # tests_require=['pytest'], - packages=find_packages(), - platforms=["linux", "unix"], - package_data={"dear_ros_node_viewer": ["setting.json", "font/*/*.ttf"]}, - entry_points=""" - [console_scripts] - dear_ros_node_viewer=dear_ros_node_viewer.__main__:main - """, -) diff --git a/src/dear_ros_node_viewer/__init__.py b/src/dear_ros_node_viewer/__init__.py new file mode 100644 index 0000000..c6b420c --- /dev/null +++ b/src/dear_ros_node_viewer/__init__.py @@ -0,0 +1,30 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +from . import caret_extend_callback_group +from . import caret_extend_path +from . import caret2networkx +from . import dear_ros_node_viewer +from . import dot2networkx +from . import graph_layout +from . import graph_manager +from . import graph_view +from . import graph_viewmodel +from . import logger_factory +from . import ros2networkx +from .dear_ros_node_viewer import main + +try: + from ._version import version +except: + from .version_dummy import version diff --git a/dear_ros_node_viewer/__main__.py b/src/dear_ros_node_viewer/__main__.py similarity index 93% rename from dear_ros_node_viewer/__main__.py rename to src/dear_ros_node_viewer/__main__.py index c8f40f9..c28d84d 100644 --- a/dear_ros_node_viewer/__main__.py +++ b/src/dear_ros_node_viewer/__main__.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -19,4 +19,4 @@ if __name__ == '__main__': - main() + main() diff --git a/src/dear_ros_node_viewer/caret2networkx.py b/src/dear_ros_node_viewer/caret2networkx.py new file mode 100644 index 0000000..bf73c0c --- /dev/null +++ b/src/dear_ros_node_viewer/caret2networkx.py @@ -0,0 +1,157 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" +Function to create NetworkX object from CARET architecture.yaml +""" + +from __future__ import annotations +import networkx as nx +import matplotlib.pyplot as plt +import yaml +from .logger_factory import LoggerFactory + +logger = LoggerFactory.create(__name__) + + +def quote_name(name: str) -> str: + """ + Quote name, because pydot requires. https://github.com/pydot/pydot/issues/258 + + Parameters + ---------- + name : str + original name + + Returns + ------- + modified_name : str + name with '"' + """ + modified_name = '"' + name + '"' + return modified_name + + +def parse_all_graph(yml, node_name_list, topic_pub_dict, topic_sub_dict): + """Parse architecture file""" + nodes = yml['nodes'] + for node in nodes: + node_name = quote_name(node['node_name']) + node_name_list.append(node_name) + if 'publishes' in node: + publishes = node['publishes'] + for publish in publishes: + if publish['topic_name'] in topic_pub_dict: + topic_pub_dict[publish['topic_name']].append(node_name) + else: + topic_pub_dict[publish['topic_name']] = [node_name] + if 'subscribes' in node: + subscribes = node['subscribes'] + for subscribe in subscribes: + if subscribe['topic_name'] in topic_sub_dict: + topic_sub_dict[subscribe['topic_name']].append(node_name) + else: + topic_sub_dict[subscribe['topic_name']] = [node_name] + + +def parse_target_path(yml, node_name_list, topic_pub_dict, topic_sub_dict): + """Parse architecture file""" + named_paths = yml['named_paths'] + if len(named_paths) > 0: + for named_path in named_paths: + node_chain = named_path['node_chain'] + for node in node_chain: + node_name = quote_name(node['node_name']) + node_name_list.append(node_name) + if node['publish_topic_name'] != 'UNDEFINED': + topic_pub_dict[node['publish_topic_name']] = [node_name] + if node['subscribe_topic_name'] != 'UNDEFINED': + topic_sub_dict[node['subscribe_topic_name']] = [node_name] + else: + logger.warning('named_paths not found') + + +def make_graph_from_topic_association(topic_pub_dict: dict[str, list[str]], + topic_sub_dict: dict[str, list[str]]): + """make graph from topic association""" + graph = nx.DiGraph() + for topic, node_pub_list in topic_pub_dict.items(): + if topic in topic_sub_dict: + node_sub_list = topic_sub_dict[topic] + else: + # node_sub_list = ["none:" + topic] + continue + for node_pub in node_pub_list: + for node_sub in node_sub_list: + # logger.debug(topic, node_pub, node_sub) + graph.add_edge(node_pub, node_sub, label=topic) + + return graph + + +def caret2networkx(filename: str, target_path: str = 'all_graph', + ignore_unconnected=True) -> nx.classes.digraph.DiGraph: + """ + Create NetworkX Graph from architecture.yaml generated by CARET + + Parameters + ---------- + filename : str + path to architecture file (e.g. '/home/abc/architecture.yaml') + target_path : str, default all_graph + 'all_graph': create a graph including all node and path + 'all_targets': create a graph including all paths in named_paths + path name: create a graph including path name in named_paths + + Returns + ------- + graph : nx.classes.digraph.DiGraph + NetworkX Graph + """ + + node_name_list: list[str] = [] + + # "/topic_0": ["/node_0", ], <- publishers of /topic_0 are ["/node_0", ] # + topic_pub_dict: dict[str, list[str]] = {} + + # "/topic_0": ["/node_1", ], <- subscribers of /topic_0 are ["/node_1", ] # + topic_sub_dict: dict[str, list[str]] = {} + + with open(filename, encoding='UTF-8') as file: + yml = yaml.safe_load(file) + if target_path == 'all_graph': + parse_all_graph(yml, node_name_list, topic_pub_dict, topic_sub_dict) + else: + parse_target_path(yml, node_name_list, topic_pub_dict, topic_sub_dict) + + graph = make_graph_from_topic_association(topic_pub_dict, topic_sub_dict) + + if not ignore_unconnected: + graph.add_nodes_from(node_name_list) + + logger.info('len(connected_nodes) = %d, len(nodes) = %d', + len(graph.nodes), len(node_name_list)) + + return graph + + +if __name__ == '__main__': + def local_main(): + """main function for this file""" + graph = caret2networkx('architecture.yaml') + pos = nx.spring_layout(graph) + # pos = nx.circular_layout(graph) + nx.draw_networkx(graph, pos) + plt.show() + + local_main() diff --git a/src/dear_ros_node_viewer/caret_extend_callback_group.py b/src/dear_ros_node_viewer/caret_extend_callback_group.py new file mode 100644 index 0000000..86d3d9b --- /dev/null +++ b/src/dear_ros_node_viewer/caret_extend_callback_group.py @@ -0,0 +1,162 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" +Function for additional information from CARET +""" + +from __future__ import annotations +import random +import networkx as nx +import yaml +from .caret2networkx import quote_name +from .logger_factory import LoggerFactory + +logger = LoggerFactory.create(__name__) + + +def create_dict_cbgroup2executor(yml: yaml) -> tuple[dict, dict]: + """Create dictionary of CallbackGroupName->Executor, CallbackGroupName->Color""" + dict_cbgroup2executor = {} + dict_cbgroup2color = {} + executors = yml['executors'] + for executor in executors: + executor_name = executor['executor_name'] + executor_type = executor['executor_type'] + callback_group_names = executor['callback_group_names'] + color = [255, 255, 255] + if len(callback_group_names) > 1: + color = [random.randint(96, 255), random.randint(96, 255), random.randint(0, 128)] + for callback_group_name in callback_group_names: + dict_cbgroup2executor[callback_group_name] = executor_name + ', ' + executor_type[:6] + dict_cbgroup2color[callback_group_name] = color + return dict_cbgroup2executor, dict_cbgroup2color + + +def create_callback_detail(callbacks: list[dict], callback_name: str) -> dict: + """ + Create detail information of callback + + Note + --- + example: + { + "callback_name": "callback_name", + "callback_type": "subscription_callback", + "description": "/topic_sub3pub1" + } + """ + callback_detail = {} + for callback in callbacks: + callback_type = callback['callback_type'] + if callback_name == callback['callback_name']: + callback_detail = {} + callback_detail['callback_name'] = callback_name + if callback_type == 'subscription_callback': + callback_detail['callback_type'] = 'sub' + callback_detail['description'] = callback['topic_name'] + elif callback_type == 'timer_callback': + callback_detail['callback_type'] = 'timer' + period_ms = float(callback['period_ns']) / 1e6 + callback_detail['description'] = str(period_ms) + 'ms' + else: + logger.warning("unexpected callback type") + callback_detail['callback_type'] = callback_type + callback_detail['description'] = '' + return callback_detail + logger.error('callback_name not found: %s', callback_name) + return None + + +def create_callback_group_list(node, dict_cbgroup2executor, dict_cbgroup2color): + """ + Create information of callback group for a node + + Note + --- + example: + [ + { + "callback_group_name": "callback_group_name", + "callback_group_type": "callback_group_type", + "executor_name": "executor_name", + "color": [255, 0, 0], + "callback_detail_list": [ + { + "callback_name": "callback_name", + "callback_type": "subscription_callback", + "description": "/topic_sub3pub1" + }, + ] + } + ] + """ + + callback_group_list = [] + if 'callback_groups' not in node or 'callbacks' not in node: + return callback_group_list + + callback_groups = node['callback_groups'] + callbacks = node['callbacks'] + for callback_group in callback_groups: + callback_group_info = {} + callback_group_name = callback_group['callback_group_name'] + callback_group_type = callback_group['callback_group_type'] + callback_names = callback_group['callback_names'] + callback_group_info['callback_group_name'] = callback_group_name + callback_group_info['callback_group_type'] = callback_group_type + callback_group_info['executor_name'] = dict_cbgroup2executor[callback_group_name] + callback_group_info['color'] = dict_cbgroup2color[callback_group_name] + callback_group_info['callback_detail_list'] = [] + for callback_name in callback_names: + callback_detail = create_callback_detail(callbacks, callback_name) + if callback_detail: + callback_group_info['callback_detail_list'].append(callback_detail) + callback_group_list.append(callback_group_info) + return callback_group_list + + +def create_dict_node_callbackgroup(yml): + """ + Create dictionary Node->CallbackGroupInfo + + Note + --- + example: + { + "node_name": [callback_group_list] + } + """ + dict_cbgroup2executor, dict_cbgroup2color = create_dict_cbgroup2executor(yml) + dict_node_cbgroup = {} + nodes = yml['nodes'] + for node in nodes: + node_name = quote_name(node['node_name']) + callback_group_list = create_callback_group_list(node, dict_cbgroup2executor, + dict_cbgroup2color) + dict_node_cbgroup[node_name] = callback_group_list + return dict_node_cbgroup + + +def extend_callback_group(filename: str, + graph: nx.classes.digraph.DiGraph) -> nx.classes.digraph.DiGraph: + """Add callback group info to a graph""" + with open(filename, encoding='UTF-8') as file: + yml = yaml.safe_load(file) + dict_node_cbgroup = create_dict_node_callbackgroup(yml) + # import json + # with open('caret_executor.json', encoding='UTF-8', mode='w') as f_caret_executor: + # json.dump(dict_node_cbgroup, f_caret_executor, ensure_ascii=True, indent=4) + for node_name in graph.nodes: + graph.nodes[node_name]['callback_group_list'] = dict_node_cbgroup[node_name] + return graph diff --git a/dear_ros_node_viewer/caret_extend_path.py b/src/dear_ros_node_viewer/caret_extend_path.py similarity index 52% rename from dear_ros_node_viewer/caret_extend_path.py rename to src/dear_ros_node_viewer/caret_extend_path.py index 756dd46..1f3c72a 100644 --- a/dear_ros_node_viewer/caret_extend_path.py +++ b/src/dear_ros_node_viewer/caret_extend_path.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -16,21 +16,21 @@ """ from __future__ import annotations import yaml -from dear_ros_node_viewer.caret2networkx import quote_name +from .caret2networkx import quote_name def get_path_dict(filename: str) -> dict: - """Get target path information""" - path_dict = {} - with open(filename, encoding='UTF-8') as file: - yml = yaml.safe_load(file) - path_info_list = yml['named_paths'] - for path_info in path_info_list: - path_name = path_info['path_name'] - node_chain = path_info['node_chain'] - node_name_list = [] - for node in node_chain: - node_name_list.append(quote_name(node['node_name'])) - path_dict[path_name] = node_name_list + """Get target path information""" + path_dict = {} + with open(filename, encoding='UTF-8') as file: + yml = yaml.safe_load(file) + path_info_list = yml['named_paths'] + for path_info in path_info_list: + path_name = path_info['path_name'] + node_chain = path_info['node_chain'] + node_name_list = [] + for node in node_chain: + node_name_list.append(quote_name(node['node_name'])) + path_dict[path_name] = node_name_list - return path_dict + return path_dict diff --git a/src/dear_ros_node_viewer/dear_ros_node_viewer.py b/src/dear_ros_node_viewer/dear_ros_node_viewer.py new file mode 100644 index 0000000..91cb4c2 --- /dev/null +++ b/src/dear_ros_node_viewer/dear_ros_node_viewer.py @@ -0,0 +1,100 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" +Main function for Dear ROS Node Viewer +""" + +from __future__ import annotations +import os +import argparse +import json +from .logger_factory import LoggerFactory +from .graph_view import GraphView + +logger = LoggerFactory.create(__name__) + + +def get_font_path(font_name: str) -> str: + """find font_path from font_name""" + if font_name[:4] == 'font': + font_path = os.path.dirname(__file__) + '/' + font_name + return font_path + return font_name + + +def load_setting_json(graph_file): + """ + Load JSON setting file + Set default values if the file doesn't exist + """ + if os.path.dirname(graph_file): + setting_file = os.path.dirname(graph_file) + '/setting.json' + else: + setting_file = './setting.json' + if not os.path.isfile(setting_file): + logger.info('Unable to find %s. Use default setting', setting_file) + setting_file = os.path.dirname(__file__) + '/setting.json' + + if os.path.isfile(setting_file): + with open(setting_file, encoding='UTF-8') as f_setting: + setting = json.load(f_setting) + app_setting = setting['app_setting'] + group_setting = setting['group_setting'] + else: + # Incase, default setting file was not found, too + logger.info('Unable to find %s. Use fixed default setting', setting_file) + app_setting = { + "window_size": [1920, 1080], + "font": "font/roboto/Roboto-Medium.ttf", + "ignore_unconnected_nodes": True, + } + group_setting = { + "__others__": { + "direction": "horizontal", + "offset": [-0.5, -0.5, 1.0, 1.0], + "color": [16, 64, 96] + } + } + + app_setting['font'] = get_font_path(app_setting['font']) + + return app_setting, group_setting + + +def parse_args(): + """ Parse arguments """ + parser = argparse.ArgumentParser( + description='Dear RosNodeViewer: Visualize ROS2 Node Graph') + parser.add_argument( + 'graph_file', type=str, nargs='?', default='architecture.yaml', + help='Graph file path. e.g. architecture.yaml(CARET) or rosgraph.dot(rqt_graph).\ + default=architecture.yaml') + args = parser.parse_args() + + logger.debug('args.graph_file = %s', args.graph_file) + + return args + + +def main(): + """ + Main function for Dear ROS Node Viewer + """ + args = parse_args() + + app_setting, group_setting = load_setting_json(args.graph_file) + graph_filename = args.graph_file + + dpg = GraphView(app_setting, group_setting) + dpg.start(graph_filename, app_setting['window_size'][0], app_setting['window_size'][1]) diff --git a/src/dear_ros_node_viewer/dot2networkx.py b/src/dear_ros_node_viewer/dot2networkx.py new file mode 100644 index 0000000..1c90836 --- /dev/null +++ b/src/dear_ros_node_viewer/dot2networkx.py @@ -0,0 +1,113 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" +Function to create NetworkX object from dot graph file (rosgraph.dot) +""" + +from __future__ import annotations +import networkx as nx +import matplotlib.pyplot as plt + +from .logger_factory import LoggerFactory +from .caret2networkx import make_graph_from_topic_association + +logger = LoggerFactory.create(__name__) + + +def dot2networkx_nodeonly(graph_org: nx.classes.digraph.DiGraph, + ignore_unconnected=True) -> nx.classes.digraph.DiGraph: + """Create NetworkX Object from dot graph file (nodes only) by rqt_graph""" + graph = nx.DiGraph() + for node_org in graph_org.nodes: + if 'label' not in graph_org.nodes[node_org]: + continue + label = graph_org.nodes[node_org]['label'] + if not ignore_unconnected: + graph.add_node(label) + + for edge in graph_org.edges: + node_pub = graph_org.nodes[edge[0]]['label'] + node_sub = graph_org.nodes[edge[1]]['label'] + label = graph_org.edges[edge]['label'] + graph.add_edge(node_pub, node_sub, label=label) + + return graph + + +def dot2networkx_nodetopic(graph_org: nx.classes.digraph.DiGraph) -> nx.classes.digraph.DiGraph: + """Create NetworkX Object from dot graph file (nodes / topics) by rqt_graph""" + + # "/topic_0": ["/node_0", ], <- publishers of /topic_0 are ["/node_0", ] # + topic_pub_dict: dict[str, list[str]] = {} + + # "/topic_0": ["/node_1", ], <- subscribers of /topic_0 are ["/node_1", ] # + topic_sub_dict: dict[str, list[str]] = {} + + for edge in graph_org.edges: + src = graph_org.nodes[edge[0]] + dst = graph_org.nodes[edge[1]] + if not ('label' in src and 'label' in dst and 'shape' in src and 'shape' in dst): + continue + src_name = src['label'] + dst_name = dst['label'] + src_is_node = bool(src['shape'] == 'ellipse') + dst_is_node = bool(dst['shape'] == 'ellipse') + + if src_is_node is True and dst_is_node is False: + if dst_name in topic_pub_dict: + topic_pub_dict[dst_name].append(src_name) + else: + topic_pub_dict[dst_name] = [src_name] + elif src_is_node is False and dst_is_node is True: + if src_name in topic_sub_dict: + topic_sub_dict[src_name].append(dst_name) + else: + topic_sub_dict[src_name] = [dst_name] + + graph = make_graph_from_topic_association(topic_pub_dict, topic_sub_dict) + + return graph + + +def dot2networkx(filename: str, ignore_unconnected=True) -> nx.classes.digraph.DiGraph: + """Function to create NetworkX object from dot graph file (rosgraph.dot)""" + graph_org = nx.DiGraph(nx.nx_pydot.read_dot(filename)) + + is_node_only = True + for node_org in graph_org.nodes: + if 'shape' in graph_org.nodes[node_org]: + if graph_org.nodes[node_org]['shape'] == 'box': + is_node_only = False + break + + if is_node_only: + graph = dot2networkx_nodeonly(graph_org, ignore_unconnected) + else: + graph = dot2networkx_nodetopic(graph_org) + + logger.info('len(connected_nodes) = %d', len(graph.nodes)) + + return graph + + +if __name__ == '__main__': + def local_main(): + """main function for this file""" + graph = dot2networkx('rosgraph_nodeonly.dot') + pos = nx.spring_layout(graph) + # pos = nx.circular_layout(graph) + nx.draw_networkx(graph, pos) + plt.show() + + local_main() diff --git a/dear_ros_node_viewer/font/roboto/Roboto-Medium.ttf b/src/dear_ros_node_viewer/font/roboto/Roboto-Medium.ttf similarity index 100% rename from dear_ros_node_viewer/font/roboto/Roboto-Medium.ttf rename to src/dear_ros_node_viewer/font/roboto/Roboto-Medium.ttf diff --git a/src/dear_ros_node_viewer/graph_layout.py b/src/dear_ros_node_viewer/graph_layout.py new file mode 100644 index 0000000..c313788 --- /dev/null +++ b/src/dear_ros_node_viewer/graph_layout.py @@ -0,0 +1,163 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" Function to layout node in graph (NetworkX) """ +from __future__ import annotations +import numpy as np +import networkx as nx + +from .logger_factory import LoggerFactory + +logger = LoggerFactory.create(__name__) + + +def place_node_by_group(graph, group_setting): + """ + Place all nodes + Nodes belonging to the same group are placed in the same area. + The area is specified in group_setting.group_setting + """ + + # for node_name in graph.nodes: + # graph.nodes[node_name]['pos'] = [0, 0] + # graph.nodes[node_name]['color'] = [128, 128, 128] + + # Add "__other__" if a node doesn't belong to any group to make process easier # + mapping_list = {} + for node_name in graph.nodes: + is_other_node = True + for group_name in group_setting.keys(): + if group_name in node_name: + is_other_node = False + if is_other_node: + mapping_list[node_name] = '"' + '__others__' + node_name.strip('"') + '"' + else: + mapping_list[node_name] = node_name + graph = nx.relabel_nodes(graph, mapping_list) + + # Place nodes and add properties into graph # + for group_name, graph_property in group_setting.items(): + layout = place_node(graph, group_name) + direction = graph_property['direction'] + offset = graph_property['offset'] + color = graph_property['color'] + + for node_name in graph.nodes: + if group_name in node_name: + pos = layout[node_name] + pos[1] = 1 - pos[1] # 0.0 is top, 1.0 is bottom + if direction == 'horizontal': + graph.nodes[node_name]['pos'] = \ + [offset[0] + pos[1] * offset[2], offset[1] + pos[0] * offset[3]] + else: + graph.nodes[node_name]['pos'] = \ + [offset[0] + pos[0] * offset[2], offset[1] + pos[1] * offset[3]] + graph.nodes[node_name]['color'] = color + + # Remove "__other__" # + mapping_list_swap = {v: k for k, v in mapping_list.items()} + graph = nx.relabel_nodes(graph, mapping_list_swap) + + return graph + + +def place_node(graph: nx.classes.digraph.DiGraph, group_name: str, prog: str = 'dot'): + """ + Place nodes belonging to group. + Normalized position [x, y] is set to graph.nodes[node]['pos'] + + Parameters + ---------- + graph: nx.classes.digraph.DiGraph + NetworkX Graph + group_name: str + group name + prog: str (default: 'dot') + Name of the GraphViz command to use for layout. + Options depend on GraphViz version but may include: + 'dot', 'twopi', 'fdp', 'sfdp', 'circo' + + Returns + ------- + layout: dict[str,tuple[int,int]] + Dictionary of normalized positions keyed by node. + """ + + graph_modified = nx.DiGraph() + for node_name in graph.nodes: + if group_name in node_name: + graph_modified.add_node(node_name) + for edge in graph.edges: + if group_name in edge[0] and group_name in edge[1]: + graph_modified.add_edge(edge[0], edge[1]) + try: + layout = nx.nx_pydot.pydot_layout(graph_modified, prog=prog) + except: + print('Please install "apt install graphviz"') + exit(1) + layout = normalize_layout(layout) + return layout + + +def normalize_layout(layout: dict[str, tuple[int, int]]): + """ + Normalize positions to [0.0, 1.0] (left-top = (0, 0)) + + Parameters + ---------- + layout: dict[str,tuple[int,int]] + Dictionary of positions keyed by node. + + Returns + ------- + layout: dict[str,tuple[int,int]] + Dictionary of normalized positions keyed by node. + """ + + if len(layout) == 0: + return layout + for key, val in layout.items(): + layout[key] = list(val) + layout_np = np.array(list(layout.values())) + layout_min, layout_max = layout_np.min(0), layout_np.max(0) + norm_w = max((layout_max[0] - layout_min[0]), 1) + norm_h = max((layout_max[1] - layout_min[1]), 1) + if norm_w == 0 or norm_h == 0: + return layout + for pos in layout.values(): + pos[0] = (pos[0] - layout_min[0]) / norm_w + pos[1] = (pos[1] - layout_min[1]) / norm_h + return layout + + +def align_layout(graph): + """ + Set (max+min) / 2 as origin(0, 0) + + Note: + This logis is not mandatory. I added this just to make zoom a little better + Without this, zoom in/out is processed based on (0,0)=left-top + When Dear PyGui support zoomable node editor, this logic is not needed + """ + layout_np = np.array(list(map(lambda val: val['pos'], graph.nodes.values()))) + layout_min, layout_max = layout_np.min(0), layout_np.max(0) + offset_x = (layout_max[0] + layout_min[0]) / 2 + offset_y = (layout_max[1] + layout_min[1]) / 2 + # offset_x -= 2 / (layout_max[0] - layout_min[0]) + # offset_y -= 2 / (layout_max[1] - layout_min[1]) + if offset_x == 0 or offset_y == 0: + return graph + for node_name in graph.nodes: + graph.nodes[node_name]['pos'][0] -= offset_x + graph.nodes[node_name]['pos'][1] -= offset_y + return graph diff --git a/src/dear_ros_node_viewer/graph_manager.py b/src/dear_ros_node_viewer/graph_manager.py new file mode 100644 index 0000000..9c6bba6 --- /dev/null +++ b/src/dear_ros_node_viewer/graph_manager.py @@ -0,0 +1,108 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +"""Class to manage graph (NetworkX)""" +from __future__ import annotations +import os +import re +import networkx as nx +from .logger_factory import LoggerFactory +from .caret2networkx import caret2networkx +from .caret_extend_callback_group import extend_callback_group +from .caret_extend_path import get_path_dict +from .dot2networkx import dot2networkx +from .ros2networkx import Ros2Networkx +from .graph_layout import place_node_by_group, align_layout + +logger = LoggerFactory.create(__name__) + + +class GraphManager: + """Class to manage graph (NetworkX)""" + def __init__(self, app_setting, group_setting): + self.app_setting = app_setting + self.group_setting = group_setting + self.dir = './' + self.graph: nx.DiGraph = nx.DiGraph() + self.caret_path_dict: dict = {} + + def load_graph_from_caret(self, filename: str, target_path: str = 'all_graph'): + """ load_graph_from_caret """ + self.graph = caret2networkx(filename, target_path, + self.app_setting['ignore_unconnected_nodes']) + self.graph = extend_callback_group(filename, self.graph) + self.load_graph_postprocess(filename) + self.caret_path_dict.update(get_path_dict(filename)) + + def load_graph_from_dot(self, filename: str): + """ load_graph_from_dot """ + self.graph = dot2networkx(filename, self.app_setting['ignore_unconnected_nodes']) + self.load_graph_postprocess(filename) + + def load_graph_from_running_ros(self): + """ load_graph_from_running_ros """ + ros2networkx = Ros2Networkx(node_name='temp') + ros2networkx.save_graph('./temp.dot') + ros2networkx.shutdown() + self.load_graph_from_dot('./temp.dot') + # for node in self.graph.nodes: + # if '"/temp"' == node: + # node_observer = node + # break + # self.graph.remove_node(node_observer) + # self.reset_internl_status() + + def load_graph_postprocess(self, filename): + """ Common process after loading graph """ + self.dir = os.path.dirname(filename) + '/' if os.path.dirname(filename) != '' else './' + self.clear_caret_path_dict() + self.filter_topic() # delete topic before node + self.filter_node() + if len(self.graph.nodes): + self.graph = place_node_by_group(self.graph, self.group_setting) + self.graph = align_layout(self.graph) + + def filter_node(self): + """Remove nodes which match filter setting""" + remove_node_list = [] + for node_name in self.graph.nodes: + node_name_org = node_name.strip('"') + for pattern in self.app_setting['ignore_node_list']: + if re.fullmatch(pattern, node_name_org): + remove_node_list.append(node_name) + break + self.graph.remove_nodes_from(remove_node_list) + logger.info('%s nodes are removed by filter', len(remove_node_list)) + + def filter_topic(self): + """Remove topics which match filter setting""" + remove_edge_list = [] + for edge in self.graph.edges: + topic_name = self.graph.edges[edge]['label'] + topic_name = topic_name.strip('"') + for pattern in self.app_setting['ignore_topic_list']: + if re.fullmatch(pattern, topic_name): + remove_edge_list.append(edge) + break + self.graph.remove_edges_from(remove_edge_list) + logger.info('%s topics are removed by filter', len(remove_edge_list)) + + if self.app_setting['ignore_unconnected_nodes']: + isolated_node_list = list(nx.isolates(self.graph)) + logger.info('%s nodes are removed due to isolated', len(isolated_node_list)) + self.graph.remove_nodes_from(isolated_node_list) + + def clear_caret_path_dict(self): + """ Clear CARET path dict """ + self.caret_path_dict.clear() + self.caret_path_dict['<< CLEAR >>'] = [] diff --git a/src/dear_ros_node_viewer/graph_view.py b/src/dear_ros_node_viewer/graph_view.py new file mode 100644 index 0000000..035d672 --- /dev/null +++ b/src/dear_ros_node_viewer/graph_view.py @@ -0,0 +1,382 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +"""Class to display node graph""" +from __future__ import annotations +import networkx as nx +import dearpygui.dearpygui as dpg +from .logger_factory import LoggerFactory +from .graph_viewmodel import GraphViewModel + +logger = LoggerFactory.create(__name__) + + +class GraphView: + """Class to display node graph""" + # Color definitions + COLOR_NODE_SELECTED = [0, 0, 64] + COLOR_NODE_BAR = [32, 32, 32] + COLOR_NODE_BACK = [64, 64, 64] + + def __init__( + self, + app_setting: dict, + group_setting: dict + ): + + self.app_setting: dict = app_setting + self.graph_viewmodel = GraphViewModel(app_setting, group_setting) + self.font_size: int = 15 + self.font_list: dict[int, int] = {} + self.dpg_window_id: int = -1 + self.dpg_id_editor: int = -1 + self.dpg_id_caret_path: int = -1 + + def start(self, graph_filename: str, window_width: int = 1920, window_height: int = 1080): + """ Start Dear PyGui context """ + dpg.create_context() + dpg.create_viewport( + title='Dear RosNodeViewer', width=window_width, height=window_height,) + dpg.setup_dearpygui() + + self._make_font_table(self.app_setting['font']) + with dpg.handler_registry(): + dpg.add_mouse_wheel_handler(callback=self._cb_wheel) + dpg.add_key_press_handler(callback=self._cb_key_press) + + with dpg.window( + pos=[0, 0], + width=window_width, height=window_height, + no_collapse=True, no_title_bar=True, no_move=True, + no_resize=True) as self.dpg_window_id: + + self.add_menu_in_dpg() + + self.graph_viewmodel.load_graph(graph_filename) + self.update_node_editor() + + # Update node position and font according to the default graph size and font size + self._cb_wheel(0, 0) + self._cb_menu_font_size(None, self.font_size, None) + + dpg.set_viewport_resize_callback(self._cb_resize) + dpg.show_viewport() + dpg.start_dearpygui() + dpg.destroy_context() + + def update_node_editor(self): + """Update node editor""" + if self.dpg_id_editor != -1: + dpg.delete_item(self.dpg_id_editor) + + with dpg.window(tag=self.dpg_window_id): + with dpg.node_editor( + menubar=False, minimap=True, + minimap_location=dpg.mvNodeMiniMap_Location_BottomLeft) as self.dpg_id_editor: + self.add_node_in_dpg() + self.add_link_in_dpg() + self.graph_viewmodel.load_layout() + + # Add CARET path + for path_name, _ in self.graph_viewmodel.graph_manager.caret_path_dict.items(): + dpg.add_menu_item(label=path_name, callback=self._cb_menu_caret_path, + parent=self.dpg_id_caret_path) + + def add_menu_in_dpg(self): + """ Add menu bar """ + with dpg.menu_bar(): + with dpg.menu(label="Layout"): + dpg.add_menu_item(label="Reset", callback=self._cb_menu_layout_reset) + dpg.add_menu_item(label="Save", callback=self._cb_menu_layout_save, shortcut='(s)') + dpg.add_menu_item(label="Load", callback=self._cb_menu_layout_load, shortcut='(l)') + + dpg.add_menu_item(label="Copy", callback=self._cb_menu_copy, shortcut='(c)') + + with dpg.menu(label="ROS"): + dpg.add_menu_item(label="Load Current Gaph", + callback=self._cb_menu_graph_current) + + with dpg.menu(label="Font"): + dpg.add_slider_int(label="Font Size", + default_value=self.font_size, min_value=8, max_value=40, + callback=self._cb_menu_font_size) + + with dpg.menu(label="NodeName"): + dpg.add_menu_item(label="Full", callback=self._cb_menu_nodename_full) + dpg.add_menu_item(label="First + Last", callback=self._cb_menu_nodename_firstlast) + dpg.add_menu_item(label="Last Only", callback=self._cb_menu_nodename_last) + + with dpg.menu(label="EdgeName"): + dpg.add_menu_item(label="Full", callback=self._cb_menu_edgename_full) + dpg.add_menu_item(label="First + Last", callback=self._cb_menu_edgename_firstlast) + dpg.add_menu_item(label="Last Only", callback=self._cb_menu_edgename_last) + + with dpg.menu(label="CARET"): + dpg.add_menu_item(label="Show Callback", callback=self._cb_menu_caret_callbackbroup) + with dpg.menu(label="PATH") as self.dpg_id_caret_path: + pass + + def add_node_in_dpg(self): + """ Add nodes and attributes """ + graph = self.graph_viewmodel.get_graph() + for node_name in graph.nodes: + # Calculate position in window + pos = graph.nodes[node_name]['pos'] + pos = [ + pos[0] * self.graph_viewmodel.graph_size[0], + pos[1] * self.graph_viewmodel.graph_size[1]] + + # Allocate node + with dpg.node(label=node_name, pos=pos) as node_id: + # Save node id + self.graph_viewmodel.add_dpg_node_id(node_name, node_id) + + # Set color + with dpg.theme() as theme_id: + with dpg.theme_component(dpg.mvNode): + dpg.add_theme_color( + dpg.mvNodeCol_TitleBar, + graph.nodes[node_name]['color'] + if 'color' in graph.nodes[node_name] + else self.COLOR_NODE_BAR, + category=dpg.mvThemeCat_Nodes) + dpg.add_theme_color( + dpg.mvNodeCol_NodeBackgroundSelected, + self.COLOR_NODE_SELECTED, + category=dpg.mvThemeCat_Nodes) + theme_color = dpg.add_theme_color( + dpg.mvNodeCol_NodeBackground, + self.COLOR_NODE_BACK, + category=dpg.mvThemeCat_Nodes) + # Set color value + self.graph_viewmodel.add_dpg_node_color(node_name, theme_color) + dpg.bind_item_theme(node_id, theme_id) + + # Set callback + with dpg.item_handler_registry() as node_select_handler: + dpg.add_item_clicked_handler(callback=self._cb_node_clicked) + dpg.bind_item_handler_registry(node_id, node_select_handler) + + # Add text for node I/O(topics) + self.add_node_attr_in_dpg(node_name) + + self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.LAST) + self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.LAST) + + def add_node_attr_in_dpg(self, node_name): + """ Add attributes in node """ + graph = self.graph_viewmodel.get_graph() + edge_list_pub = [] + edge_list_sub = [] + for edge in graph.edges: + if edge[0] == node_name: + label = graph.edges[edge]['label'] if 'label' in graph.edges[edge] else 'out' + if label in edge_list_pub: + continue + edge_list_pub.append(label) + if edge[1] == node_name: + label = graph.edges[edge]['label'] if 'label' in graph.edges[edge] else 'in' + if label in edge_list_sub: + continue + edge_list_sub.append(label) + + for edge in edge_list_sub: + with dpg.node_attribute(attribute_type=dpg.mvNode_Attr_Input) as attr_id: + text_id = dpg.add_text(default_value=edge) + self.graph_viewmodel.add_dpg_nodeedge_idtext(node_name, edge, attr_id, text_id) + for edge in edge_list_pub: + with dpg.node_attribute(attribute_type=dpg.mvNode_Attr_Output) as attr_id: + text_id = dpg.add_text(default_value=edge) + self.graph_viewmodel.add_dpg_nodeedge_idtext(node_name, edge, + attr_id, text_id) + + # Add text for executor/callbackgroups + self.add_node_callbackgroup_in_dpg(node_name) + # Hide by default + self.graph_viewmodel.display_callbackgroup(False) + + def add_node_callbackgroup_in_dpg(self, node_name): + """ Add callback group information """ + graph = self.graph_viewmodel.get_graph() + if 'callback_group_list' in graph.nodes[node_name]: + callback_group_list = graph.nodes[node_name]['callback_group_list'] + for callback_group in callback_group_list: + executor_name = callback_group['executor_name'] + callback_group_name = callback_group['callback_group_name'] + # callback_group_type = callback_group['callback_group_type'] + callback_group_name = self.graph_viewmodel.omit_name( + callback_group_name, GraphViewModel.OmitType.LAST) + callback_detail_list = callback_group['callback_detail_list'] + color = callback_group['color'] + with dpg.node_attribute() as attr_id: + dpg.add_text('=== Callback Group [' + executor_name + '] ===', color=color) + for callback_detail in callback_detail_list: + # callback_name = callback_detail['callback_name'] + callback_type = callback_detail['callback_type'] + description = callback_detail['description'] + description = self.graph_viewmodel.omit_name( + description, GraphViewModel.OmitType.LAST) + dpg.add_text(default_value='cb_' + callback_type + ': ' + description, + color=color) + self.graph_viewmodel.add_dpg_callbackgroup_id( + callback_group['callback_group_name'], attr_id) + + def add_link_in_dpg(self): + """ Add links between node I/O """ + graph = self.graph_viewmodel.get_graph() + for edge in graph.edges: + if 'label' in graph.edges[edge]: + label = graph.edges[edge]['label'] + edge_id = dpg.add_node_link( + self.graph_viewmodel.get_dpg_nodeedge_id(edge[0], label), + self.graph_viewmodel.get_dpg_nodeedge_id(edge[1], label)) + self.graph_viewmodel.add_dpg_id_edge(label, edge_id) + else: + edge_id = dpg.add_node_link( + self.graph_viewmodel.get_dpg_nodeedge_id(edge[0], 'out'), + self.graph_viewmodel.get_dpg_nodeedge_id(edge[1], 'in')) + + # Set color. color is the same color as publisher + with dpg.theme() as theme_id: + with dpg.theme_component(dpg.mvNodeLink): + theme_color = dpg.add_theme_color( + dpg.mvNodeCol_Link, + graph.nodes[edge[0]]['color'], + category=dpg.mvThemeCat_Nodes) + self.graph_viewmodel.add_dpg_edge_color(edge, theme_color) + dpg.bind_item_theme(edge_id, theme_id) + + def _cb_resize(self, sender, app_data): + """ + callback function for window resized (Dear PyGui) + change node editer size + """ + window_width = app_data[2] + window_height = app_data[3] + dpg.set_item_width(self.dpg_window_id, window_width) + dpg.set_item_height(self.dpg_window_id, window_height) + + def _cb_node_clicked(self, sender, app_data): + """ + change connedted node color + restore node color when re-clicked + """ + node_id = app_data[1] + self.graph_viewmodel.high_light_node(node_id) + + def _cb_wheel(self, sender, app_data): + """ + callback function for mouse wheel in node editor(Dear PyGui) + zoom in/out graph according to wheel direction + """ + self.graph_viewmodel.zoom_inout(app_data > 0) + + def _cb_key_press(self, sender, app_data): + """callback function for key press""" + if app_data == ord('S'): + self._cb_menu_layout_save() + elif app_data == ord('L'): + self._cb_menu_layout_load() + elif app_data == ord('C'): + self._cb_menu_copy() + + def _cb_menu_layout_reset(self): + """ Reset layout """ + self.graph_viewmodel.reset_layout() + + def _cb_menu_layout_save(self): + """ Save current layout """ + self.graph_viewmodel.save_layout() + + def _cb_menu_layout_load(self): + """ Load layout from file """ + self.graph_viewmodel.load_layout() + + def _cb_menu_copy(self): + self.graph_viewmodel.copy_selected_node_name(self.dpg_id_editor) + + def _cb_menu_graph_current(self): + """ Update graph using current ROS status """ + self.graph_viewmodel.load_running_graph() + self.update_node_editor() + + def _cb_menu_font_size(self, sender, app_data, user_data): + """ Change font size """ + self.font_size = app_data + if self.font_size in self.font_list: + self.graph_viewmodel.update_font(self.font_list[self.font_size]) + + def _cb_menu_nodename_full(self): + """ Display full name """ + self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.FULL) + + def _cb_menu_nodename_firstlast(self): + """ Display omitted name """ + self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.FIRST_LAST) + + def _cb_menu_nodename_last(self): + """ Display omitted name """ + self.graph_viewmodel.update_nodename(GraphViewModel.OmitType.LAST) + + def _cb_menu_edgename_full(self): + """ Display full name """ + self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.FULL) + + def _cb_menu_edgename_firstlast(self): + """ Display omitted name """ + self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.FIRST_LAST) + + def _cb_menu_edgename_last(self): + """ Display omitted name """ + self.graph_viewmodel.update_edgename(GraphViewModel.OmitType.LAST) + + def _cb_menu_caret_callbackbroup(self, sender, app_data, user_data): + """ Show callback group info """ + if dpg.get_item_label(sender) == 'Show Callback': + self.graph_viewmodel.display_callbackgroup(True) + dpg.set_item_label(sender, 'Hide Callback') + else: + self.graph_viewmodel.display_callbackgroup(False) + dpg.set_item_label(sender, 'Show Callback') + + def _cb_menu_caret_path(self, sender, app_data, user_data): + """ High light selected CARET path """ + path_name = dpg.get_item_label(sender) + self.graph_viewmodel.high_light_caret_path(path_name) + + def _make_font_table(self, font_path): + """Make font table""" + with dpg.font_registry(): + for i in range(8, 40): + try: + self.font_list[i] = dpg.add_font(font_path, i) + except SystemError: + logger.error('Failed to load font: %s', font_path) + + +if __name__ == '__main__': + def local_main(): + """main function for this file""" + graph = nx.DiGraph() + nx.add_path(graph, ['3', '5', '4', '1', '0', '2']) + nx.add_path(graph, ['3', '0', '4', '2', '1', '5']) + layout = nx.spring_layout(graph) + for key, val in layout.items(): + graph.nodes[key]['pos'] = list(val) + graph.nodes[key]['color'] = [128, 128, 128] + app_setting = { + "font": "/usr/share/fonts/truetype/ubuntu/Ubuntu-C.ttf" + } + GraphView(app_setting, graph) + + local_main() diff --git a/src/dear_ros_node_viewer/graph_viewmodel.py b/src/dear_ros_node_viewer/graph_viewmodel.py new file mode 100644 index 0000000..a5bb33a --- /dev/null +++ b/src/dear_ros_node_viewer/graph_viewmodel.py @@ -0,0 +1,340 @@ +# Copyright 2022 Tier IV, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +"""Class to bind graph and GUI components""" +from __future__ import annotations +import os +from enum import Enum +import textwrap +import json +import networkx as nx +import dearpygui.dearpygui as dpg +from .graph_manager import GraphManager +from .logger_factory import LoggerFactory + +logger = LoggerFactory.create(__name__) + + +class GraphViewModel: + """Class to bind graph and GUI components""" + # Color definitions + COLOR_HIGHLIGHT_SELECTED = [0, 0, 64] + COLOR_HIGHLIGHT_PUB = [0, 64, 0] + COLOR_HIGHLIGHT_SUB = [64, 0, 0] + COLOR_HIGHLIGHT_CARET_PATH = [0, 96, 0] + COLOR_HIGHLIGHT_DEF = [64, 64, 64] + COLOR_HIGHLIGHT_EDGE = [196, 196, 196] + + class OmitType(Enum): + """Name omission type""" + FULL = 1 + FIRST_LAST = 2 + LAST = 3 + + def __init__(self, + app_setting: dict, + group_setting: dict): + self.graph_size: list[int] = [1920, 1080] + self.graph_manager = GraphManager(app_setting, group_setting) + self.node_selected_dict: dict[str, bool] = {} # [node_name, is_selected] + + # bind list to components in PyGui + self.dpg_bind = { + 'node_id': {}, # {"node_name": id} + 'node_color': {}, # {"node_name": color_id} + 'nodeedge_id': {}, # {"nodename_edgename": attr_id} + 'nodeedge_text': {}, # {"nodename_edgename": text_id} + 'id_edge': {}, # {id: "edge_name"} + 'edge_color': {}, # {edge_obj: color_id} + 'callbackgroup_id': {}, # {"callback_group_name": attr_id} + } + + def get_graph(self) -> nx.DiGraph: + """Graph getter""" + return self.graph_manager.graph + + def load_running_graph(self): + """Load running ROS Graph""" + self.graph_manager.load_graph_from_running_ros() + self._reset_internl_status() + + def load_graph(self, graph_filename: str): + """Load Graph from file""" + if '.yaml' in graph_filename: + try: + self.graph_manager.load_graph_from_caret(graph_filename) + except FileNotFoundError as err: + logger.error(err) + elif '.dot' in graph_filename: + try: + self.graph_manager.load_graph_from_dot(graph_filename) + except FileNotFoundError as err: + logger.error(err) + else: + logger.error('Graph is not loaded. Unknown file format: %s', graph_filename) + # return # keep going + self._reset_internl_status() + + def _reset_internl_status(self): + """ Reset internal status """ + self.dpg_bind['node_id'].clear() + self.dpg_bind['node_color'].clear() + self.dpg_bind['nodeedge_id'].clear() + self.dpg_bind['nodeedge_text'].clear() + self.dpg_bind['id_edge'].clear() + self.dpg_bind['edge_color'].clear() + self.dpg_bind['callbackgroup_id'].clear() + self.node_selected_dict.clear() + for node_name in self.get_graph().nodes: + self.node_selected_dict[node_name] = False + + def add_dpg_node_id(self, node_name, dpg_id): + """ Add association b/w node_name and dpg_id """ + self.dpg_bind['node_id'][node_name] = dpg_id + + def add_dpg_node_color(self, node_name, dpg_id): + """ Add association b/w node_name and dpg_id """ + self.dpg_bind['node_color'][node_name] = dpg_id + + def add_dpg_nodeedge_idtext(self, node_name, edge_name, attr_id, text_id): + """ Add association b/w node_attr and dpg_id """ + key = self._make_nodeedge_key(node_name, edge_name) + self.dpg_bind['nodeedge_id'][key] = attr_id + self.dpg_bind['nodeedge_text'][key] = text_id + + def add_dpg_id_edge(self, edge_name, edge_id): + """ Add association b/w edge and dpg_id """ + self.dpg_bind['id_edge'][edge_id] = edge_name + + def add_dpg_edge_color(self, edge_name, edge_id): + """ Add association b/w edge and dpg_id """ + self.dpg_bind['edge_color'][edge_name] = edge_id + + def add_dpg_callbackgroup_id(self, callback_group_name, dpg_id): + """ Add association b/w callback_group_name and dpg_id """ + self.dpg_bind['callbackgroup_id'][callback_group_name] = dpg_id + + def get_dpg_nodeedge_id(self, node_name, edge_name): + """ Get association for a selected name """ + key = self._make_nodeedge_key(node_name, edge_name) + return self.dpg_bind['nodeedge_id'][key] + + def _make_nodeedge_key(self, node_name, edge_name): + """create dictionary key for topic attribute in node""" + return node_name + '###' + edge_name + + def high_light_node(self, dpg_id_node): + """ High light the selected node and connected nodes """ + graph = self.get_graph() + selected_node_name = [k for k, v in self.dpg_bind['node_id'].items() if v == dpg_id_node][0] + is_re_clicked = self.node_selected_dict[selected_node_name] + for node_name, _ in self.node_selected_dict.items(): + publishing_edge_list = [e for e in graph.edges if node_name in e[0]] + publishing_edge_subscribing_node_name_list = \ + [e[1] for e in graph.edges if e[0] == node_name] + subscribing_edge_list = [e for e in graph.edges if node_name in e[1]] + subscribing_edge_publishing_node_name_list = \ + [e[0] for e in graph.edges if e[1] == node_name] + if self.node_selected_dict[node_name]: + # Disable highlight for all the other nodes# + self.node_selected_dict[node_name] = False + dpg.set_value( + self.dpg_bind['node_color'][node_name], + self.COLOR_HIGHLIGHT_DEF) + for edge_name in publishing_edge_list: + dpg.set_value( + self.dpg_bind['edge_color'][edge_name], + graph.nodes[node_name]['color']) + for pub_node_name in publishing_edge_subscribing_node_name_list: + dpg.set_value( + self.dpg_bind['node_color'][pub_node_name], + self.COLOR_HIGHLIGHT_DEF) + for edge_name in subscribing_edge_list: + dpg.set_value( + self.dpg_bind['edge_color'][edge_name], + graph.nodes[node_name]['color']) # todo. incorrect color + for sub_node_name in subscribing_edge_publishing_node_name_list: + dpg.set_value( + self.dpg_bind['node_color'][sub_node_name], + self.COLOR_HIGHLIGHT_DEF) + break + + if not is_re_clicked: + # Enable highlight for the selected node # + publishing_edge_list = [e for e in graph.edges if selected_node_name in e[0]] + publishing_edge_subscribing_node_name_list = \ + [e[1] for e in graph.edges if e[0] == selected_node_name] + subscribing_edge_list = [e for e in graph.edges if selected_node_name in e[1]] + subscribing_edge_publishing_node_name_list = \ + [e[0] for e in graph.edges if e[1] == selected_node_name] + self.node_selected_dict[selected_node_name] = True + dpg.set_value( + self.dpg_bind['node_color'][selected_node_name], + self.COLOR_HIGHLIGHT_SELECTED) + for edge_name in publishing_edge_list: + dpg.set_value( + self.dpg_bind['edge_color'][edge_name], + self.COLOR_HIGHLIGHT_EDGE) + for pub_node_name in publishing_edge_subscribing_node_name_list: + dpg.set_value( + self.dpg_bind['node_color'][pub_node_name], + self.COLOR_HIGHLIGHT_PUB) + for edge_name in subscribing_edge_list: + dpg.set_value( + self.dpg_bind['edge_color'][edge_name], + self.COLOR_HIGHLIGHT_EDGE) + for sub_node_name in subscribing_edge_publishing_node_name_list: + dpg.set_value( + self.dpg_bind['node_color'][sub_node_name], + self.COLOR_HIGHLIGHT_SUB) + + def zoom_inout(self, is_zoom_in): + """ Zoom in/out """ + previous_graph_size = self.graph_size + if is_zoom_in: + self.graph_size = list(map(lambda val: val * 1.1, self.graph_size)) + else: + self.graph_size = list(map(lambda val: val * 0.9, self.graph_size)) + scale = (self.graph_size[0] / previous_graph_size[0], + self.graph_size[1] / previous_graph_size[1]) + + for _, node_id in self.dpg_bind['node_id'].items(): + pos = dpg.get_item_pos(node_id) + pos = (pos[0] * scale[0], pos[1] * scale[1]) + dpg.set_item_pos(node_id, pos) + + def reset_layout(self): + """ Reset node layout """ + for node_name, node_id in self.dpg_bind['node_id'].items(): + pos = self.get_graph().nodes[node_name]['pos'] + pos = (pos[0] * self.graph_size[0], pos[1] * self.graph_size[1]) + dpg.set_item_pos(node_id, pos) + + def load_layout(self): + """ Load node layout """ + graph = self.get_graph() + filename = self.graph_manager.dir + 'layout.json' + if not os.path.exists(filename): + logger.info('%s does not exist. Use auto layout', filename) + return + with open(filename, encoding='UTF-8') as f_layout: + pos_dict = json.load(f_layout) + for node_name, pos in pos_dict.items(): + if node_name in graph.nodes: + graph.nodes[node_name]['pos'] = pos + self.reset_layout() + + def save_layout(self): + """ Save node layout """ + pos_dict = {} + for node_name, node_id in self.dpg_bind['node_id'].items(): + pos = dpg.get_item_pos(node_id) + pos = (pos[0] / self.graph_size[0], pos[1] / self.graph_size[1]) + pos_dict[node_name] = pos + + filename = self.graph_manager.dir + '/layout.json' + with open(filename, encoding='UTF-8', mode='w') as f_layout: + json.dump(pos_dict, f_layout, ensure_ascii=True, indent=4) + + def update_font(self, font): + """ Update font used in all nodes according to current font size """ + for node_id in self.dpg_bind['node_id'].values(): + dpg.bind_item_font(node_id, font) + + def update_nodename(self, omit_type: OmitType): + """ Update node name """ + for node_name, node_id in self.dpg_bind['node_id'].items(): + dpg.set_item_label(node_id, self.omit_name(node_name, omit_type)) + + def update_edgename(self, omit_type: OmitType): + """ Update edge name """ + for nodeedge_name, text_id in self.dpg_bind['nodeedge_text'].items(): + edgename = nodeedge_name.split('###')[-1] + dpg.set_value(text_id, value=self.omit_name(edgename, omit_type)) + + def omit_name(self, name: str, omit_type: OmitType) -> str: + """ replace an original name to a name to be displayed """ + display_name = name.strip('"') + if omit_type == self.OmitType.FULL: + display_name = textwrap.fill(display_name, 60) + elif omit_type == self.OmitType.FIRST_LAST: + display_name = display_name.split('/') + if '' in display_name: + display_name.remove('') + if len(display_name) > 1: + display_name = '/' + display_name[0] + '/' + display_name[-1] + else: + display_name = '/' + display_name[0] + display_name = textwrap.fill(display_name, 50) + else: + display_name = display_name.split('/') + display_name = '/' + display_name[-1] + display_name = textwrap.fill(display_name, 40) + + return display_name + + def copy_selected_node_name(self, dpg_id_nodeeditor): + """Copy selected node names to clipboard""" + def get_key(dic, val): + for key, value in dic.items(): + if val == value: + return key + return None + + copied_str = '' + selected_nodes = dpg.get_selected_nodes(dpg_id_nodeeditor) + selected_links = dpg.get_selected_links(dpg_id_nodeeditor) + if len(selected_nodes) == 1: + copied_str = get_key(self.dpg_bind['node_id'], selected_nodes[0]) + copied_str = copied_str.strip('"') + print(copied_str) + elif len(selected_links) == 1: + copied_str = self.dpg_bind['id_edge'][selected_links[0]] + copied_str = copied_str.strip('"') + print(copied_str) + elif len(selected_nodes) > 1: + for node_id in selected_nodes: + node_name = get_key(self.dpg_bind['node_id'], node_id) + node_name = node_name.strip('"') + copied_str += '"' + node_name + '",\n' + print(node_name) + print('---') + dpg.set_clipboard_text(copied_str) + + def display_callbackgroup(self, onoff: bool): + """Switch visibility of callback group in a node""" + callbackgroup_id = self.dpg_bind['callbackgroup_id'] + for _, value in callbackgroup_id.items(): + if onoff: + dpg.show_item(value) + else: + dpg.hide_item(value) + + def high_light_caret_path(self, path_name): + """ High light the selected CARET path """ + # Disable high light for all nodes + graph = self.get_graph() + for node_name in graph.nodes: + dpg.set_value( + self.dpg_bind['node_color'][node_name], + self.COLOR_HIGHLIGHT_DEF) + + # Then, high light nodes in the path + node_list = self.graph_manager.caret_path_dict[path_name] + for node_name in node_list: + if node_name in self.dpg_bind['node_color']: + dpg.set_value( + self.dpg_bind['node_color'][node_name], + self.COLOR_HIGHLIGHT_CARET_PATH) + else: + logger.error('%s is not included in the current graph', node_name) diff --git a/src/dear_ros_node_viewer/logger_factory.py b/src/dear_ros_node_viewer/logger_factory.py new file mode 100644 index 0000000..9d0c00e --- /dev/null +++ b/src/dear_ros_node_viewer/logger_factory.py @@ -0,0 +1,48 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +""" +Logger Factory +""" +import logging + + +class LoggerFactory(): + '''Logger Factory''' + level: int = logging.DEBUG + log_filename: str = None + + @classmethod + def create(cls, name) -> logging.Logger: + '''Create logger''' + logger = logging.getLogger(name) + logger.setLevel(cls.level) + stream_handler = logging .StreamHandler() + stream_handler.setLevel(cls.level) + handler_format = logging.Formatter('[%(levelname)-7s][%(filename)s:%(lineno)s] %(message)s') + stream_handler.setFormatter(handler_format) + logger.addHandler(stream_handler) + if cls.log_filename: + file_handler = logging.FileHandler(cls.log_filename) + file_handler.setLevel(cls.level) + handler_format = logging.Formatter( + '[%(asctime)s][%(levelname)-7s][%(filename)s:%(lineno)s] %(message)s') + file_handler.setFormatter(handler_format) + logger.addHandler(file_handler) + return logger + + @classmethod + def config(cls, level, log_filename) -> None: + '''Config''' + LoggerFactory.level = level + LoggerFactory.log_filename = log_filename diff --git a/src/dear_ros_node_viewer/ros2networkx.py b/src/dear_ros_node_viewer/ros2networkx.py new file mode 100644 index 0000000..845ce8e --- /dev/null +++ b/src/dear_ros_node_viewer/ros2networkx.py @@ -0,0 +1,122 @@ +# Copyright 2023 iwatake2222 +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License.s +""" +Utility class for polling ROS statistics from running ROS graph + +Note +---- +Reference: /opt/ros/galactic/lib/python3.8/site-packages/rqt_graph/rosgraph2_impl.py +""" + +import threading +import time +import networkx as nx +import matplotlib.pyplot as plt +from .logger_factory import LoggerFactory + +# Note: Use try-except to avoid error at pytest in GitHub Actions (todo) +try: + import rclpy + from rclpy.executors import MultiThreadedExecutor + from rqt_graph.rosgraph2_impl import Graph + from rqt_graph.dotcode import RosGraphDotcodeGenerator + from qt_dotgraph.pydotfactory import PydotFactory +except ImportError: + pass + +logger = LoggerFactory.create(__name__) + + +class Ros2Networkx(): + """Utility class for polling ROS statistics from running ROS graph""" + def __init__(self, node_name='Ros2Networkx'): + rclpy.init() + self.node_name_ = node_name + self.node_ = rclpy.create_node(node_name) + self.executor_ = MultiThreadedExecutor() + self.executor_.add_node(self.node_) + self.thread_ = threading.Thread(target=self.node_loop) + self.thread_.start() + + def node_loop(self): + """thread main function""" + while rclpy.ok(): + logger.info('Analyzing...') + self.executor_.spin_once(timeout_sec=1.0) + + def save_graph(self, filename: str = None) -> str: + """save dot graph""" + time.sleep(5) + graph = Graph(self.node_) + graph.set_node_stale(5.0) + graph.update() + + dotcode_generator = RosGraphDotcodeGenerator(self.node_) + dotcode = dotcode_generator.generate_dotcode( + rosgraphinst=graph, + ns_filter='', + topic_filter='', + # graph_mode='node_topic', + graph_mode='node_node', + hide_single_connection_topics=True, + hide_dead_end_topics=True, + cluster_namespaces_level=0, + # accumulate_actions=accumulate_actions, + dotcode_factory=PydotFactory(), + # orientation=orientation, + quiet=True, + unreachable=True, + group_tf_nodes=True, + hide_tf_nodes=True, + # group_image_nodes=group_image_nodes, + hide_dynamic_reconfigure=True + ) + + if filename: + with open(filename, encoding='UTF8', mode='w') as dot_file: + dot_file.write(dotcode) + + return dotcode + + def get_graph(self) -> nx.classes.digraph.DiGraph: + """get graph as NetworkX""" + _ = self.save_graph('temp.dot') + graph = nx.DiGraph(nx.nx_pydot.read_dot('temp.dot')) + for node in graph.nodes: + if self.node_name_ in graph.nodes[node]['label']: + node_observer = node + break + graph.remove_node(node_observer) + return graph + + def shutdown(self): + """shutdown thread""" + self.node_.destroy_node() + rclpy.shutdown() + + +def main(): + """test code""" + node_name = 'Ros2Networkx' + ros2networkx = Ros2Networkx(node_name=node_name) + graph = ros2networkx.get_graph() + ros2networkx.shutdown() + + pos = nx.spring_layout(graph) + nx.draw_networkx(graph, pos) + plt.show() + + +if __name__ == '__main__': + main() diff --git a/src/dear_ros_node_viewer/setting.json b/src/dear_ros_node_viewer/setting.json new file mode 100644 index 0000000..883cb31 --- /dev/null +++ b/src/dear_ros_node_viewer/setting.json @@ -0,0 +1,49 @@ +{ + "app_setting": { + "window_size": [1920, 1080], + "font": "font/roboto/Roboto-Medium.ttf", + "ignore_unconnected_nodes": true, + "ignore_node_list": [ + "/node_name/to_be_ignored/in_regularexpression", + "/wild_card/is/.*" + ], + "ignore_topic_list": [ + "/topic_name/to_be_ignored/in_regularexpression", + "/tf", + "/tf_static", + "/diagnostics" + ] + }, + "group_setting": { + "/sensing": { + "direction": "horizontal", + "offset": [0.0, 1.0, 2.5, 2.0], + "color": [128, 0, 128] + }, + "/localization": { + "direction": "horizontal", + "offset": [0.0, 3.5, 2.5, 2.0], + "color": [0, 0, 128] + }, + "/perception": { + "direction": "horizontal", + "offset": [3.0, 3.5, 4.0, 4.0], + "color": [0, 128, 0] + }, + "/planning": { + "direction": "horizontal", + "offset": [7.0, 0.0, 4.0, 4.0], + "color": [128, 128, 0] + }, + "/control": { + "direction": "horizontal", + "offset": [3.0, -0.8, 3.0, 1.5], + "color": [196, 64, 0] + }, + "__others__": { + "direction": "horizontal", + "offset": [-0.5, -0.5, 1.0, 1.0], + "color": [16, 64, 96] + } + } +} diff --git a/src/dear_ros_node_viewer/version_dummy.py b/src/dear_ros_node_viewer/version_dummy.py new file mode 100644 index 0000000..245f903 --- /dev/null +++ b/src/dear_ros_node_viewer/version_dummy.py @@ -0,0 +1 @@ +version = '0.0.0' diff --git a/tests/__init__.py b/tests/__init__.py index f3f7ded..017bcaa 100644 --- a/tests/__init__.py +++ b/tests/__init__.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -10,4 +10,4 @@ # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and -# limitations under the License. +# limitations under the License. \ No newline at end of file diff --git a/tests/test_caret2networkx.py b/tests/test_caret2networkx.py index cf5711f..8ffd6e3 100644 --- a/tests/test_caret2networkx.py +++ b/tests/test_caret2networkx.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -15,7 +15,7 @@ Test caret2networkx module """ -from dear_ros_node_viewer.caret2networkx import caret2networkx, quote_name +from src.dear_ros_node_viewer.caret2networkx import caret2networkx, quote_name def test_quote_name(): diff --git a/tests/test_dear_ros_node_viewer.py b/tests/test_dear_ros_node_viewer.py index 4a34869..929c6fd 100644 --- a/tests/test_dear_ros_node_viewer.py +++ b/tests/test_dear_ros_node_viewer.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -15,7 +15,7 @@ Test dear_ros_node_viewer module """ -import dear_ros_node_viewer +import src.dear_ros_node_viewer def test_main(): diff --git a/tests/test_dot2networkx.py b/tests/test_dot2networkx.py index 8174c84..c788204 100644 --- a/tests/test_dot2networkx.py +++ b/tests/test_dot2networkx.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -15,7 +15,7 @@ Test dot2networkx module """ -from dear_ros_node_viewer.dot2networkx import dot2networkx +from src.dear_ros_node_viewer.dot2networkx import dot2networkx def test_dot2networkx(): diff --git a/tests/test_graph_layout.py b/tests/test_graph_layout.py index b00a2d1..1e21a33 100644 --- a/tests/test_graph_layout.py +++ b/tests/test_graph_layout.py @@ -1,4 +1,4 @@ -# Copyright 2022 Tier IV, Inc. +# Copyright 2023 iwatake2222 # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. @@ -16,7 +16,7 @@ """ import networkx as nx -from dear_ros_node_viewer.graph_layout import place_node_by_group, align_layout +from src.dear_ros_node_viewer.graph_layout import place_node_by_group, align_layout def test_graph_layout():