move_base配置参数解析


move_base实际需要设置6部分参数:

  1. move_base自身参数
  2. 全局代价地图(global_costmap)
  3. 局部代价地图(local_costmap)
  4. 全局规划器(global_planner)
  5. 局部规划器(local_planner)
  6. 恢复机制(recovery_behaviors)

以上参数在move_base节点加载时全部加载,用以下参数文件格式:

<launch>
  <node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
	<rosparam file="$(find myrobot)/param/navigation_omi/omi/costmap_common_params.yaml" command="load" ns="global_costmap" />
	<rosparam file="$(find myrobot)/param/navigation_omi/omi/costmap_common_params.yaml" command="load" ns="local_costmap" />
        <rosparam file="$(find myrobot)/param/navigation_omi/local_costmap_params.yaml" command="load" />
        <rosparam file="$(find myrobot)/param/navigation_omi/global_costmap_params.yaml" command="load" />
	<rosparam file="$(find myrobot)/param/navigation_omi/omi/base_local_planner_params.yaml" command="load" />
	<rosparam file="$(find myrobot)/param/navigation_omi/omi/base_global_planner_params.yaml" command="load" />
        <rosparam file="$(find myrobot)/param/navigation_omi/move_base_params.yaml" command="load" />
	<remap from="/cmd_vel" to="/raw_cmd_vel"/>
  </node>
</launch>

costmap_common_params.yaml

max_obstacle_height: 1.0 # assume something like an arm is mounted on top of the robot

# Obstacle Cost Shaping (http://wiki.ros.org/costmap_2d/hydro/inflation)
robot_radius: 0.2 # 如果机器人是圆形,则指定机器人的半径;
map_type: voxel # 地图类型;


# 障碍物层的参数配置
obstacle_layer:
	enabled: true # 使能障碍物层;
	max_obstacle_height: 2.0 # 考虑的最大障碍物高度;
	origin_z: 0.0
	z_resolution: 0.2
	z_voxels: 2
	unknown_threshold: 15
	mark_threshold: 0
	combination_method: 1
	track_unknown_space: true # true 禁止全局路径规划穿越未知区域;
	obstacle_range: 5.5 # 添加障碍物范围,一方面考虑激光范围,另外范围越大越耗计算资源;
	raytrace_range: 6.0 # 清除障碍物范围;
	publish_voxel_map: false
	observation_sources: ultrasonic scan # 数据源;
	ultrasonic:
		data_type: PointCloud2
		topic: /robot_base/ultra_pcloud2 #ultra_pcloud2
		marking: true
		clearing: false
		min_obstacle_height: 0.0
		max_obstacle_height: 2.0
		oscillation_timeout: 0.0
		inf_is_valid: true
		observation_persistence: 0.0
	scan:
		data_type: LaserScan # scan数据类型;
		topic: scan # scan的话题名称;
		marking: true # 是否根据scan添加障碍物;
		clearing: true # 是否根据scan清除障碍物;
		min_obstacle_height: 0.0 # scan检测到的最小有效障碍物高度;
		max_obstacle_height: 2.0 # scan检测到的最大有效障碍物高度;
		inf_is_valid: true # scan的无穷远数据是否有效;


# 全局膨胀层参数配置
global_inflation_layer:
	enabled: true # 是否使能全局膨胀层;
	cost_scaling_factor: 5.0 # 膨胀层的指数衰减速度,值越小衰减越慢(default: 10);
	inflation_radius: 1.1 # 全局最大有效膨胀半径,即安装指数衰减扩张的最大半径,计算障碍物cos函数时使用。

  
# 局部膨胀层参数配置
local_inflation_layer:
	enabled: true # 是否使能局部膨胀层;
	cost_scaling_factor: 5.0 # 膨胀层的指数衰减速度,值越小衰减越慢(default: 10);
	inflation_radius: 0.1 # 局部最大有效膨胀半径,即安装指数衰减扩张的最大半径,计算障碍物cos函数时使用。


# 静态层参数配置

static_layer:
	map_topic: navigation_map # 静态地图话题
	enabled: true # 是否使用静态层

dwa_local_planner_params.yaml

DWAPlannerROS:
	# Robot Configuration Parameters - Kobuki 机器人配置参数-Kobuki
	max_vel_x: 0.5 # x方向最大线速度绝对值,单位:米
	min_vel_x: -0.05 # x方向最小线速度绝对值,单位:米/秒。如果为负值表示可以后退.

	max_vel_y: 0.0 # diff drive robot # y方向最大线速度绝对值,单位:米/秒。turtlebot为差分驱动机器人,所以为0
	min_vel_y: 0.0 # diff drive robot # y方向最小线速度绝对值,单位:米/秒。turtlebot为差分驱动机器人,所以为0

	max_trans_vel: 0.5 # 机器人最大平移速度的绝对值,单位为 m/s
	min_trans_vel: 0.1 # 器人最小平移速度的绝对值,单位为 m/s
	trans_stopped_vel: 0.1 # 机器人被认属于“停止”状态时的平移速度。如果机器人的速度低于该值,则认为机器人已停止。单位为 m/s
	# 注意不要将min_trans_vel设置为0,否则DWA认为平移速度不可忽略,将创建较小的旋转速度。

	max_rot_vel: 0.55 # 机器人的最大旋转角速度的绝对值,单位为 rad/s
	min_rot_vel: 0.35 # 机器人的最小旋转角速度的绝对值,单位为 rad/s
	rot_stopped_vel: 0.4 # 机器人被认属于“停止”状态时的旋转速度。单位为 rad/s

	acc_lim_x: 2.0 # 机器人在x方向的极限加速度,单位meters/sec^2
	acc_lim_theta: 4.0 # 机器人的极限旋转加速度,单位为rad/sec^2
	acc_lim_y: 0.0 # diff drive robot 机器人在y方向的极限加速度,对于差分机器人来说当然是0


	# Goal Tolerance Parameters 目标容差参数 注:这三个参数的设置及影响讨论请参考《ROS导航功能调优指南》
	yaw_goal_tolerance: 0.1 # 到达目标点时,控制器在偏航/旋转时的弧度容差(tolerance)。即:到达目标点时偏行角允许的误差,单位弧度
	xy_goal_tolerance: 0.1 # 到到目标点时,控制器在x和y方向上的容差(tolerence)(米)。即:到达目标点时,在xy平面内与目标点的距离误差
	# latch_xy_goal_tolerance: false # 设置为true时表示:如果到达容错距离内,机器人就会原地旋转;即使转动是会跑出容错距离外。


	# Forward Simulation Parameters 正向仿真参数 注:参数的设置及影响讨论请参考《ROS导航功能调优指南》
	sim_time: 1.7 # 前向模拟轨迹的时间,单位为s(seconds).7
	vx_samples: 6 # x方向速度空间的采样点数.
	vy_samples: 1 # y方向速度空间采样点数 Tutulebot为差分驱动机器人,所以y方向永远只有1个值(0.0)
	vtheta_samples: 20 # 旋转方向的速度空间采样点数.


	# Trajectory Scoring Parameters 轨迹评分参数
	path_distance_bias: 32.0 #60.0 # 控制器与给定路径接近程度的权重
	goal_distance_bias: 24.0 #24.0 # 控制器与局部目标点的接近程度的权重,也用于速度控制
	occdist_scale: 10.0 # 控制器躲避障碍物的程度
	forward_point_distance: 0.325 # 以机器人为中心,额外放置一个计分点的距离
	stop_time_buffer: 0.2 # 机器人在碰撞发生前必须拥有的最少时间量。该时间内所采用的轨迹仍视为有效。即:为防止碰撞,机器人必须提前停止的时间长度
	scaling_speed: 0.25 # 开始缩放机器人足迹时的速度的绝对值,单位为m/s。
	# 在进行对轨迹各个点计算footprintCost之前,会先计算缩放因子。如果当前平移速度小于scaling_speed,则缩放因子为1.0,
	# 否则,缩放因子为(vmag - scaling_speed) / (max_trans_vel - scaling_speed) * max_scaling_factor + 1.0。
	# 然后,该缩放因子会被用于计算轨迹中各个点的footprintCost。

	max_scaling_factor: 0.2 # 最大缩放因子。max_scaling_factor为上式的值的大小。
	turn_round_penalty: 6.0
	turn_round_scale: 1.0


	# Oscillation Prevention Parameters 防振参数
	oscillation_reset_dist: 0.05 # 机器人必须运动多少米远后才能复位震荡标记(机器人运动多远距离才会重置振荡标记)


	# Debugging 调试参数
	publish_traj_pc : true # 将规划的轨迹在RVIZ上进行可视化
	publish_cost_grid_pc: false # 将代价值进行可视化显示,如果设置为true,那么就会在~/cost_cloud话题上发sensor_msgs/PointCloud2类型消息.
	global_frame_id: odom # 全局参考坐标系为odom


	# Differential-drive robot configuration - necessary? # 差分机器人配置参数
	# holonomic_robot: false # 是否为全向机器人。值为false时为差分机器人;为true时表示全向机器人

global_costmap_params.yaml

global_costmap:
	global_frame: map # 全局坐标系
	robot_base_frame: base_link # 机器人基准坐标系
	update_frequency: 1.0 # global_costmap更新频率(内部计算用);
	publish_frequency: 1.0 # global_costmap发布频率(Rviz显示用);
	static_map: true # 是否位静态地图
	transform_tolerance: 0.5 # 订阅tf时的时间差冗余量;
	resolution: 0.05 # 栅格地图分辨率;
	plugins:
		- {name: static_layer, type: "costmap_2d::StaticLayer"}
		- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"}
		# - {name: range_sensor_layer, type: "range_sensor_layer::RangeSensorLayer"}
		# - {name: vectormap_layer, type: "vectormap_layer::VectorMapLayer"}
		- {name: global_inflation_layer, type: "costmap_2d::InflationLayer"}
		# - {name: polygon_obstacle_layer, type: "polygon_obstacle_layer_namespace::PolygonObstacleLayer"}

local_costmap_params.yaml

local_costmap:
	global_frame: odom
	robot_base_frame: base_link
	update_frequency: 7.0 # 局部代价地图的更新频率(内部计算使用);
	publish_frequency: 7.0 # 局部代价地图的发布频率 (Rviz显示使用);
	static_map: true # 是否为静态地图属性,代价地图位动态;
	rolling_window: true # 是否位滚动窗口(随着机器人移动而滑动);
	width: 6.0 # 局部地图宽度;
	height: 6.0 # 局部地图高度(长度);
	resolution: 0.05 # 栅格地图分辨率;
	transform_tolerance: 0.5 # 订阅tf时的时间差冗余量;
	plugins: # 局部代价地图使用的地图插件(顺序颠倒会影响效果)
		- {name: static_layer, type: "costmap_2d::StaticLayer"} # 静态地图层
		- {name: obstacle_layer, type: "costmap_2d::VoxelLayer"} # 障碍物层
		# - {name: range_sensor_layer, type: "range_sensor_layer::RangeSensorLayer"}
		# - {name: vectormap_layer, type: "vectormap_layer::VectorMapLayer"}
		- {name: local_inflation_layer, type: "costmap_2d::InflationLayer"} # 膨胀层
		# - {name: polygon_obstacle_layer, type: "polygon_obstacle_layer_namespace::PolygonObstacleLayer"}

move_base_params.yaml

shutdown_costmaps: false # move_base空闲时shutdown_costmaps为true会关掉cost_map,激活是会重新开启

controller_frequency: 10.0 #10.0 # 向底盘控制移动话题cmd_vel发送命令的频率,也是局部路径规划的更新频率,规划一次就算一次速度
controller_patience: 5.0 #5.0 # 在空间清理操作执行前,控制器花多长时间等有效控制下发

planner_frequency: 5.0 #1.0 # 全局规划操作的执行频率
planner_patience: 7.0 #7.0 # 在空间清理操作执行前,留给规划器多长时间来找出一条有效规划

oscillation_timeout: 10.0 # 10 # 执行修复机制前,允许振荡的时间
oscillation_distance: 0.2 # 来回运动在多大距离以上不会被认为是振荡

# local planner - default is trajectory rollout
base_local_planner: "dwa_local_planner/DWAPlannerROS" # 指定用于move_base的局部规划器名称
#base_local_planner: "teb_local_planner/TebLocalPlannerROS"

base_global_planner: "navfn/NavfnROS" #指定用于move_base的全局规划器插件名称
#base_global_planner: "global_planner/GlobalPlanner" #alternatives: global_planner/GlobalPlanner, carrot_planner/CarrotPlanner
clearing_radius: 20.0

#We plan to integrate recovery behaviors for robot but currently those belong to gopher and still have to be adapted.
## recovery behaviors; we avoid spinning, but we need a fall-back replanning
#recovery_behavior_enabled: false

recovery_behaviors:
	- name: 'super_conservative_reset1'
	type: 'clear_costmap_recovery/ClearCostmapRecovery'
	#- name: 'conservative_reset1'
	#type: 'clear_costmap_recovery/ClearCostmapRecovery'
	- name: 'aggressive_reset1'
	type: 'clear_costmap_recovery/ClearCostmapRecovery'
	- name: 'clearing_rotation1'
	type: 'rotate_recovery/RotateRecovery'

super_conservative_reset1:
	reset_distance: 1.5

aggressive_reset1:
	reset_distance: 0.0

参考链接:
[1] dwa_local_planner_params.yaml解读
[2] 【移动机器人技术】move_base参数配置方法及含义
[3] move_base_params.yaml参数解析

  • 8
    点赞
  • 168
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值