From ae5e3f2135205a2492530d5dfb56d2bb258fcbd1 Mon Sep 17 00:00:00 2001 From: manthan99 Date: Thu, 13 Jul 2023 11:36:26 +0200 Subject: [PATCH] change params --- smb_navigation/config/base_local_planner_exploration.yaml | 8 ++++---- .../global_costmap_params_exploration.yaml | 2 +- .../config/move_base_costmaps/local_costmap_params.yaml | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/smb_navigation/config/base_local_planner_exploration.yaml b/smb_navigation/config/base_local_planner_exploration.yaml index 42344c2..24d1c14 100644 --- a/smb_navigation/config/base_local_planner_exploration.yaml +++ b/smb_navigation/config/base_local_planner_exploration.yaml @@ -20,14 +20,14 @@ TebLocalPlannerROS: global_plan_viapoint_sep: 0.5 # Robot - max_vel_x: 0.75 + max_vel_x: 0.5 max_vel_y: 0.0 - max_vel_x_backwards: 0.75 + max_vel_x_backwards: 0.5 max_vel_y_backwards: 0.0 max_vel_theta: 1.0 acc_lim_x: 1.0 acc_lim_y: 0.0 - acc_lim_theta: 1.0 + acc_lim_theta: 2.0 use_proportional_saturation: true @@ -75,7 +75,7 @@ TebLocalPlannerROS: weight_kinematics_turning_radius: 0.5 weight_optimaltime: 25.0 weight_shortest_path: 1.0 - weight_obstacle: 1 + weight_obstacle: 50 weight_viapoint: 1.0 # Increase to stick closer to global plan weight_dynamic_obstacle: 10 # not in use yet selection_alternative_time_cost: False # not in use yet diff --git a/smb_navigation/config/move_base_costmaps/global_costmap_params_exploration.yaml b/smb_navigation/config/move_base_costmaps/global_costmap_params_exploration.yaml index 614267e..759a93f 100644 --- a/smb_navigation/config/move_base_costmaps/global_costmap_params_exploration.yaml +++ b/smb_navigation/config/move_base_costmaps/global_costmap_params_exploration.yaml @@ -7,7 +7,7 @@ global_costmap: rolling_window: true resolution: 0.05 - footprint: [[0.43, 0.43], [0.43, -0.43], [-0.43, -0.43], [-0.43, 0.43]] # footprint fo the robot, centered in robot centre + footprint: [[0.40, 0.40], [0.40, -0.40], [-0.40, -0.40], [-0.40, 0.40]] # footprint fo the robot, centered in robot centre # robot_radius: 0.4 # Just use radius now instead of footprint (To speedup collision checking) width: 30.0 diff --git a/smb_navigation/config/move_base_costmaps/local_costmap_params.yaml b/smb_navigation/config/move_base_costmaps/local_costmap_params.yaml index 0cd7dec..9e6e0ca 100644 --- a/smb_navigation/config/move_base_costmaps/local_costmap_params.yaml +++ b/smb_navigation/config/move_base_costmaps/local_costmap_params.yaml @@ -4,7 +4,7 @@ local_costmap: update_frequency: 10.0 publish_frequency: 2.0 transform_tolerance: 0.5 # [s] - footprint: [[0.43, 0.43], [0.43, -0.43], [-0.43, -0.43], [-0.43, 0.43]] # footprint fo the robot, centered in robot centre + footprint: [[0.40, 0.40], [0.40, -0.40], [-0.40, -0.40], [-0.40, 0.40]] # footprint fo the robot, centered in robot centre # robot_radius: 0.4 # Just use radius now instead of footprint (To speedup collision checking) rolling_window: true