目的
ROSのmove_base(Navigation Stock)で、Map上にロボットの立ち入り禁止区域を設定する方法について説明する。
map_serverを2個立ち上げる。
map_serverを2個立ち上げ、move_baseのMapにはロボットの立ち入り禁止区域を黒く塗りつぶしたMapを指定し、amclのMapには、通常のMap(gmapping,cartgrapherなどで作成したMap)を指定する。
move_baseでは、map_serverで読み込んだMap上の黒い箇所は障害物として認識されており、この場所は立ち入り禁止区域となる。move_baseのゴールとして指定することはできず、経路探索の領域からも除外される。立ち入り禁止区域を画像編集ソフト(Gimp・Pintaなど)で立ち入り禁止区域を黒く塗る。
ただし、障害物が本来ないところに障害物を設置すると、amclなどの自己位置推定モジュールが誤検出を起こしてしまう可能性がある。
そこで、map_serverを2個に立ち上げ、move_baseとamclで別ファイルを指定する。自己位置推定の誤検出を防ぎつつも、立ち入り禁止区域を設定することができる。
launchファイル例
<launch>
<arg name="map_amcl_file" default="$(find test_maps)/maps/map_amcl.yaml" />
<arg name="map_movebase_file" default="$(find test_maps)/maps/map_movebase.yaml" />
<arg name="move_base_include" default="$(find test_navigation)/launch/include/move_base.launch.xml" />
<arg name="amcl_include" default="$(find test_navigation)/launch/include/amcl.launch.xml" />
<node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" />
<node name="map_movebase_server" pkg="map_server" type="map_server" args="$(arg map_movebase_file)" >
<remap from="map" to="map_movebase" />
<remap from="static_map" to="static_map_movebase" />
</node>
<include file="$(arg amcl_include)" />
<include file="$(arg move_base_include)" >
<remap from="map_topic" value="map_movebase" />
</include>
</launch>
なお、fetch roboticsのmove_baseのlaunchファイルには、この機能が実装されています。
https://github.com/fetchrobotics/fetch_ros/blob/indigo-devel/fetch_navigation/