ROSで複数マシンで複数ノードを起動する方法をミニマムなサンプルで説明。
環境
- PC: デスクトップマシン(192.168.11.3) / RaspberryPi3(192.168.11.12)
- OS: Ubuntu 16.04
- ROS: ROS Kinetic
やること
- デスクトップマシンをROS Masterとして、デスクトップマシンおよびラズパイ上で同じノードを1つずつ起動
前準備
- デスクトップとラズパイ間で、パスワード無しでsshできるようにする(互いの公開鍵id_rsa.pubを ~/.ssh/authorized_keysに登録)
- デスクトップの.bashrcに
export ROSLAUNCH_SSH_UNKNOWN=1
を追記
ROSLAUNCH
starter.launch
<launch>
<arg name="user" default="$(env USER)" />
<machine name="main" address="192.168.11.3" env-loader="/home/$(arg user)/ros_work/src/mypkg/env/machine1.sh" />
<machine name="sub" address="192.168.11.12" env-loader="/home/$(arg user)/ros_work/src/mypkg/env/machine2.sh" />
<node pkg="mypkg" type="node.py" name="main_node" machine="main">
<param name="myparam" value="hello main" />
</node>
<node pkg="mypkg" type="node.py" name="sub_node" machine="sub">
<param name="myparam" value="hello sub" />
</node>
</launch>
マシンのセットアップスクリプト
machine1.sh
#!/bin/bash
u="$USER"
CATKIN_SHELL="bash"
export ROS_MASTER_URI="http://192.168.11.3:11311"
export ROS_IP="192.168.11.3"
. /home/$u/ros_work/devel/setup.bash
exec "$@"
machine2.sh
#!/bin/bash
u="$USER"
CATKIN_SHELL="bash"
export ROS_MASTER_URI="http://192.168.11.3:11311"
export ROS_IP="192.168.11.12"
. /home/$u/ros_work/devel/setup.bash
exec "$@"
テスト用のノード
node.py
#!/usr/bin/python
# coding: utf-8
import rospy
if __name__ == '__main__':
rospy.init_node('node')
sense = rospy.get_param('~myparam')
rate = rospy.Rate(1)
while not rospy.is_shutdown():
rospy.loginfo('msg: %s' % sense)
rate.sleep()
起動方法
- ラズパイ側に上記を適宜構成で入れたworkspaceをコピー。デスクトップ側とディレクトリ構成が同じになっていないとダメ。
- デスクトップ側で
roslaunch mypkg starter.launch
で起動。(パッケージ名は適当)