move_base
参数详解:move_base
概述引言
ROS的move_base
正如其名,是用于基座移动的功能包,用于实现基座的移动。为把握move_base
对于costmap2D
,global planner
,local planner
的调用关系。
这里采用turtlebot_navigation
的package 为例进行说明。
move_base
的启动启动move_base
的launch文件内容通常为(以Turtlebot 2e为例):
turtlebot_apps/turtlebot_navigation/launch/amcl_demo.launch
的启动代码为:
<arg name="custom_param_file" default="$(find turtlebot_navigation)/param/$(arg 3d_sensor)_costmap_params.yaml"/>
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml">
<arg name="custom_param_file" value="$(arg custom_param_file)"/>
include>
turtlebot_apps/turtlebot_navigation/launch/gmapping_demo.launch
中的启动代码为:
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>
可见建图的过程中采用的是默认参数,而导航过程考虑了3D sensor的传感器特征。以下看看各种传感器的costmap_param.yaml
定义:
$ ls -al
total 48
lrwxrwxrwx 1 teddyluo teddyluo 10 5月 15 20:43 astra_costmap_params.yaml -> dummy.yaml
lrwxrwxrwx 1 teddyluo teddyluo 10 5月 15 20:43 asus_xtion_pro_costmap_params.yaml -> dummy.yaml
lrwxrwxrwx 1 teddyluo teddyluo 10 5月 15 20:43 asus_xtion_pro_offset_costmap_params.yaml -> dummy.yaml
-rw-rw-r-- 1 teddyluo teddyluo 1621 5月 15 20:43 costmap_common_params.yaml
-rw-rw-r-- 1 teddyluo teddyluo 57 5月 15 20:43 dummy.yaml
-rw-rw-r-- 1 teddyluo teddyluo 2262 5月 15 20:43 dwa_local_planner_params.yaml
-rw-rw-r-- 1 teddyluo teddyluo 405 5月 15 20:43 global_costmap_params.yaml
-rw-rw-r-- 1 teddyluo teddyluo 1730 5月 15 20:43 global_planner_params.yaml
lrwxrwxrwx 1 teddyluo teddyluo 10 5月 15 20:43 kinect_costmap_params.yaml -> dummy.yaml
-rw-rw-r-- 1 teddyluo teddyluo 394 5月 15 20:43 local_costmap_params.yaml
-rw-rw-r-- 1 teddyluo teddyluo 695 5月 15 20:43 lsxxx_costmap_params.yaml
-rw-rw-r-- 1 teddyluo teddyluo 1764 5月 15 20:43 move_base_params.yaml
其中 dummy.yaml
是个空文件。
可以看到,最常用的传感器的$(arg 3d_sensor)_costmap_params.yaml
并没有定义。可以认为这两条指令是等价的。
move_base.launch.xml
的内容
<launch>
<include file="$(find turtlebot_navigation)/launch/includes/velocity_smoother.launch.xml"/>
<include file="$(find turtlebot_navigation)/launch/includes/safety_controller.launch.xml"/>
<arg name="odom_frame_id" default="odom"/>
<arg name="base_frame_id" default="base_footprint"/>
<arg name="global_frame_id" default="map"/>
<arg name="odom_topic" default="odom" />
<arg name="laser_topic" default="scan" />
<arg name="custom_param_file" default="$(find turtlebot_navigation)/param/dummy.yaml"/>
<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" />
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/global_planner_params.yaml" command="load" />
<rosparam file="$(find turtlebot_navigation)/param/navfn_global_planner_params.yaml" command="load" />
<rosparam file="$(arg custom_param_file)" command="load" />
<param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
<param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
<param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
<param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
<param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>
<remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg laser_topic)"/>
node>
launch>
move_base
节点定义<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="global_costmap" /> #通用的costmap参数定义(全局空间)
<rosparam file="$(find turtlebot_navigation)/param/costmap_common_params.yaml" command="load" ns="local_costmap" /> #通用的costmap参数定义(局部空间)
<rosparam file="$(find turtlebot_navigation)/param/local_costmap_params.yaml" command="load" /> #本地的costmap参数定义
<rosparam file="$(find turtlebot_navigation)/param/global_costmap_params.yaml" command="load" /> #全局costmap参数定义
<rosparam file="$(find turtlebot_navigation)/param/dwa_local_planner_params.yaml" command="load" /> #dwa本地规划参数定义
<rosparam file="$(find turtlebot_navigation)/param/move_base_params.yaml" command="load" /> #底盘移动启动文件
<rosparam file="$(find turtlebot_navigation)/param/global_planner_params.yaml" command="load" /> #全局规划参数定义
<rosparam file="$(find turtlebot_navigation)/param/navfn_global_planner_params.yaml" command="load" /> #navfn全局规划参数定义
<rosparam file="$(arg custom_param_file)" command="load" />
<param name="global_costmap/global_frame" value="$(arg global_frame_id)"/>
<param name="global_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
<param name="local_costmap/global_frame" value="$(arg odom_frame_id)"/>
<param name="local_costmap/robot_base_frame" value="$(arg base_frame_id)"/>
<param name="DWAPlannerROS/global_frame_id" value="$(arg odom_frame_id)"/>
<remap from="cmd_vel" to="navigation_velocity_smoother/raw_cmd_vel"/>
<remap from="odom" to="$(arg odom_topic)"/>
<remap from="scan" to="$(arg laser_topic)"/>
node>
注:由于手上没有编辑器,所以简要在上面用符号#
表示注释。
首先,代价地图的定义,包含全局代价地图和局部代价地图:
/param/costmap_common_params.yaml" command="load" ns="global_costmap"
/param/costmap_common_params.yaml" command="load" ns="local_costmap"
/param/local_costmap_params.yaml" command="load"
/param/global_costmap_params.yaml" command="load" #全局costmap参数定义
其次,加载了规划器的参数,
dwa_local_planner_params.yaml
global_planner
的参数global_planner_params.yaml
navfn_global_planner_params.yaml
$(arg custom_param_file)
,由前面可知是一个空文件最后,定义了坐标系:
global_costmap/global_frame
--> map
全局代价地图中全局坐标系为mapglobal_costmap/robot_base_frame
--> base_footprint
全局代价地图中机器人本体坐标系为base_footprint
local_costmap/global_frame
--> odom
局部代价的全局坐标系为odomlocal_costmap/robot_base_frame
--> base_footprint
局部代价机器人本体坐标系为base_footprint
DWAPlannerROS/global_frame_id
--> odom
DWA局部规划器中全局坐标系为odom
三个topic的remap:
cmd_vel
--> navigation_velocity_smoother/raw_cmd_vel
将速度话题cmd_vel
remap为navigation_velocity_smoother/raw_cmd_vel
odom
--> odom
odom
remap为 odom
(写得能通用,因为可以在前面改变topic的name)scan
--> scan
scan
remap为 scan
注:变量名称
<arg name="odom_frame_id" default="odom"/>
<arg name="base_frame_id" default="base_footprint"/>
<arg name="global_frame_id" default="map"/>
<arg name="odom_topic" default="odom" />
<arg name="laser_topic" default="scan" />
<arg name="custom_param_file" default="$(find turtlebot_navigation)/param/dummy.yaml"/>
理解为
odom_frame_id
的默认值为odom
(odom
坐标系)base_frame_id
的默认值为base_footprint
(base_footprint
坐标系)global_frame_id
的默认值为map
(map
坐标系)odom_topic
的默认值为odom
(odom
topic)laser_topic
的默认值为scan
(scan
topic)custom_param_file
的默认值为$(find turtlebot_navigation)/param/dummy.yaml
turtlebot_ws/src/turtlebot_apps/turtlebot_navigation
目录的文件树结构├── CHANGELOG.rst
├── CMakeLists.txt
├── env-hooks #钩子
│ └── 25.turtlebot-navigation.sh.em #设置一些稳定的默认值,目前是导出TURTLEBOT_MAP_FILE,使用默认的地图。
├── laser #雷达相关设置
│ ├── costmap_common_params.yaml #costmap的通用参数
│ ├── laser_amcl_demo.launch #激光amcl启动文件
│ ├── laser_gmapping_demo.launch #激光gmapping启动文件
│ └── move_base_laser.launch #带激光底盘移动启动文件
├── launch #启动目录
│ ├── amcl_demo.launch #amcl启动文件
│ ├── gmapping_demo.launch #gmapping启动文件
│ ├── graveyard
│ │ └── graveyard_bump_navi_demo.launch #
│ └── includes #启动文件的子模块
│ ├── amcl #即时定位
│ │ ├── amcl.launch.xml #即时定位核心启动文件
│ │ ├── astra_amcl.launch.xml -> amcl.launch.xml #使用astra进行定位
│ │ ├── asus_xtion_pro_amcl.launch.xml -> amcl.launch.xml #使用asus_xtion_pro进行定位
│ │ ├── asus_xtion_pro_offset_amcl.launch.xml -> amcl.launch.xml #使用asus_xtion_pro_live进行定位
│ │ ├── kinect_amcl.launch.xml -> amcl.launch.xml #使用kinect进行定位
│ │ └── r200_amcl.launch.xml #使用r200进行定位
│ ├── gmapping #实时建图
│ │ ├── astra_gmapping.launch.xml -> gmapping.launch.xml #使用astra建图
│ │ ├── asus_xtion_pro_gmapping.launch.xml -> gmapping.launch.xml #使用asus_xtion_pro建图
│ │ ├── asus_xtion_pro_offset_gmapping.launch.xml -> gmapping.launch.xml #使用asus_xtion_pro_live建图
│ │ ├── gmapping.launch.xml #实际建图核心启动文件
│ │ ├── kinect_gmapping.launch.xml -> gmapping.launch.xml #使用kinect建图
│ │ └── r200_gmapping.launch.xml #使用r200建图
│ ├── move_base.launch.xml #底盘移动启动文件
│ ├── safety_controller.launch.xml #安全控制启动文件
│ └── velocity_smoother.launch.xml #速度平滑启动文件
├── maps #地图目录
│ ├── willow-2010-02-18-0.10.pgm
│ └── willow-2010-02-18-0.10.yaml
├── package.xml
├── param #参数目录
│ ├── astra_costmap_params.yaml -> dummy.yaml #astra的costmap参数定义,指向空文件
│ ├── asus_xtion_pro_costmap_params.yaml -> dummy.yaml #asus_xtion_pro的costmap参数定义,指向空文件
│ ├── asus_xtion_pro_offset_costmap_params.yaml -> dummy.yaml #asus_xtion_pro_live的costmap参数定义,指向空文件
│ ├── costmap_common_params.yaml #通用的costmap参数定义
│ ├── dummy.yaml #空文件,没有自定义的参数设置
│ ├── dwa_local_planner_params.yaml #dwa本地规划参数定义
│ ├── global_costmap_params.yaml #全局costmap参数定义
│ ├── global_planner_params.yaml #全局规划参数定义
│ ├── kinect_costmap_params.yaml -> dummy.yaml #kinect的costmap参数定义,指向空文件
│ ├── local_costmap_params.yaml #本地的costmap参数定义
│ ├── move_base_params.yaml #底盘移动参数定义
│ ├── navfn_global_planner_params.yaml #navfn全局规划参数定义
│ └── r200_costmap_params.yaml #r200的costmap参数定义
└── src #源码目录
└── laser_footprint_filter.cpp #激光过滤footprint源码, 订阅/scan话题,过滤后,重发布/scan_filtered话题
下面我们先来学习速度平滑、安全驾驶,再看看环境代价地图的定义,再理解规划器的设置,最后看看move_base启动本身。