ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

click to hide/show revision 1
initial version
acc_lim_x: 0.15
acc_lim_theta: 0.05

I think your acceleration limits, especially the theta acceleration, are too low. I have found that if i set the theta acceleration limit very low, TEB will try to reverse more often than just rotate in place. This makes sense intuitively because the system will have to spend more time rotating then reversing. Also try upping your max_vel_theta limit.

By allowing the robot to rotate more freely you should find that it will stop trying to back up as much. You should also be able to relax the weight_kinematics_forward_drive to allow for reverse movements that are sometimes necessary.

Also, you have a whole bunch of footprint types listed. You should only have two lines, the footprint_model type and its corresponding option. For example if you want to use a polygon, have:

footprint:
    type: "polygon"
    vertices: [[1.1,0.4],[-0.3,0.4],[-0.3,-0.4],[1.1,-0.4]]

Here is my base_local_planner_params.yaml file for TEB configuration for a 3 wheeled differential robot that works ok:

TebLocalPlannerROS:

odom_topic: odom
map_frame: /odom

# Trajectory

teb_autosize: True
dt_ref: 0.4
dt_hysteresis: 0.1
global_plan_overwrite_orientation: True
# This is so we stick to the global plan and don't make s's 
max_global_plan_lookahead_dist: 2.0
feasibility_check_no_poses: 5
# not sure what this does
global_plan_viapoint_sep: .5

# Robot

max_vel_x: 0.35
max_vel_x_backwards: 0.2
max_vel_theta: 0.7
acc_lim_x: 0.5
# If this is low, we overshoot on a rotate
acc_lim_theta: 0.5
min_turning_radius: 0.0
footprint_model: 
   type: "polygon"
   vertices: [
       [ 0.45, 0.375],
       [ -0.45, 0.375],
       [ -0.45, -0.375],
       [ 0.45, -0.375],
   ]

# GoalTolerance

xy_goal_tolerance: 0.3
yaw_goal_tolerance: 0.2
free_goal_vel: False

# Obstacles

min_obstacle_dist: 0.01
inflation_dist: 0.2
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 1.0
obstacle_poses_affected: 30
costmap_converter_plugin: ""
costmap_converter_spin_thread: True
costmap_converter_rate: 5

# Optimization

no_inner_iterations: 5
no_outer_iterations: 4
optimization_activate: True
optimization_verbose: False
penalty_epsilon: 0.04
weight_max_vel_x: 2
weight_max_vel_theta: 1
weight_acc_lim_x: 1
weight_acc_lim_theta: 1
weight_kinematics_nh: 1000
weight_kinematics_forward_drive: 150
weight_kinematics_turning_radius: 1
weight_optimaltime: 1
weight_obstacle: 50
weight_dynamic_obstacle: 10 
selection_alternative_time_cost: False
weight_viapoint: 100


# Homotopy Class Planner

enable_homotopy_class_planning: True
enable_multithreading: True
simple_exploration: False
max_number_classes: 4
roadmap_graph_no_samples: 15
roadmap_graph_area_width: 5
h_signature_prescaler: 0.5
h_signature_threshold: 0.1
obstacle_keypoint_offset: 0.1
obstacle_heading_threshold: 0.45
visualize_hc_graph: False