Skip to content

Commit

Permalink
Increase size of local cost map
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Nov 29, 2024
1 parent e8b0c6d commit e7b5d1b
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 21 deletions.
2 changes: 1 addition & 1 deletion docker/config/components.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,6 @@
components:
- type: LDR20
parent_link: cover_link
xyz: 0.18 0.0 0.02
xyz: 0.185 0.0 0.0
rpy: 0.0 0.0 0.0
device_namespace: None
20 changes: 10 additions & 10 deletions husarion_ugv_navigation/config/nav2_laserscan_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,8 @@ local_costmap:
update_frequency: 5.0
publish_frequency: 2.0

width: 5
height: 5
width: 8
height: 8
resolution: 0.05

always_send_full_costmap: true
Expand All @@ -161,18 +161,18 @@ local_costmap:
obstacle_layer:
plugin: nav2_costmap_2d::ObstacleLayer
footprint_clearing_enabled: true
min_obstacle_height: 0.1
max_obstacle_height: 0.5
observation_sources: scan
scan:
topic: <observation_topic>
clearing: true
marking: true
data_type: LaserScan
raytrace_max_range: 12.0
raytrace_min_range: 0.9
min_obstacle_height: 0.1
max_obstacle_height: 0.5
obstacle_max_range: 12.0
obstacle_min_range: 0.9
raytrace_max_range: 12.0
raytrace_min_range: 0.9
inflation_layer:
plugin: nav2_costmap_2d::InflationLayer
cost_scaling_factor: 1.3
Expand Down Expand Up @@ -205,18 +205,18 @@ global_costmap:
obstacle_layer:
plugin: nav2_costmap_2d::ObstacleLayer
footprint_clearing_enabled: true
min_obstacle_height: 0.1
max_obstacle_height: 0.5
observation_sources: scan
scan:
topic: <observation_topic>
clearing: true
marking: true
data_type: LaserScan
raytrace_max_range: 12.0
raytrace_min_range: 0.9
min_obstacle_height: 0.1
max_obstacle_height: 0.5
obstacle_max_range: 12.0
obstacle_min_range: 0.9
raytrace_max_range: 12.0
raytrace_min_range: 0.9
inflation_layer:
plugin: nav2_costmap_2d::InflationLayer
cost_scaling_factor: 1.5
Expand Down
20 changes: 10 additions & 10 deletions husarion_ugv_navigation/config/nav2_pointcloud_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -148,8 +148,8 @@ local_costmap:
update_frequency: 5.0
publish_frequency: 2.0

width: 5
height: 5
width: 8
height: 8
resolution: 0.05

always_send_full_costmap: true
Expand All @@ -164,19 +164,19 @@ local_costmap:
origin_z: 0.0
z_resolution: 0.05
z_voxels: 10
min_obstacle_height: 0.1
max_obstacle_height: 0.5
mark_threshold: 0
observation_sources: point_cloud
point_cloud:
topic: <observation_topic>
clearing: true
marking: true
data_type: PointCloud2
raytrace_max_range: 12.0
raytrace_min_range: 0.9
min_obstacle_height: 0.1
max_obstacle_height: 0.5
obstacle_max_range: 12.0
obstacle_min_range: 0.9
raytrace_max_range: 12.0
raytrace_min_range: 0.9
inflation_layer:
plugin: nav2_costmap_2d::InflationLayer
cost_scaling_factor: 1.3
Expand Down Expand Up @@ -212,19 +212,19 @@ global_costmap:
origin_z: 0.0
z_resolution: 0.05
z_voxels: 10
min_obstacle_height: 0.1
max_obstacle_height: 0.5
mark_threshold: 0
observation_sources: point_cloud
point_cloud:
topic: <observation_topic>
clearing: true
marking: true
data_type: PointCloud2
raytrace_max_range: 12.0
raytrace_min_range: 0.9
min_obstacle_height: 0.1
max_obstacle_height: 0.5
obstacle_max_range: 12.0
obstacle_min_range: 0.9
raytrace_max_range: 12.0
raytrace_min_range: 0.9
inflation_layer:
plugin: nav2_costmap_2d::InflationLayer
cost_scaling_factor: 1.5
Expand Down

0 comments on commit e7b5d1b

Please sign in to comment.