diff --git a/config/adc_rosnav/amcl_no_tf.yaml b/config/adc_rosnav/amcl_no_tf.yaml index 02cb42e41bb09cb387d99c6e6c3eece8dc6f1618..5032cf811940983e3b8c73b4064f7796aa3d06d6 100644 --- a/config/adc_rosnav/amcl_no_tf.yaml +++ b/config/adc_rosnav/amcl_no_tf.yaml @@ -38,9 +38,9 @@ laser_likelihood_max_dist: 2.0 laser_model_type: 'likelihood_field' # odom parameters odom_model_type: "diff" -odom_alpha1: 10.0 -odom_alpha2: 10.0 +odom_alpha1: 1.0 +odom_alpha2: 1.0 odom_alpha3: 0.2 -odom_alpha4: 10.0 +odom_alpha4: 1.0 odom_alpha5: 0.2 tf_broadcast: false diff --git a/config/adc_rosnav/costmap/local_params.yaml b/config/adc_rosnav/costmap/local_params.yaml index 492193e50bfdf124e9e55ae1c0f1599c1ff14d6e..a6e76ee1c565d43b8db25db0cb659c8a3e003b30 100644 --- a/config/adc_rosnav/costmap/local_params.yaml +++ b/config/adc_rosnav/costmap/local_params.yaml @@ -3,8 +3,8 @@ global_frame: adc_car/odom update_frequency: 5.0 publish_frequency: 2.0 rolling_window: true -width: 5.0 -height: 5.0 +width: 3.0 +height: 3.0 resolution: 0.05 origin_x: 0.0 origin_y: 0.0 diff --git a/config/adc_rosnav/global_planner/iri_opendrive_params.yaml b/config/adc_rosnav/global_planner/iri_opendrive_params.yaml index 45e7c0e11bbb974e4e007f8c1aa95f133b3227e5..8201302a90f4559f7ca05834d4e583cc4c89d0e9 100644 --- a/config/adc_rosnav/global_planner/iri_opendrive_params.yaml +++ b/config/adc_rosnav/global_planner/iri_opendrive_params.yaml @@ -1,9 +1,9 @@ base_global_planner: "iri_opendrive_global_planner/OpendriveGlobalPlanner" OpendriveGlobalPlanner: opendrive_frame: "opendrive" - angle_tol: 0.5 + angle_tol: 1.5707 dist_tol: 0.3 - multi_hyp: True + multi_hyp: False resolution: 0.01 scale_factor: 10.0 min_road_length: 0.01