本記事では、ChoreonoidとROSパッケージを使ってHector SLAMによる地図生成を行う手順を紹介します。
Hector SLAMは、独国ダルムシュタット工科大学のロボット研究チーム”Hector”のメンバーが開発したROS環境で利用できるオープンソースソフトウェアとなります。拡張カルマンフィルタベースのアルゴリズムを採用しており、オドメトリフリーなのでドローンでも使えるSLAM手法となります。
本記事は、ChoreonoidとROSディストリビューションのインストールを行っていることを前提としています。インストールしていない方は、Choreonoid公式HPを参考に「ROSのインストール」と「Choreonoid関連パッケージのビルド」を行ってください。
<https://choreonoid.org/ja/documents/latest/ros/index.html#>

1. 使用した環境

・Ubuntu 20.04 LTS
・Choreonoid 1.8
・ROS Noetic Ninjemys
・Hector SLAM
・map_server 1.17.3

2. Hector SLAMとmap_serverパッケージのインストール

以下のコマンドを実行し、Hector SLAMとmap_serverパッケージをインストールします。

sudo apt install -y ros-noetic-hector* ros-noetic-map-server

上記のROSパッケージをインストールしていない場合、launchファイル実行時に以下のエラーが発生します。

roslaunch cnoid_turtlebot3_slam cnoid_turtlebot3_world_slam_2d.launch slam_method:=hector
ERROR: cannot launch node of type [hector_mapping/hector_mapping]: hector_mapping

3. TurtleBot3関連パッケージのダウンロード・インストール

TurtleBot3関連パッケージのダウンロード・インストール方法は、「Choreonoid tips ⑦【gmappingを使ったSLAM】」の項番3~5をご参照ください。

4. cnoid_turtlebot3_pkgsパッケージのダウンロード

cnoid_turtlebot3_pkgs.zipをダウンロードし、ZIPファイルを解凍します。ここでは、ダウンロードディレクトリにcnoid_turtlebot3_pkgs.zipファイルが保存されていることとします。別のディレクトリに格納している場合は適宜ファイルパスを変更してください。
ZIPファイルの解凍が完了したら、~/catkin_ws/src以下に対象のディレクトリをコピーします。
cnoid_turtlebot3_pkgs.zipは、以下リンクからダウンロードできます。
https://rtc-fukushima.jp/wp/wp-content/uploads/2023/05/cnoid_turtlebot3_pkgs.zip

cd ~/ダウンロード
unzip cnoid_turtlebot3_pkgs.zip
cp -rfp cnoid_turtlebot3_pkgs ~/catkin_ws/src

5. シンボリック・リンクの追加

cnoid_turtlebot3_pkgsパッケージのモデルファイルでturtlebot3パッケージとturtlebot3_simulationsパッケージのメッシュファイルを参照しているので、以下のコマンドを実行しシンボリック・リンクを追加します。

ln -s ~/catkin_ws/src/turtlebot3/turtlebot3_description/ ~/catkin_ws/src/cnoid_turtlebot3_pkgs/cnoid_turtlebot3_bringup/model/resource/turtlebot3_description
ln -s ~/catkin_ws/src/turtlebot3_simulations/turtlebot3_gazebo/models/turtlebot3_world/meshes/ ~/catkin_ws/src/cnoid_turtlebot3_pkgs/cnoid_turtlebot3_bringup/model/resource/turtlebot3_world

6. ChoreonoidとTurtleBot3関連パッケージのビルド

以下のコマンドを実行し、ChoreonoidとTurtleBot3関連パッケージのビルドを行います。

cd ~/catkin_ws
catkin build
source devel/setup.bash

7. TurtleBot3とHector SLAMによる2D地図生成

以下のコマンドを実行し、TurtleBot3のSLAM用launchファイルを起動します。実行引数に「slam_methods:=hector」を指定します。指定していない場合は、gmappingによるSLAMが実行されるので注意してください。

roslaunch cnoid_turtlebot3_slam cnoid_turtlebot3_world_slam_2d.launch slam_methods:=hector

次に別ターミナルを起動し、TurtleBot3の遠隔操作launchファイルを起動します。

roslaunch turtlebot3_teleop turtlebot3_teleop_key.launch

TurtleBot3の遠隔操作launchを起動したターミナル上で、キーボードからw(直進), x(後退), d(右旋回), a(左旋回), s(停止)を入力すればTurtleBot3を動かし2D地図生成を行えます。


図1. Choreonoid画面

 


図2. RViz画面

8. 作成した地図の保存

別のターミナルを起動し、以下のコマンドで作成した地図を保存します。-fオプションのあとは出力ファイル名を指定してください。

mkdir ~/catkin_ws/src/cnoid_turtlebot3_pkgs/cnoid_turtlebot3_slam/map
rosrun map_server map_saver -f ~/catkin_ws/src/cnoid_turtlebot3_pkgs/cnoid_turtlebot3_slam/map/map

図3. Hector SLAMで作成した地図

9. Hector SLAM用のlaunchファイルの解説

今回はHector SLAMを使用しておりオドメトリを使用しないので、4~7行目で”odom_frame”, “base_frame”の引数の初期値を”base_link”に変更しています。

<launch>
  <!-- Arguments -->
  <arg name="model" default="$(env TURTLEBOT3_MODEL)" doc="model type [burger, waffle, waffle_pi]"/>
  <!-- arg name="odom_frame" default="odom"/ -->
  <!-- arg name="base_frame" default="base_footprint"/ -->
  <arg name="odom_frame" default="base_link"/>
  <arg name="base_frame" default="base_link"/>

16行目で”hector_mapping”ノードを起動することで、Hector SLAMを実行できます。
”hector_mapping”ノード起動時に設定しているパラメータの設定は、以下をご参照ください。
http://wiki.ros.org/hector_mapping

 <!-- Hector mapping -->
  <node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
    <!-- Frame names -->
    <param name="map_frame"  value="map" />
    <param name="odom_frame" value="$(arg odom_frame)" />
    <param name="base_frame" value="$(arg base_frame)" />

 
 
いかがだったでしょうか。
ChoreonoidでHector SLAMを行いたい方のお役に立てれば幸いです。