障碍层地图通过订阅传感器话题,将传感器输出的障碍物信息存进buffer(剔除过高、过远的点),在本层地图上将观测到的点云标记为障碍物,将传感器到点云的连线上的点标记为FREE_SPACE
。最后在bound范围内,将本层地图合并到主地图上。
配置参数
通用代价地图中的障碍层常常是这样设置的:1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26obstacles:
enabled: true
obstacle_range: 2.0
raytrace_range: 5.0
track_unknown_space: true
combination_method: 1
observation_sources: laser_scan_sensor pointcloud2_sensor
laser_scan_sensor:
data_type: LaserScan
topic: /scan
marking: true
clearing: true
max_obstacle_height: 1.0
min_obstacle_height: -1.0
pointcloud2_sensor:
topic: /people_cloud
data_type: PointCloud2
sensor_frame: "/base_link"
obstacle_range: 5.0
raytrace_range: 5.0
observation_persistence: 5.0
marking: true
clearing: true
min_obstacle_height: 0.0
max_obstacle_height: 2.0
observation_persistence: 2.0. 如果设置为0,代价地图只考虑最近的观测数据
min_obstacle_height: 传感器读数的最小高度(以米为单位)视为有效。通常设置为地面高度。决定是否将地面的部分加入到代价地图,默认0
车周围实际没有障碍物,不同参数的情况如下:
这种情况下,避障太保守了。
max_obstacle_height: 默认2,单位米。插入代价地图的障碍物的最大高度,应当比机器人高度稍微高一点,应该是用于有机械臂的情况。设置为大于全局
max_obstacle_height
参数的值将会失效,设置为小于全局max_obstacle_height
的值将过滤掉传感器上大于该高度以的点。obstacle_range: 设置机器人检测障碍物的最大范围,意思是说超过该范围的障碍物,并不进行检测,只有靠近到该范围内才把该障碍物当作影响路径规划和移动的障碍物。对能否及早发现障碍物至关重要 ,跟车速也有关系。 如果车速0.6,
obstacle_range
设置为1.5,连正常避障都实现不了,至少也得3raytrace_range: 在机器人移动过程中,实时清除代价地图上的障碍物的最大范围,更新可自由移动的空间数据。假如设置该值为3米,那么就意味着在3米内的障碍物,本来开始时是有的,但是本次检测却没有了,那么就需要在代价地图上来更新,将旧障碍物的空间标记为可以自由移动的空间
增大raytrace_range
, obstacle_range
会增大数据量,影响代价地图刷新
inf_is_valid
: 默认是false,但是对点云障碍无效,仅对雷达scan有效:
1 | if (inf_is_valid) |
障碍层所用的参数:obstacles params
不能将近处障碍添加到代价地图
调来调去,发现min_obstacle_height
还是要设置为-0.3
比较合适,这时因为地面的原因,导致局部代价地图的四角都有了障碍,因此再降低obstacle_range
避免这一现象
局部代价地图中无法清除不在视野的障碍
costmap raytraces to clear out obstacles. 障碍物要想从地图上清除,它所占据的空间必须被新的观测看到。但是参数observation_persistence
常常无效。
last_updated_
is updated on every new cloud that needs to be added to the buffer. purgeStaleObservations
函数 checks the cloud’s time stamp with last_updated_
. When we stop publishing a point cloud last_updated_
will never be updated. Hence the observations will not time-out and remain in the observation_list_
. This may result in the following warning, when the robot drives away from the clouds in observation_list_
: Sensor origin at (x, y) is out of map bounds. The costmap cannot raytrace for it
将文件observation_buffer.cpp
中的函数purgeStaleObservations
中的last_updated_
改为nh_->now()
,会影响共享库liblayers.so
和 libcostmap_2d.so
1
2nav2_util::LifecycleNode::SharedPtr nh
last_updated_(nh->now())