mirror of
https://github.com/bjoernellens1/cps_rmp220_support.git
synced 2024-11-23 15:45:08 +00:00
update
This commit is contained in:
parent
92067d1c19
commit
bd79d51b16
@ -509,26 +509,51 @@ local_costmap:
|
|||||||
plugin: "nav2_costmap_2d::InflationLayer"
|
plugin: "nav2_costmap_2d::InflationLayer"
|
||||||
cost_scaling_factor: 8.0 # was 3.0
|
cost_scaling_factor: 8.0 # was 3.0
|
||||||
inflation_radius: 0.44
|
inflation_radius: 0.44
|
||||||
|
# voxel_layer:
|
||||||
|
# plugin: "nav2_costmap_2d::VoxelLayer"
|
||||||
|
# enabled: True
|
||||||
|
# publish_voxel_map: True
|
||||||
|
# origin_z: 0.0
|
||||||
|
# z_resolution: 0.05
|
||||||
|
# z_voxels: 16
|
||||||
|
# max_obstacle_height: 2.0
|
||||||
|
# mark_threshold: 0
|
||||||
|
# observation_sources: scan
|
||||||
|
# scan:
|
||||||
|
# topic: /scan
|
||||||
|
# max_obstacle_height: 2.0
|
||||||
|
# clearing: True
|
||||||
|
# marking: True
|
||||||
|
# data_type: "LaserScan"
|
||||||
|
# raytrace_max_range: 8.0 # was 3.0
|
||||||
|
# raytrace_min_range: 0.0
|
||||||
|
# obstacle_max_range: 2.5
|
||||||
|
# obstacle_min_range: 0.0
|
||||||
voxel_layer:
|
voxel_layer:
|
||||||
plugin: "nav2_costmap_2d::VoxelLayer"
|
plugin: "nav2_costmap_2d::VoxelLayer"
|
||||||
enabled: True
|
enabled: True
|
||||||
publish_voxel_map: True
|
footprint_clearing_enabled: true
|
||||||
|
max_obstacle_height: 2.0
|
||||||
|
publish_voxel_map: false
|
||||||
origin_z: 0.0
|
origin_z: 0.0
|
||||||
z_resolution: 0.05
|
z_resolution: 0.1
|
||||||
z_voxels: 16
|
z_voxels: 16
|
||||||
max_obstacle_height: 2.0
|
max_obstacle_height: 2.0
|
||||||
mark_threshold: 0
|
unknown_threshold: 4
|
||||||
observation_sources: scan
|
mark_threshold: 2
|
||||||
scan:
|
observation_sources: oak-d
|
||||||
topic: /scan
|
combination_method: 1
|
||||||
max_obstacle_height: 2.0
|
oak-d: # no frame set, uses frame from message
|
||||||
|
topic: /stereo/points
|
||||||
|
max_obstacle_height: 1.5
|
||||||
|
min_obstacle_height: 0.02
|
||||||
|
obstacle_max_range: 3.0
|
||||||
|
obstacle_min_range: 0.0
|
||||||
|
raytrace_max_range: 3.2
|
||||||
|
raytrace_min_range: 0.0
|
||||||
clearing: True
|
clearing: True
|
||||||
marking: True
|
marking: True
|
||||||
data_type: "LaserScan"
|
data_type: "PointCloud2"
|
||||||
raytrace_max_range: 8.0 # was 3.0
|
|
||||||
raytrace_min_range: 0.0
|
|
||||||
obstacle_max_range: 2.5
|
|
||||||
obstacle_min_range: 0.0
|
|
||||||
static_layer:
|
static_layer:
|
||||||
plugin: "nav2_costmap_2d::StaticLayer"
|
plugin: "nav2_costmap_2d::StaticLayer"
|
||||||
map_subscribe_transient_local: True
|
map_subscribe_transient_local: True
|
||||||
|
Loading…
Reference in New Issue
Block a user