今日は、私がいつも使っているROS2のネームスペース区別術の一例を解説したいと思います。もっといい方法があるのかもしれませんが、私の出した解決法ということで参考にしてもらえるとありがたいです。
ROS2はデフォルトではLAN内にいる他のコンピュータにもノードとトピックが見えるという仕様があります。この仕様を利用することでコンピュータ複数台で連携させたシステムを作りやすくなりました。(ROS1でもできます)私は、その仕組みを利用して多くのデバイスを複数のPCで同時に動かすシステムを作ったこともあります。
ただし、それぞれのPCで共通のプロセスをROS2で立ち上げようとしたとき、同じ名前のノード・トピックが同じLAN内に存在することになるため、メッセージが混乱してしまいます。回避方法としては、
- launchファイルにオリジナルのネームスペースをつける
- トピック名を変更する
- 通信可能なポートを指定して区別する
などの方法があると思います。ただし、1・2のようなオリジナルの名前をつけるのはいちいち面倒だし、3だとそもそも実現したいシステムを実現できなくなってしまいます。
そこで、この記事ではIPアドレスを利用して自動的にノードを区別する方法を示します。
ネームスペースの仕様
ここでネームスペースの仕様について確認します。ネームスペースは、ノード名と区別してつけられる固有の名称で、ROS1のlaunchファイルではgroupタグで指定することができます。
ネームスペースについて分かる範囲での特徴まとめ
- ネームスペースがついたノードから発信される相対パス形式のトピックにはすべてネームスペースが付与される(例:プログラム内で"topicA"と指定している場合はネームスペースが付与される。"/topicA"の場合は付与されない)
- ネームスペースの先頭に数字はつけられない
- "/"によって区切ることが可能で、親子関係を作ることができる。("/nsA/nsB"と"/nsA"があれば、"/nsA/nsB"は"/nsA"の子という扱いになる)
- ネームスペースで区切っても、別のネームスペースからトピックを送ることは可能(remapで指定)
IPアドレスをネームスペースにする方法
IPアドレスをネームスペースにしていきます。IPアドレスの付与自体はとても簡単で、launchをPythonで記述しているので、Python上でIPアドレスを取得して文字列にしてネームスペースにするだけです。
IPアドレスの取得方法はこの記事を参考にしました。
記事の実装に少し手を加えて、IPアドレスリストの0番目を参照して、"."を消して先頭に"ip_"を追加しています。
ネームスペースに加えるときは次のようにします。ここでは、motpy_rosのexample_mosaic.launch.py(https://github.com/Ar-Ray-code/motpy_ros)を書き換えました。
import launch import launch_ros.actions # Get IP address----------------------------------------------------------------- import netifaces as ni import psutil import os import socket def ip_get(): if os.name == "nt": return socket.gethostbyname_ex(socket.gethostname())[2] pass else: result = [] address_list = psutil.net_if_addrs() for nic in address_list.keys(): ni.ifaddresses(nic) try: ip = ni.ifaddresses(nic)[ni.AF_INET][0]['addr'] if ip not in ["127.0.0.1"]: ip_data = ip.replace(".","") result.append(ip_data) except KeyError as err: pass return "/ip_"+str(result[0]) # ----------------------------------------------------------------- def generate_launch_description(): ns = ip_get() webcam = launch_ros.actions.Node( package='v4l2_camera', node_executable='v4l2_camera_node', namespace=ns+'/camera/color', ) face_detect = launch_ros.actions.Node( package='motpy_ros', node_executable='face_detect', namespace=ns, parameters=[ {'imshow_isshow' : 0} ] ) # <以下省略…>
実行
これで、同じLAN内のそれぞれのPCで実行します。$ ros2 launch motpy_ros example_mosaic.launch.py
Rqt-graphの実行結果
トピックの確認
(foxy):~/ros2_ws$ ros2 topic list /ip_1921681117/bounding_boxes /ip_1921681117/camera/color/camera_info /ip_1921681117/camera/color/image_raw /ip_1921681117/camera/depth/image_rect_raw /ip_1921681117/motpy/image_raw /ip_1921681117/tracking_data/bounding_boxes /ip_1921681133/bounding_boxes /ip_1921681133/camera/color/camera_info /ip_1921681133/camera/color/image_raw /ip_1921681133/camera/depth/image_rect_raw /ip_1921681133/motpy/image_raw /ip_1921681133/tracking_data/bounding_boxes /parameter_events /rosout
ノード名の確認
(foxy):~/ros2_ws$ ros2 node list /ip_1921681117/camera/color/v4l2_camera /ip_1921681117/darknet_tracking /ip_1921681117/face_detect /ip_1921681117/mosaic_bbox /ip_1921681117/rqt_gui_py_node_149111 /ip_1921681133/camera/color/v4l2_camera /ip_1921681133/darknet_tracking /ip_1921681133/face_detect /ip_1921681133/mosaic_bbox /ip_1921681133/rqt_gui_py_node_131955
ちゃんとIPアドレスで振り分けられています。
IPを固定にしていない場合や、最初から使用台数が決まっている場合はこの手法を取るメリットは無いですが、不特定多数のデバイスを参加させる可能性がある用途においてはとても役立つと思います。また、別のPCからIPアドレスと実行中のデバイスを関連付けることができるので、確認をしやすいとも思います。