From 48df91eedb5f15e9aa580a8217aa2ece8db5bf39 Mon Sep 17 00:00:00 2001 From: fherrero <fherrero@iri.upc.edu> Date: Mon, 15 Feb 2021 11:21:37 +0100 Subject: [PATCH] Update ackermann params yaml --- .../adc_car_move_base/local_planner/ackermann_params.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/config/adc_car_move_base/local_planner/ackermann_params.yaml b/config/adc_car_move_base/local_planner/ackermann_params.yaml index 1aa1eea..46cc01c 100644 --- a/config/adc_car_move_base/local_planner/ackermann_params.yaml +++ b/config/adc_car_move_base/local_planner/ackermann_params.yaml @@ -23,7 +23,7 @@ AckermannPlannerROS: steer_angle_samples: 21 prune_plan: true - xy_goal_tolerance: 0.25 + xy_goal_tolerance: 0.1 yaw_goal_tolerance: 0.5 trans_stopped_vel: 0.1 rot_stopped_vel: 0.1 @@ -31,7 +31,7 @@ AckermannPlannerROS: restore_defaults: false max_trans_vel: 1.0 - min_trans_vel: 0.0 + min_trans_vel: -1.0 max_trans_acc: 0.2 max_steer_angle: 0.4 min_steer_angle: -0.4 @@ -42,7 +42,7 @@ AckermannPlannerROS: wheel_distance: 0.216 wheel_radius: 0.05 - split_ignore_lenght: 0.1 + split_ignore_length: 0.1 cmd_vel_avg: 1 odom_avg: 1 -- GitLab