diff --git a/orange_navigation/config/navigation2_params.yaml b/orange_navigation/config/navigation2_params.yaml index 3e89276..c23314a 100644 --- a/orange_navigation/config/navigation2_params.yaml +++ b/orange_navigation/config/navigation2_params.yaml @@ -179,8 +179,8 @@ controller_server_rclcpp_node: local_costmap: local_costmap: ros__parameters: - update_frequency: 5.0 - publish_frequency: 2.0 + update_frequency: 10.0 + publish_frequency: 5.0 global_frame: odom robot_base_frame: base_footprint use_sim_time: True @@ -188,12 +188,12 @@ local_costmap: width: 8 height: 8 resolution: 0.05 - footprint: "[ [0.2, 0.33], [0.2, -0.33], [-0.65, -0.33], [-0.65, 0.33] ]" + footprint: "[ [0.40, 0.45], [0.40, -0.45], [-0.70, -0.45], [-0.70, 0.45] ]" plugins: ["obstacle_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" - inflation_radius: 0.2 - cost_scaling_factor: 30.0 + inflation_radius: 0.3 + cost_scaling_factor: 25.0 obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: True @@ -204,6 +204,8 @@ local_costmap: clearing: True marking: True data_type: "LaserScan" + clearing_radius: 1.0 + raytrace_range: 5.0 static_layer: map_subscribe_transient_local: True always_send_full_costmap: True