在我们使用local_costmap局部代价地图的参数的时候,我们发现了rolling_window这个选项,也就是滑动窗口,这个东西的作用我后面讲,我先讲一下我遇到的问题,我们在参加智能车航天物流组的时候,我们发现我们所规定的全局规划中的点于点之间的导航线是由dwa功能包自动生成的,它会严格按照确定没有障碍物的最短路径进行规划,这就出现了一个问题,在跑第一圈的时候我们的地图还是完全的“未知”的状态,而随着跑过去之后,地图会被轻微的篡改,会有一道像羊拉屎一样的,白色的,确定没有障碍物的空白小格子留在车跑过的路线上,而第二圈点和点之间规划出的线会弯弯曲曲严格的贴合着这些白色的格子,这就让我们的车子跑起来一直左右打方向盘,虽然勉强可以保持直行,但是随着越跑越多之后,摆的会越来越大,很容易撞墙。而将rolling_window参数设置为true之后,就可以避免这种问题,这时全局规划不会记录之前跑过的地方,也就不会留下像羊拉屎一样的痕迹来干扰我们的规划,让我们后面的规划和第一次的规划一样好。
global_costmap:
global_costmap:
# footprint: [[0.25,0.2],[0.25,-0.2],[-0.4,-0.2],[-0.4,0.2]] #[[0.325,0.225],[0.325,-0.225],[-0.325,-0.225],[-0.325,0.225]]
footprint: [[0.01,0.01],[0.01,-0.01],[-0.01,-0.01],[-0.01,0.01]]
footprint_padding: 0.01
transform_tolerance: 1.0
update_frequency: 50.0 #5.0
publish_frequency: 50.0
global_frame: map
robot_base_frame: base_link
resolution: 0.05
rolling_window: true
track_unknown_space: true
plugins:
- {name: static, type: "costmap_2d::StaticLayer"}
- {name: inflation, type: "costmap_2d::InflationLayer"}
static:
map_topic: /map
subscribe_to_updates: true
sensor:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: base_link, data_type: LaserScan, topic: /scan, marking: true, clearing: true}
inflation:
inflation_radius: 0.8
cost_scaling_factor: 10.0
local_costmap:
local_costmap:
footprint: [[0.25,0.2],[0.25,-0.2],[-0.4,-0.2],[-0.4,0.2]] #[[0.325,0.225],[0.325,-0.225],[-0.325,-0.225],[-0.325,0.225]]
footprint_padding: 0.01
transform_tolerance: 1.0
update_frequency: 50.0
publish_frequency: 50.0
global_frame: map
robot_base_frame: base_link
resolution: 0.05
static_map: false
rolling_window: true
width: 2.0
height: 2.0
plugins:
- {name: sensor, type: "costmap_2d::ObstacleLayer"}
- {name: inflation, type: "costmap_2d::InflationLayer"}
sensor:
observation_sources: laser_scan_sensor
laser_scan_sensor: {sensor_frame: laser, data_type: LaserScan, topic: scan, marking: true, clearing: true}
inflation:
inflation_radius: 1.0 #2.5
cost_scaling_factor: 10.0 #8.0