環境
この記事は以下の環境で動いています。
項目 | 値 |
---|---|
CPU | Core i5-8250U |
Ubuntu | 16.04 |
ROS | Kinetic |
Gazebo | 7.14.0 |
インストールについてはROS講座02 インストールを参照してください。
またこの記事のプログラムはgithubにアップロードされています。ROS講座11 gitリポジトリを参照してください。
概要
move baseはnavigation stackの中心になる移動のためのパッケージです。これでRvizから目標地点を入力して、ロボットがそこに移動するということを目指します。
move_baseと周りの物のパッケージの関係は以下のようになります。move_baseには位置推定のモジュールはありません。robot_localizetionやgmappingを使って位置を取得して、それとmapトピック、scanトピック、odomトピックの4つを使ってロボットへの指示であるcmd_velを生成します。
またmove_baseの中は以下のように5つのパートに分かれます。
ros wikiより
install
sudo apt-get install -y ros-kinetic-move-base
ソースコード
config
move_baseは上に書いたように5つの部分に分かれますが、今回はそのうちの3つ(global_costmap、local_costmap、local_planner)にパラメーターを設定します。
コンフィグファイルはgithubに置きます。
launch
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="model" default="$(find nav_lecture)/xacro/dtw_robot.xacro" />
<arg name="rvizconfig" default="$(find nav_lecture)/rviz/move_base.rviz" />
<!-- gazebo world -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find nav_lecture)/worlds/test1.world"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="headless" value="false"/>
<arg name="debug" value="false"/>
</include>
<!-- dtw_robot -->
<include file="$(find nav_lecture)/launch/dtw_spawn.launch">
<arg name="robot_name" value="dtw_robot1"/>
</include>
<group ns="dtw_robot1">
<!-- to increase the wheel odometry error -->
<param name="/dtw_robot1/diff_drive_controller/wheel_radius" value="0.055" />
<!-- robot localization -->
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_se" clear_params="true" output="screen">
<rosparam command="load" file="$(find nav_lecture)/config/ekf_localization/mode1.yaml" />
<param name="tf_prefix" value="dtw_robot1"/>
<remap from="/odometry/filtered" to="fusion/odom" />
<remap from="odom0" to="diff_drive_controller/odom" />
<remap from="imu0" to="imu/data" />
</node>
<!-- gmapping -->
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" clear_params="true">
<rosparam command="load" file="$(find nav_lecture)/config/gmapping.yaml" />
<remap from="scan" to="front_laser/scan" />
<param name="base_frame" value="dtw_robot1/base_link" />
<param name="odom_frame" value="dtw_robot1/odom" />
<param name="map_frame" value="dtw_robot1/map" />
</node>
<!-- move_base -->
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find nav_lecture)/config/move_base/local_costmap_params_old.yaml" command="load" />
<rosparam file="$(find nav_lecture)/config/move_base/global_costmap_params_old.yaml" command="load" />
<rosparam file="$(find nav_lecture)/config/move_base/base_local_planner_params.yaml" command="load" />
<param name="global_costmap/global_frame" value="dtw_robot1/map" />
<param name="global_costmap/robot_base_frame" value="dtw_robot1/base_link" />
<param name="local_costmap/laser_scan_sensor/sensor_frame" value="dtw_robot1/front_laser_link" />
<param name="local_costmap/laser_scan_sensor/topic" value="/dtw_robot1/front_laser/scan" />
<param name="local_costmap/global_frame" value="dtw_robot1/odom" />
<param name="local_costmap/robot_base_frame" value="dtw_robot1/base_link" />
<remap from="cmd_vel" to="diff_drive_controller/cmd_vel" />
<remap from="odom" to="diff_drive_controller/odom" />
</node>
</group>
<!-- rviz -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(arg rvizconfig)" required="true" >
<remap from="/move_base_simple/goal" to="/dtw_robot1/move_base_simple/goal"/>
</node>
</launch>
上に書いたようにmove_baseは外との接続が多いのでrosトピック名、tf_frame名の設定項目が多くなります。
実行
roslaunch nav_lecture move_base.launch
以下のようにrvizの上の「2D Nav Goal」のボタンを押した後にrviz上の位置をクリックするとROSトピックが飛んでmove_baseが起動します。