diff --git a/config/nav2_params.yaml b/config/nav2_params.yaml index 1a88fd5..ab5b72f 100644 --- a/config/nav2_params.yaml +++ b/config/nav2_params.yaml @@ -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: -1.0 # was 100 before: setting now to laser reported range (8m) laser_min_range: -1.0 laser_model_type: "likelihood_field" max_beams: 60 @@ -194,8 +194,8 @@ controller_server: local_costmap: local_costmap: ros__parameters: - update_frequency: 5.0 - publish_frequency: 2.0 + update_frequency: 10.0 # was 5.0 + publish_frequency: 5.0 # was 2.0 global_frame: odom robot_base_frame: base_link use_sim_time: True @@ -229,7 +229,7 @@ local_costmap: clearing: True marking: True data_type: "LaserScan" - raytrace_max_range: 3.0 + raytrace_max_range: 8.0 # was 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0 @@ -264,7 +264,7 @@ global_costmap: clearing: True marking: True data_type: "LaserScan" - raytrace_max_range: 3.0 + raytrace_max_range: 8.0 # was 3.0 raytrace_min_range: 0.0 obstacle_max_range: 2.5 obstacle_min_range: 0.0