diff --git a/params/amcl.yaml b/params/amcl.yaml index e72b96063dde8595683ad4ea7b95a1ea9b128c3b..4c484e0c65726b8c1aba99299dbdede3e05fda77 100644 --- a/params/amcl.yaml +++ b/params/amcl.yaml @@ -37,9 +37,9 @@ laser_likelihood_max_dist: 2.0 laser_model_type: 'likelihood_field' # odom parameters odom_model_type: "diff" -odom_alpha1: 0.2 -odom_alpha2: 0.2 -odom_alpha3: 0.2 -odom_alpha4: 0.2 -odom_alpha5: 0.2 +odom_alpha1: 0.005 +odom_alpha2: 0.005 +odom_alpha3: 0.010 +odom_alpha4: 0.005 +odom_alpha5: 0.003 tf_broadcast: true diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml index 2ddbeb0c4e181fa59f3243b84c0f9e1b52f943cd..7af68624bc8401d434719f6ed0682dd187315733 100755 --- a/params/costmap/common_params.yaml +++ b/params/costmap/common_params.yaml @@ -57,4 +57,4 @@ inflation_layer: inflate_unknown: false inflation_radius: 2.0 cost_scaling_factor: 5.0 - inflation_radius: 0.5 \ No newline at end of file + inflation_radius: 0.5 diff --git a/params/global_planner/global_planner_params.yaml b/params/global_planner/global_planner_params.yaml index 43e309ed42c97c5a74f6afd6038f30944c1861a2..547cca1f606ba959863c4588883aef3f58073357 100644 --- a/params/global_planner/global_planner_params.yaml +++ b/params/global_planner/global_planner_params.yaml @@ -13,8 +13,8 @@ GlobalPlanner: #default use_grid_path: false # planner parameters lethal_cost: 253 - neutral_cost: 50 - cost_factor: 3.0 + neutral_cost: 66 + cost_factor: 0.55 planner_window_x: 0.0 planner_window_y: 0.0 # orientation fileter diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml index a13f9db6c72757bb3fe13342da73db244d755a8a..7bc8051e2d78d533da135829249c4326f4dbf1cf 100644 --- a/params/local_planner/dwa_params.yaml +++ b/params/local_planner/dwa_params.yaml @@ -6,11 +6,11 @@ DWAPlannerROS: max_trans_vel: 0.5 min_trans_vel: 0.1 max_vel_x: 0.5 - min_vel_x: -0.2 + min_vel_x: 0.0 max_vel_y: 0.0 min_vel_y: 0.0 max_rot_vel: 2.0 - min_rot_vel: -2.0 + min_rot_vel: 0.1 acc_lim_theta: 5.0 acc_lim_x: 1.0 acc_lim_y: 0.0 @@ -23,7 +23,7 @@ DWAPlannerROS: yaw_goal_tolerance: 0.1 # Forward simulation parameters - sim_time: 2.5 + sim_time: 3.5 sim_granularity: 0.1 angular_sim_granularity: 0.1 vx_samples: 21 @@ -32,9 +32,9 @@ DWAPlannerROS: controller_frequency: 20.0 # defines the sim_period # Trajectory scoring parameters - path_distance_bias: 32.0 - goal_distance_bias: 24.0 - occdist_scale: 0.01 + path_distance_bias: 50.0 + goal_distance_bias: 20.0 + occdist_scale: 0.02 twirling_scale: 0.0 stop_time_buffer: 0.2 forward_point_distance: 0.325 diff --git a/params/move_base_params.yaml b/params/move_base_params.yaml index d64f555c8b8aa403903261f7063995d149a98af8..7d1a6b7c40ce36dfae673122def3aad44c251a1d 100644 --- a/params/move_base_params.yaml +++ b/params/move_base_params.yaml @@ -3,21 +3,27 @@ recovery_behavior_enabled: false recovery_behaviors: + - {name: rotational_recovery, type: rotational_recovery/RotationalRecovery} - {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery} - {name: rotate_recovery, type: rotate_recovery/RotateRecovery} + - {name: twist_recovery, type: twist_recovery/TwistRecovery} - {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery} -controller_frequency: 10.0 -planner_patience: 5.0 +controller_frequency: 4.0 +planner_patience: 8.0 controller_patience: 5.0 -planner_frequency: 0.0 -max_planning_retries: -1 +planner_frequency: 5.0 +max_planning_retries: 5.0 conservative_reset_dist: 3.0 +linear_x: -0.5 +linear_y: 0.0 +angular_z: 0.0 + clearing_rotation_allowed: false -clearing_radius: 0.46 +clearing_radius: 0.46 shutdown_costmaps: false -oscillation_timeout: 0.0 -oscillation_distance: 0.5 +oscillation_timeout: 4.0 +oscillation_distance: 0.2 diff --git a/params/pointcloud_to_laserscan.yaml b/params/pointcloud_to_laserscan.yaml index c7176520ffe36b88392c5f3ab6d70d7fb110d393..120eb90529316fad34fa03874c46fad29c8e51e7 100644 --- a/params/pointcloud_to_laserscan.yaml +++ b/params/pointcloud_to_laserscan.yaml @@ -15,4 +15,4 @@ use_inf: true # 0 : Detect number of cores # 1 : Single threaded # 2->inf : Parallelism level -concurrency_level: 1 \ No newline at end of file +concurrency_level: 1