update
This commit is contained in:
36
config/config/costmap_params.yaml
Normal file
36
config/config/costmap_params.yaml
Normal file
@@ -0,0 +1,36 @@
|
||||
robot_costmap_2d:
|
||||
global_frame: map
|
||||
robot_base_frame: base_link
|
||||
rolling_window: false
|
||||
track_unknown_space: false
|
||||
|
||||
plugins:
|
||||
- name: static_layer
|
||||
type: StaticLayer
|
||||
|
||||
- name: inflation_layer
|
||||
type: InflationLayer
|
||||
|
||||
- name: obstacle_layer
|
||||
type: ObstacleLayer
|
||||
|
||||
- name: voxel_layer
|
||||
type: VoxelLayer
|
||||
|
||||
library_path: ./libplugins.so
|
||||
footprint:
|
||||
- [0.3, 0.3]
|
||||
- [0.3, -0.3]
|
||||
- [-0.3, -0.3]
|
||||
- [-0.3, 0.3]
|
||||
|
||||
transform_tolerance: 0.0
|
||||
update_frequency: 1.0
|
||||
width: 0.0
|
||||
height: 0.0
|
||||
resolution: 0.0
|
||||
origin_x: 0.0
|
||||
origin_y: 0.0
|
||||
|
||||
footprint_padding: 0.0
|
||||
robot_radius: 0.0
|
||||
5
config/config/inflation_layer_params.yaml
Normal file
5
config/config/inflation_layer_params.yaml
Normal file
@@ -0,0 +1,5 @@
|
||||
inflation_layer:
|
||||
enabled: true
|
||||
inflate_unknown: false
|
||||
cost_scaling_factor: 15.0
|
||||
inflation_radius: 0.55
|
||||
18
config/config/obstacle_layer_params.yaml
Normal file
18
config/config/obstacle_layer_params.yaml
Normal file
@@ -0,0 +1,18 @@
|
||||
obstacle_layer:
|
||||
track_unknown_space: true
|
||||
transform_tolerance: 0.2
|
||||
topic: "map"
|
||||
sensor_frame: laser_frame
|
||||
observation_persistence: 0.0
|
||||
expected_update_rate: 0.0
|
||||
data_type: PointCloud
|
||||
min_obstacle_height: 0.0
|
||||
max_obstacle_height: 2.0
|
||||
inf_is_valid: false
|
||||
clearing: false
|
||||
marking: true
|
||||
obstacle_range: 2.5
|
||||
raytrace_range: 3.0
|
||||
footprint_clearing_enabled: true
|
||||
combination_method: 1
|
||||
|
||||
11
config/config/static_layer_params.yaml
Normal file
11
config/config/static_layer_params.yaml
Normal file
@@ -0,0 +1,11 @@
|
||||
static_layer:
|
||||
enabled: true
|
||||
map_topic: "map"
|
||||
first_map_only: false
|
||||
subscribe_to_updates: false
|
||||
track_unknown_space: true
|
||||
use_maximum: false
|
||||
lethal_cost_threshold: 100
|
||||
unknown_cost_value: -1
|
||||
trinary_costmap: true
|
||||
base_frame_id: "map"
|
||||
11
config/config/voxel_layer_params.yaml
Normal file
11
config/config/voxel_layer_params.yaml
Normal file
@@ -0,0 +1,11 @@
|
||||
voxel_layer:
|
||||
enabled: true
|
||||
footprint_clearing_enabled: true
|
||||
max_obstacle_height: 3.0
|
||||
origin_z: 0.0
|
||||
z_resolution: 0.2
|
||||
z_voxels: 16
|
||||
unknown_threshold: 15.0
|
||||
mark_threshold: 0
|
||||
combination_method: 1
|
||||
|
||||
Reference in New Issue
Block a user