ROSではロボットを目的の位置まで移動させるためのライブラリ群であるNavigationスタックが用意されています。自作のロボットでNavigationスタックが使えるようにしていきたいと思います。
スタックとは、パッケージを集めたもので、高レベルのライブラリを形成するものです。今回使用するNavigationスタックは複数のパッケージから構成されているという事ですね。
Navigationスタックを動作させるためのハードウェア要件
Navigationスタックは以下のハードウェア要件を想定して作られています。- ディフェレンシャル・ドライブ(差動二輪ロボット)と全方位移動ロボット。
- 車輪部のどこかに平面レーザーが必要。
- 四角形または円形ロボット。
Navigationスタックのセットアップ
それでは、今まで作成してきたロボットのNavigationスタックで動作に必要な設定を行っていきます。tf座標情報
ROSが提供する座標変換パッケージtfを使い、ロボットの各部の位置関係をパブリッシュします。この設定はcontroller.launchファイルにすでに記述済みです。<!-- convert joint states to TF transforms for rviz, etc --> <node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen" ns="/my_robo">
センサ情報
Navigationスタックでは障害物の回避のため、センサ情報を必要とします。こちらも前回までの設定でシミュレーションできるようにしましたね。オドメトリ情報
Navigationスタックはオドメトリ情報が必要です。オドメトリ情報はロボットの移動量を示す値です。今回作成したロボットのシミュレーションではシミュレーターから得ることができます。基本制御
Navigationスタックはロボットがgeometry_msgs/Twistメッセージを受け取って動作する前提で作られています。これも今回作成したロボットのシミュレータにより実現されています。地図
前回Map作成の手順を示しました。この地図を使用することにします。
ナビゲーションの環境を整える
では、ナビケーション用のパッケージを作成して、Navigationスタックのための各種設定ファイルを作成していきます。
必要となるソフトウェアをインストールしていきます。
sudo apt-get install ros-indigo-amcl sudo apt-get install ros-indigo-move-base
パッケージを作成します。
cs cd my_robo catkin_create_pkg my_robo_2dnav move_base my_robo_description Created file my_robo_2dnav/package.xml Created file my_robo_2dnav/CMakeLists.txt Successfully created files in /home/my_robo/catkin_ws/src/my_robo/my_robo_2dnav. Please adjust the values in package.xml. roscd my_robo_2dnav
適当なエディタを使い、設定ファイルを作成していきます。ここではエディタにatomを使っています。
atom costmap_common_params.yaml
obstacle_range: 2.5 raytrace_range: 3.0 footprint: [[-0.2, -0.1], [-0.2, 0.1], [0.2, 0.1], [0.2, -0.1]] #robot_radius: ir_of_robot inflation_radius: 0.55 observation_sources: laser_scan_sensor laser_scan_sensor: {sensor_frame: /hokuyo_link, data_type: LaserScan, topic: /rrbot/laser/scan, marking: true, clearing: true}
atom global_costmap_params.yaml
global_costmap: global_frame: /map robot_base_frame: base_footprint update_frequency: 5.0 static_map: true
atom local_costmap_params.yaml
local_costmap: global_frame: odom robot_base_frame: base_footprint update_frequency: 5.0 publish_frequency: 2.0 static_map: false rolling_window: true width: 6.0 height: 6.0 resolution: 0.05
atom base_local_planner_params.yaml
TrajectoryPlannerROS: max_vel_x: 0.45 min_vel_x: 0.1 max_vel_theta: 1.0 min_in_place_vel_theta: 0.4 acc_lim_theta: 3.2 acc_lim_x: 2.5 acc_lim_y: 2.5 holonomic_robot: false meter_scoring: true
launchファイル作成します。
roscd my_robo_2dnav mkdir launch cd launch atom move_base.launch
<launch> <master auto="start"/> <!-- Run the map server --> <arg name="map_file" default="$(find my_robo_2dnav)/map/map.yaml"/> <node name="map_server" pkg="map_server" type="map_server" args="$(arg map_file)" /> <!--- Run AMCL --> <!--<include file="$(find amcl)/examples/amcl_diff.launch" />--> <node pkg="amcl" type="amcl" name="amcl" output="screen" args="/scan:=/rrbot/laser/scan"> <!-- Publish scans from best pose at a max of 10 Hz --> <param name="odom_model_type" value="diff"/> <param name="odom_alpha5" value="0.1"/> <param name="transform_tolerance" value="0.2" /> <param name="gui_publish_rate" value="10.0"/> <param name="laser_max_beams" value="30"/> <param name="min_particles" value="500"/> <param name="max_particles" value="5000"/> <param name="kld_err" value="0.05"/> <param name="kld_z" value="0.99"/> <param name="odom_alpha1" value="0.2"/> <param name="odom_alpha2" value="0.2"/> <!-- translation std dev, m --> <param name="odom_alpha3" value="0.8"/> <param name="odom_alpha4" value="0.2"/> <param name="laser_z_hit" value="0.5"/> <param name="laser_z_short" value="0.05"/> <param name="laser_z_max" value="0.05"/> <param name="laser_z_rand" value="0.5"/> <param name="laser_sigma_hit" value="0.2"/> <param name="laser_lambda_short" value="0.1"/> <param name="laser_lambda_short" value="0.1"/> <param name="laser_model_type" value="likelihood_field"/> <!-- <param name="laser_model_type" value="beam"/> --> <param name="laser_likelihood_max_dist" value="2.0"/> <param name="update_min_d" value="0.2"/> <param name="update_min_a" value="0.5"/> <param name="odom_frame_id" value="odom"/> <param name="resample_interval" value="1"/> <param name="transform_tolerance" value="0.1"/> <param name="recovery_alpha_slow" value="0.0"/> <param name="recovery_alpha_fast" value="0.0"/> </node> <!--- Run Move Base --> <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen" args="/cmd_vel:=/my_robo/diff_drive_controller/cmd_vel"> <rosparam file="$(find my_robo_2dnav)/costmap_common_params.yaml" command="load" ns="global_costmap" /> <rosparam file="$(find my_robo_2dnav)/costmap_common_params.yaml" command="load" ns="local_costmap" /> <rosparam file="$(find my_robo_2dnav)/local_costmap_params.yaml" command="load" /> <rosparam file="$(find my_robo_2dnav)/global_costmap_params.yaml" command="load" /> <rosparam file="$(find my_robo_2dnav)/base_local_planner_params.yaml" command="load" /> </node> </launch>
launchファイル内ではまず、マップサーバーを起動しています。
地図ファイルは、my_robo_2dnavパッケージ内にmapという名前のディレクトリを作成しその中にmap.pgmとmap.yamlを配置しました。
次にamclを起動しています。これはモンテカルロ位置推定(MCL)による、ロボットの位置推定プログラム(Robot Localization)です。
最後にmove_baseを起動しています。これは、ロボットの移動を司るプログラム群になっています。
これらを連携してNavigationを実現しています。まずは動かしてみましょう。ロジックの詳しい内容は今は割愛します。詳しくはhttp://wiki.ros.org/amclを参照してください。
それでは準備が整いましたので、起動してみましょう。まずはいつものようにロボットのシミュレーション環境を起動します。
roslaunch my_robo_description gazebo.launch
新しくターミナルを開き、Navigationを起動します。
roslaunch my_robo_2dnav move_base.launch
新しくターミナルを開き、RVizを実行します。
rosrun rviz rviz
RVizが起動したら、Addボタンをクリックして次のトピックを表示させてください。
Path : /move_base/NavfnROS/plan
Map : /map
Fixed Frameは「map」に設定します。
では、移動先を指定してみましょう。上部の「2D Navi Goal」をクリックします。
そして地図上でゴール地点に指定したい場所を、クリックしたままドラッグすると、ドラッグした方向に矢印が描かれます。矢印の方向が、ゴール地点に到達した時のロボットの向きになります。
ゴール地点が設定されると、ロボットが動き始めます。
比較的に直進の動作はうまくいくのですが、ロボットがカーブを曲がるとオドメトリが大きく狂います。おそらく動作確認のために設定ファイルはほとんどwiki.ros.orgのサンプルと同じにしているため、正しくオドメトリを計算できていないためでしょう。作成したロボットに合わせて設定を見直す必要があります。
これからパラメータの調整が必要とはいえ、ほとんどプログラミングなしに、自分で設計したロボットを動作させる環境を整えることができることがわかったと思います。
ROSで始めるロボティクス(6) ー ROSでデプスカメラPMD CamBoard pico flexxを使う
ROSで始めるロボティクス(7) ー ロボットのための二次元mapを作る
ROSで始めるロボティクス(8) ー ロボットのナビゲーションを行う
ROSで始めるロボティクス(7) ー ロボットのための二次元mapを作る
ROSで始めるロボティクス(8) ー ロボットのナビゲーションを行う
参考文献:
記載されている会社名、および商品名等は、各社の商標または登録商標です。
はじめまして、ある大学でこちらのホームページを参考に研究させていただいているものです。とても参考になりました.質問なのですが最後の最後でゴールを指定してもモデルが動きませんでした.教えていただけたら幸いです.
返信削除