diff --git a/nav2_bringup/bringup/params/forklift_params.yaml b/nav2_bringup/bringup/params/forklift_params.yaml index 257e5979d1f..aee1ac74d98 100644 --- a/nav2_bringup/bringup/params/forklift_params.yaml +++ b/nav2_bringup/bringup/params/forklift_params.yaml @@ -52,6 +52,11 @@ controller_server: no_outer_iterations: 4 max_number_classes: 4 min_turning_radius: 0.2 + use_sin_cos_approximation: True + weight_velocity_obstacle_ratio: 10.0 + obstacle_proximity_ratio_max_vel: 0.8 + obstacle_proximity_lower_bound: 0.0 + obstacle_proximity_upper_bound: 1.0 controller_server_rclcpp_node: @@ -62,20 +67,20 @@ controller_server_rclcpp_node: local_costmap: local_costmap: ros__parameters: - global_frame: map + global_frame: odom + update_frequency: 10.0 + publish_frequency: 7.0 robot_base_frame: base_link - plugins: ["obstacle_layer"] - obstacle_layer.plugin: "nav2_costmap_2d::ObstacleLayer" + map_topic: /costmap_node/map + plugins: ["static_layer"] + static_layer: + plugin: "nav2_costmap_2d::StaticLayer" + map_subscribe_transient_local: False rolling_window: True - width: 8 - height: 8 + width: 7 + height: 7 resolution: 2.0 - robot_radius: 0.25 - obstacle_layer: - enabled: True - observation_sources: scan - static_layer: - map_subscribe_transient_local: True + footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]" always_send_full_costmap: True local_costmap_client: ros__parameters: @@ -203,7 +208,7 @@ global_costmap: footprint: "[[1.8, 0.4], [1.8, -0.4], [-0.2, -0.4], [-0.2, 0.4]]" map_topic: /costmap_node/map track_unknown_space: false - plugins: ["static_layer", "obstacle_layer"] + plugins: ["static_layer", "obstacle_layer", "inflation_layer"] obstacle_layer: plugin: "nav2_costmap_2d::ObstacleLayer" enabled: false @@ -211,6 +216,10 @@ global_costmap: static_layer: plugin: "nav2_costmap_2d::StaticLayer" map_subscribe_transient_local: False + inflation_layer: + plugin: "nav2_costmap_2d::InflationLayer" + cost_scaling_factor: 10.0 + inflation_radius: 0.55 always_send_full_costmap: True global_costmap_client: ros__parameters: