From 485b59d5fcd4e33951998afef4d96614345c7fb9 Mon Sep 17 00:00:00 2001 From: shunki1006 Date: Mon, 20 Nov 2023 03:50:20 +0000 Subject: [PATCH 1/2] fix_Nav2_param_&_navigation_launch --- ..._from_left .yaml => navigation2_params_from_left.yaml} | 8 ++++---- .../config/navigation2_params_from_right.yaml | 2 +- orange_navigation/launch/multi_map_navigation.launch.xml | 2 +- orange_navigation/launch/waypoint_navigation.launch.xml | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) rename orange_navigation/config/{navigation2_params_from_left .yaml => navigation2_params_from_left.yaml} (97%) diff --git a/orange_navigation/config/navigation2_params_from_left .yaml b/orange_navigation/config/navigation2_params_from_left.yaml similarity index 97% rename from orange_navigation/config/navigation2_params_from_left .yaml rename to orange_navigation/config/navigation2_params_from_left.yaml index 975eebc..751e20c 100644 --- a/orange_navigation/config/navigation2_params_from_left .yaml +++ b/orange_navigation/config/navigation2_params_from_left.yaml @@ -23,7 +23,7 @@ amcl: laser_min_range: -1.0 laser_model_type: "likelihood_field" set_initial_pose: True - initial_pose: {x: 0.0, y: 2.0, z: 0.0, yaw: 0.0} + initial_pose: {x: 0.0, y: 4.2, z: 0.0, yaw: 0.0} max_beams: 300 max_particles: 1500 min_particles: 500 @@ -124,8 +124,8 @@ controller_server: general_goal_checker: stateful: True plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.25 - yaw_goal_tolerance: 0.50 + xy_goal_tolerance: 0.10 #0.25 + yaw_goal_tolerance: 0.10 #0.50 FollowPath: plugin: "dwb_core::DWBLocalPlanner" @@ -198,7 +198,7 @@ local_costmap: width: 8 height: 8 resolution: 0.05 - footprint: "[ [0.40, 0.45], [0.40, -0.45], [-0.70, -0.45], [-0.70, 0.45] ]" + footprint: "[ [0.20, 0.33], [0.20, -0.33], [-0.65, -0.33], [-0.65, 0.33] ]" plugins: ["obstacle_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" diff --git a/orange_navigation/config/navigation2_params_from_right.yaml b/orange_navigation/config/navigation2_params_from_right.yaml index 73a21d9..b508220 100644 --- a/orange_navigation/config/navigation2_params_from_right.yaml +++ b/orange_navigation/config/navigation2_params_from_right.yaml @@ -258,7 +258,7 @@ global_costmap: inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 2.0 - inflation_radius: 1.5 + inflation_radius: 3.0 always_send_full_costmap: True global_costmap_client: ros__parameters: diff --git a/orange_navigation/launch/multi_map_navigation.launch.xml b/orange_navigation/launch/multi_map_navigation.launch.xml index fa95acb..7111b9f 100644 --- a/orange_navigation/launch/multi_map_navigation.launch.xml +++ b/orange_navigation/launch/multi_map_navigation.launch.xml @@ -11,7 +11,7 @@ - + diff --git a/orange_navigation/launch/waypoint_navigation.launch.xml b/orange_navigation/launch/waypoint_navigation.launch.xml index 5a806d4..c608d88 100644 --- a/orange_navigation/launch/waypoint_navigation.launch.xml +++ b/orange_navigation/launch/waypoint_navigation.launch.xml @@ -5,7 +5,7 @@ - + From 72ecc99be429cfdd4c9f48e70188487313d967fb Mon Sep 17 00:00:00 2001 From: shunki1006 Date: Mon, 20 Nov 2023 04:27:56 +0000 Subject: [PATCH 2/2] fix_nav2_param_&_launch_file_path --- .../config/navigation2_params_from_left.yaml | 4 ++-- .../config/navigation2_params_from_right.yaml | 8 ++++---- orange_navigation/launch/waypoint_navigation.launch.xml | 4 ++-- 3 files changed, 8 insertions(+), 8 deletions(-) diff --git a/orange_navigation/config/navigation2_params_from_left.yaml b/orange_navigation/config/navigation2_params_from_left.yaml index 751e20c..e16dd22 100644 --- a/orange_navigation/config/navigation2_params_from_left.yaml +++ b/orange_navigation/config/navigation2_params_from_left.yaml @@ -124,8 +124,8 @@ controller_server: general_goal_checker: stateful: True plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.10 #0.25 - yaw_goal_tolerance: 0.10 #0.50 + xy_goal_tolerance: 0.10 + yaw_goal_tolerance: 0.10 FollowPath: plugin: "dwb_core::DWBLocalPlanner" diff --git a/orange_navigation/config/navigation2_params_from_right.yaml b/orange_navigation/config/navigation2_params_from_right.yaml index b508220..284db20 100644 --- a/orange_navigation/config/navigation2_params_from_right.yaml +++ b/orange_navigation/config/navigation2_params_from_right.yaml @@ -124,8 +124,8 @@ controller_server: general_goal_checker: stateful: True plugin: "nav2_controller::SimpleGoalChecker" - xy_goal_tolerance: 0.25 - yaw_goal_tolerance: 0.50 + xy_goal_tolerance: 0.10 + yaw_goal_tolerance: 0.10 FollowPath: plugin: "dwb_core::DWBLocalPlanner" @@ -198,7 +198,7 @@ local_costmap: width: 8 height: 8 resolution: 0.05 - footprint: "[ [0.40, 0.45], [0.40, -0.45], [-0.70, -0.45], [-0.70, 0.45] ]" + footprint: "[ [0.20, 0.33], [0.20, -0.33], [-0.65, -0.33], [-0.65, 0.33] ]" plugins: ["obstacle_layer", "inflation_layer"] inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" @@ -258,7 +258,7 @@ global_costmap: inflation_layer: plugin: "nav2_costmap_2d::InflationLayer" cost_scaling_factor: 2.0 - inflation_radius: 3.0 + inflation_radius: 1.5 always_send_full_costmap: True global_costmap_client: ros__parameters: diff --git a/orange_navigation/launch/waypoint_navigation.launch.xml b/orange_navigation/launch/waypoint_navigation.launch.xml index c608d88..3c40cb5 100644 --- a/orange_navigation/launch/waypoint_navigation.launch.xml +++ b/orange_navigation/launch/waypoint_navigation.launch.xml @@ -2,14 +2,14 @@ - + - +