mirror of
https://github.com/6-robot/wpb_home.git
synced 2025-09-15 12:58:59 +08:00
update param for cost_map
This commit is contained in:
parent
dbe944d2c1
commit
5437a8c30c
@ -2,11 +2,9 @@ obstacle_range: 6.0
|
||||
raytrace_range: 6.0
|
||||
robot_radius: 0.25
|
||||
inflation_radius: 0.30
|
||||
cost_scaling_factor: 10.0
|
||||
observation_sources: scan_filtered
|
||||
scan_filtered: {
|
||||
sensor_frame: base_footprint,
|
||||
observation_persistence: 0.0,
|
||||
max_obstacle_height: 1.5,
|
||||
min_obstacle_height: 0.0,
|
||||
data_type: LaserScan,
|
||||
|
||||
Loading…
Reference in New Issue
Block a user