はじめに
ROS melodicをインストールしたRaspberryPi4B(Raspbian32bitのBuster)を搭載したサーバPCに対し、WSLによるUbuntu20.04環境にROS NoeticをインストールしたWindows10 PCから遠隔制御もしくはRVIZによる状態モニタをしようとした際に色々苦戦したので内容の覚書です。
使用しているPCの情報は以下の通り。
クライアント側からサーバ側へのリモートlaunch
はじめに、それぞれのPCにおいてROS IPの設定等を実施します。
クライアント側の設定
export ROS_MASTER_URI=http://192.168.11.12:11311
export ROS_IP=192.168.11.4
export DISPLAY=:0
export ROSLAUNCH_SSH_UNKNOWN=1
サーバ側の設定
export ROS_IP=192.168.11.12
リモート用launchファイルの作成
クライアント側からサーバ側へのリモートlaunchに向け、クライアント側でlaunchファイルを作成します。
今回はサーバ側にある「rover」というパッケージの「locomotion」というノードを起動してみます。
launchファイルの書き方については、誠に勝手ながら以下の記事を参考にさせていただきました。
ROS講座21 複数のPCでROS接続2
<launch>
<!-- サーバ側へのSSH用 -->
<machine name="Rover" address="192.168.11.12" env-loader="/home/pi/navigation_ws/devel/env.sh" user="pi" password="******" default="true"/>
<!-- サーバ側でのノードlaunch用 -->
<node machine="Rover" name="locomotion" pkg="rover" type="locomotion" />
</launch>
問題①Noetic-Melodic間のroslaunchにおける引数齟齬に伴う動作不良
先ほど作成したlaunchファイルを実行していきます。
以下の実行メッセージの通り、SSHまではできたものの、その後のroslaunchを実行した際にエラーが出ました。
guest@DESKTOP-LHVML0O:~/catkin_ws$ roslaunch remote remote.launch
... logging to /home/guest/.ros/log/6ef7931a-05c5-11ed-a6d8-3c7c3f503402/roslaunch-DESKTOP-LHVML0O-4221.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
WARNING: ignoring defunct <master /> tag
started roslaunch server http://192.168.11.4:49684/
remote[192.168.11.12-0] starting roslaunch
remote[192.168.11.12-0]: creating ssh connection to 192.168.11.12:22, user[pi]
launching remote roslaunch child with command: [env ROS_MASTER_URI=http://192.168.11.12:11311 /home/pi/navigation_ws/devel/env.sh roslaunch -c 192.168.11.12-0 -u http://192.168.11.4:49684/ --run_id 6ef7931a-05c5-11ed-a6d8-3c7c3f503402 --sigint-timeout 15.0 --sigterm-timeout 2.0]
remote[192.168.11.12-0]: ssh connection created
remote[192.168.11.12-0]: Usage: roslaunch [options] [package] <filename> [arg_name:=value...]
roslaunch [options] <filename> [<filename>...] [arg_name:=value...]
If <filename> is a single dash ('-'), launch XML is read from standard input.
roslaunch: error: no such option: --sigint-timeout
[192.168.11.12-0] killing on exit
RLException: remote roslaunch failed to launch: rasp3
The traceback for the exception was written to the log file
遠隔先のRaspberryPi(Melodic)でroslaunchを実施した際に勝手に指定された引数「--sigint-timeout」において、『そんなオプション知らん』と言われています。オペレート側のPC(Noetic)が勝手につけたものみたいでした。オプション「--sigint-timeout」についてROSのWebを確認してみましたが、確かにMelodicでは対応していないことがわかりました。
ということで、異なるROSバージョン間(Melodic-Noetic)の通信は無理だと悟りました。
が、少し粘ってみました。
実際にroslaunchを実行している部分のargsの指定において、'--sigint-timeout'と'--sigterm-timeout'に関する引数をコメントアウトします。(「--sigint-timeout」を外して実行してみたら、次に同じように「--sigterm-timeout」についてもエラーになりました)
if not machine.env_loader:
raise ValueError("machine.env_loader must have been assigned before creating ssh child instance")
# args = [machine.env_loader, 'roslaunch', '-c', name, '-u', server_uri, '--run_id', run_id,
# '--sigint-timeout', str(sigint_timeout), '--sigterm-timeout', str(sigterm_timeout)]
args = [machine.env_loader, 'roslaunch', '-c', name, '-u', server_uri, '--run_id', run_id]
上記修正をした上で再実行します。
guest@DESKTOP-LHVML0O:~/catkin_ws$ roslaunch remote remote.launch
... logging to /home/guest/.ros/log/0b73fc46-05c7-11ed-92d3-dca6329a3378/roslaunch-DESKTOP-LHVML0O-4284.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.
started roslaunch server http://192.168.11.4:49773/
remote[192.168.11.12-0] starting roslaunch
remote[192.168.11.12-0]: creating ssh connection to 192.168.11.12:22, user[pi]
launching remote roslaunch child with command: [env ROS_MASTER_URI=http://192.168.11.12:11311 /home/pi/navigation_ws/devel/env.sh roslaunch -c 192.168.11.12-0 -u http://192.168.11.4:49773/ --run_id 0b73fc46-05c7-11ed-92d3-dca6329a3378]
remote[192.168.11.12-0]: ssh connection created
SUMMARY
========
PARAMETERS
* /rosdistro: noetic
* /rosversion: 1.15.14
MACHINES
* Rover
NODES
/
locomotion(rover/locomotion)
ROS_MASTER_URI=http://192.168.11.12:11311
ROSのバージョン間のエラーが消えました!
なんだいけるじゃないの・・・と思いきや、いつまで待ってもサーバ側のノードが起動しません。
問題➁リモート通信時のホスト名指定に留意
先に結論を記載しておきますが、ノードが起動しないことに対する本問題はROSのバージョン差異は全く関係なく、ネットワーク環境/設定に依存するものでした。
まずはノードが動作開始できないにあたり、どこで処理が止まっているのか、リモート動作に係るpythonコードを覗いてみました。
for child in self.remote_processes:
nodes = self.remote_nodes[child.machine.config_key()]
body = '\n'.join([n.to_remote_xml() for n in nodes])
# #3799: force utf-8 encoding
xml = '<?xml version="1.0" encoding="utf-8"?>\n<launch>\n%s</launch>'%body
api = child.getapi()
try:
self.logger.debug("sending [%s] XML [\n%s\n]"%(child.uri, xml))
code, msg, val = api.launch(xml)
どうやらremote.pyの中のtry文にある「code, msg, val = api.launch(xml)」がいつまで経っても処理できていません。
ROSバージョン差異によってxmlの設定がおかしい、もしくは互換性がないのか?とか思ってみてprint出力してみても中身は正しそう。直前のdebugの引数になっているchild.uriはどうなっているのかと思ってこちらもprint出力してみました。
http://rasp3:34719/
ふむ、問題なし。
ロボット側のアドレスとポート指定かあ、特に問題ないなあと思っていたけど、ここで疑問が…。
私のネットワーク環境ではサーバ側に対しクライアントPCからホスト名指定でSSHアクセスができません。
これもホスト名指定になっているから接続できないのでは…?と思い、コード中に拙い文字列置換の処理を入れて、ホスト名である「rasp3」の部分をIPアドレス「192.168.11.12」に置換しました。
for child in self.remote_processes:
nodes = self.remote_nodes[child.machine.config_key()]
body = '\n'.join([n.to_remote_xml() for n in nodes])
#add ホスト名ではリモート接続できないネットワーク環境のためIPアドレスに置換
tmp = child.uri.replace("rasp3", "192.168.11.12")
child.uri = tmp
# #3799: force utf-8 encoding
xml = '<?xml version="1.0" encoding="utf-8"?>\n<launch>\n%s</launch>'%body
api = child.getapi()
try:
self.logger.debug("sending [%s] XML [\n%s\n]"%(child.uri, xml))
code, msg, val = api.launch(xml)
これにて再試行してみます。
guest@DESKTOP-LHVML0O:~/catkin_ws$ roslaunch remote remote.launch
~略~
SUMMARY
========
PARAMETERS
* /rosdistro: noetic
* /rosversion: 1.15.14
MACHINES
* Rover
NODES
/
locomotion(rover/locomotion)
ROS_MASTER_URI=http://192.168.11.12:11311
[192.168.11.12-0]: launching nodes...
[192.168.11.12-0]: ROS_MASTER_URI=http://192.168.11.12:11311
[192.168.11.12-0]: process[locomotion-1]: started with pid [2054]
[192.168.11.12-0]: ... done launching nodes
動いた!!!
つまり、URIがホスト名での指定になるので、PC側の設定 & DNS側の設定ができていないことが原因でした。ということで、上記remote.pyは元に戻し、以下参考にしてPC側の設定にてホスト名でアクセスできるように設定変更しました。
host名でアクセスを設定する
generateHosts = ture # <-- 入れる
127.0.0.1 localhost
192.168.11.12 rasp3 # <-- 入れる
結論
これで晴れて、クライアント側(Noetic)からサーバ側(melodic)のノードをリモート起動できました。
つまり、異なるバージョン(Noetic to Melodic)のROS間でもリモートlaunchはできます。
P.S.
後に気づいた話ながら…。
これ同じように異なるROSバージョン間のリモートlaunch困る人出るのではと思って記事を書いたら、公式QAにもばっちり書いてありました。和訳だと思って本記事残します。
How can I suppress sigint-timeout and sigterm-timout options from roslaunch ?