87 lines
2.8 KiB
YAML
87 lines
2.8 KiB
YAML
global_costmap:
|
|
plugins:
|
|
- { name: static_layer, type: "costmap_2d::StaticLayer" }
|
|
# - { name: keep_out_layer, type: "costmap_2d::KeepOutLayer" }
|
|
- { name: obstacle_layer, type: "costmap_2d::ObstacleLayer" }
|
|
- { name: inflation_layer, type: "costmap_2d::InflationLayer" }
|
|
|
|
track_unknown_space: false
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
map_type: costmap
|
|
# footprint: [[0.3, 0.15], [0.25, 0.2], [-0.1, 0.2], [-0.1, -0.2], [0.25, -0.2], [0.3, -0.15]]
|
|
# footprint_padding: 0.05
|
|
robot_radius: 0.2
|
|
|
|
update_frequency: 5
|
|
publish_frequency: 0.5
|
|
transform_tolerance: 0.5
|
|
|
|
static_map: true
|
|
always_send_full_costmap: false
|
|
resolution: 0.05
|
|
|
|
static_layer:
|
|
map_topic: /map # /grid_map_realtime #
|
|
track_unknown_space: false
|
|
|
|
# keep_out_layer:
|
|
# enabled: true
|
|
# fill_zones: false
|
|
# inflation_option: 3
|
|
|
|
obstacle_layer:
|
|
observation_sources: 3dscan # 2dscan # /cloud_registered_body
|
|
3dscan: { sensor_frame: body, data_type: PointCloud2, topic: /cloud_registered_body, obstacle_range: 10, raytrace_range: 10, marking: true, clearing: true, min_obstacle_height: -0.3, max_obstacle_height: 0.1 }
|
|
# 2dscan: { sensor_frame: laser_link, data_type: LaserScan, topic: scan, obstacle_range: 6.0, raytrace_range: 6.5, marking: true, clearing: true }
|
|
track_unknown_space: false
|
|
inflation_option: 3
|
|
|
|
inflation_layer:
|
|
inflation_radius: 0.2
|
|
cost_scaling_factor: 2.61
|
|
|
|
local_costmap:
|
|
plugins:
|
|
- { name: static_layer, type: "costmap_2d::StaticLayer" }
|
|
# - { name: keep_out_layer, type: "costmap_2d::KeepOutLayer" }
|
|
- { name: obstacle_layer, type: "costmap_2d::ObstacleLayer" }
|
|
- { name: inflation_layer, type: "costmap_2d::InflationLayer" }
|
|
|
|
static_layer:
|
|
map_topic: /map # /grid_map_realtime #
|
|
track_unknown_space: false
|
|
|
|
global_frame: map
|
|
robot_base_frame: base_link
|
|
map_type: costmap
|
|
# footprint: [[0.3, 0.15], [0.25, 0.2], [-0.1, 0.2], [-0.1, -0.2], [0.25, -0.2], [0.3, -0.15]]
|
|
# footprint_padding: 0.0
|
|
robot_radius: 0.2
|
|
|
|
update_frequency: 5 #5
|
|
publish_frequency: 2 # 1.0
|
|
transform_tolerance: 0.5
|
|
|
|
static_map: false
|
|
rolling_window: true
|
|
width: 3
|
|
height: 3
|
|
resolution: 0.05
|
|
|
|
# keep_out_layer:
|
|
# enabled: true
|
|
# fill_zones: false
|
|
# inflation_option: 3
|
|
|
|
obstacle_layer:
|
|
observation_sources: 3dscan # 2dscan
|
|
3dscan: { sensor_frame: body, data_type: PointCloud2, topic: /cloud_registered_body, obstacle_range: 3, raytrace_range: 3, marking: true, clearing: true, min_obstacle_height: -0.2, max_obstacle_height: 0.2 }
|
|
# 2dscan: { sensor_frame: laser_link, data_type: LaserScan, topic: scan, obstacle_range: 6.0, raytrace_range: 6.5, marking: true, clearing: true }
|
|
track_unknown_space: false
|
|
inflation_option: 3
|
|
|
|
inflation_layer:
|
|
inflation_radius: 0.2
|
|
cost_scaling_factor: 2.61
|