Skip to content

Commit

Permalink
Merge pull request #14 from LCAS/nav_fixes
Browse files Browse the repository at this point in the history
map update and nav fixes for improved robustness
  • Loading branch information
gcielniak authored Dec 12, 2023
2 parents ff73bac + 7749eb4 commit 057e9a5
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 11 deletions.
Binary file modified src/limo_navigation/maps/assessment_map.pgm
Binary file not shown.
2 changes: 1 addition & 1 deletion src/limo_navigation/maps/assessment_map.yaml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
image: assessment_map.pgm
mode: trinary
resolution: 0.05
origin: [-1.51, -0.758, 0]
origin: [-1.51, -1.31, 0]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.25
20 changes: 10 additions & 10 deletions src/limo_navigation/params/nav2_params.yaml
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
amcl:
ros__parameters:
use_sim_time: False
alpha1: 0.2
alpha2: 0.2
alpha3: 0.2
alpha4: 0.2
alpha5: 0.2
alpha1: 0.02
alpha2: 0.02
alpha3: 0.02
alpha4: 0.02
alpha5: 0.02
base_frame_id: "base_footprint"
beam_skip_distance: 0.5
beam_skip_error_threshold: 0.9
Expand All @@ -14,7 +14,7 @@ amcl:
global_frame_id: "map"
lambda_short: 0.1
laser_likelihood_max_dist: 2.0
laser_max_range: 100.0
laser_max_range: 10.0
laser_min_range: -1.0
laser_model_type: "likelihood_field"
max_beams: 60
Expand Down Expand Up @@ -187,13 +187,13 @@ controller_server:
global_costmap:
global_costmap:
ros__parameters:
footprint_padding: 0.03
footprint_padding: 0.00
update_frequency: 1.0
publish_frequency: 1.0
global_frame: map
robot_base_frame: base_link
use_sim_time: True
robot_radius: 0.22 # radius set and used, so no footprint points
robot_radius: 0.10 # radius set and used, so no footprint points
resolution: 0.05
plugins: ["static_layer", "obstacle_layer", "inflation_layer"]
obstacle_layer:
Expand Down Expand Up @@ -224,7 +224,7 @@ global_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: true
inflation_radius: 0.55
inflation_radius: 0.1
cost_scaling_factor: 1.0
inflate_unknown: false
inflate_around_unknown: true
Expand Down Expand Up @@ -266,7 +266,7 @@ local_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
enabled: true
inflation_radius: 0.4
inflation_radius: 0.1
cost_scaling_factor: 1.0
inflate_unknown: false
inflate_around_unknown: true
Expand Down

0 comments on commit 057e9a5

Please sign in to comment.