teb_local_planner do not generate local path when there is a Obstacles
my robot model is a car-like mode and using ubuntu 14.04+ros indigo. The global planner is based on a "waypoint",which mean the global path will not regenerated even there is a Obstacles.
So, I would like to use Local_planner to avoid Obstacles (local_planner generated a new local path to avoid obstacles and then back to global path ).
when i use teb_local_planner, the teb_local_planner's global path always follow with Global_planner's path .Since my Global_planner's path is fixed, the teb_local_planner's global path also becomed fixed, and the teb_local_planner's local path never can get a new path which can avoid obstacles.
please see the below screenshot. the Blue Line is teb_local_planner's global path (this path is same with my Global path which generated by "waypoints"), while the Red path is teb_local_planner's local path( this path is generated dynamicly). When the obstacles appear after "waypoints" generated global path, the teb_local_planner's will find the obstacles and go backward and upwards but never can pass the obstacles.
How can i just use teb_local_planner to avoid obstacles. In DWA and Traj local planner,there are params which named "path_distance_bias" and "goal_distance_bias" to change the weight of global path, But i did not find the similar params in teb_local_planner.
teb_params.yaml:
TebLocalPlannerROS:
odom_topic: /GTR/odom
# Trajectory
teb_autosize: True
dt_ref: 0.3
dt_hysteresis: 0.1
min_samples: 3
global_plan_overwrite_orientation: True
global_plan_viapoint_sep: -0.1
allow_init_with_backwards_motion: True
max_global_plan_lookahead_dist: 8.0 #default=3
feasibility_check_no_poses: 2
publish_feedback: true #default false using teb_plot.py
# Robot
max_vel_x: 0.5
max_vel_x_backwards: 0.5
max_vel_y: 0.0
max_vel_theta: 1.6
acc_lim_x: 0.2
acc_lim_theta: 0.5
# ****** Carlike robot parameters ****** min_turning_radius: 0.1
wheelbase: 1.5
cmd_angle_instead_rotvel: true # **********************
footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
type: "line"
line_start: [-2.4, 0.0] # for type "line"
line_end: [2.4, 0.0] # for type "line"
# GoalTolerance
xy_goal_tolerance: 1
yaw_goal_tolerance: 3
free_goal_vel: False
# Obstacles
min_obstacle_dist: 3
include_costmap_obstacles: true
costmap_obstacles_behind_robot_dist: 3.0
obstacle_poses_affected: 30
inflation_dist: 0
obstacle_association_force_inclusion_factor: 1.5
obstacle_association_cutoff_factor: 5
costmap_converter_plugin: "costmap_converter::CostmapToPolygonsDBSConcaveHull"
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.1
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: 1
weight_kinematics_turning_radius: 1
weight_optimaltime: 1
weight_obstacle: 50
weight_viapoint: 1.0
weight_inflation: 0.1
weight_dynamic_obstacle: 10
# Homotopy Class Planner
enable_homotopy_class_planning: True
enable_multithreading: True
simple_exploration: False
max_number_classes: 4
selection_cost_hysteresis: 1.0
selection_obst_cost_scale: 1.0
selection_viapoint_cost_scale: 1.0
selection_alternative_time_cost: False
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: true