Teb local planner gets stuck at local minimum
I have written a full-coverage global path planner plug-in, which returns a "raster" pattern shown below. To follow this path, I am using teb_local_planner's (TEB) path following ability. When i first applied TEB, the local planner would find a local minimum at the first cut-back (turning section in the back and forth pattern) it came to and would simply stay there and oscillate. To solve this, i reduced the prune path parameter (which i found in a header file) from 1m to 0.1m. This solved the issue very well. Also, i had to be sure that TEB would never request a new global plan so i edited out all re-planning requests.
My current issue is that sometimes segments of the global plan requires the robot to go down a dead end path segment, turn, and return exactly how it came. In this scenario TEB always finds a local minimum at this path end and gets stuck. I have to bump the robot forward to get out of this situation.
Does anyone know how i can resolve this? Perhaps removing way-points within the local region (not sure how/where to do this)? or some new weight parameter? Thank you in advance.
My system is ROS Kinetic and Ubuntu 16.04.
Edit: here is my teb_local_planner configuration.
TebLocalPlannerROS:
#################################
# Trajectory
teb_autosize: True
dt_ref: 0.3
dt_hysteresis: 0.1
global_plan_overwrite_orientation: False # I supply the desired orientation
global_plan_viapoint_sep: 0.01 # there are 20 between each green point shown in rviz
allow_init_with_backwards_motion: False
max_global_plan_lookahead_dist: 0.7 # If too high then it cuts corners even with via_point weight high??
force_reinit_new_goal_dist: 0.6 # not sure about this one but lower seemed better...?
feasibility_check_no_poses: 0 # never replan no matter what. even if completely stuck (TEB replans when desperate even with planner_frequency=0 for some reason)
via_points_ordered: True # path following. false increases oscillation around the path
#################################
# Robot # Note: the real robot never recovers from a oscillation. However, the simulation often does.
max_vel_x: 0.5 # these are simulation values. for the real robot they are about 3m/s
max_vel_x_backwards: 0.5
max_vel_y: 0.5
max_vel_theta: 5
acc_lim_x: 10.0
acc_lim_y: 10
acc_lim_theta: 9
min_turning_radius: 0.0
#################################
# Note: I added these parameters to help on the real robot (not needed in simulation)
min_vel_x: 0.0
min_vel_y: 0.0
min_vel_theta: 0
min_vel_x_backwards: 0.0
footprint_model:
type: "point"
#################################
# GoalTolerance
xy_goal_tolerance: 0.1
yaw_goal_tolerance: 0.1
free_goal_vel: True
#################################
# Obstacles
min_obstacle_dist: 0.5 # This value must also include our robot radius, since footprint_model is set to "point".
include_costmap_obstacles: True
costmap_obstacles_behind_robot_dist: 0.5
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.1
weight_max_vel_x: 480 # these are high to encourage the real robot not to go painfully slow
weight_max_vel_y: 480
weight_max_vel_theta: 520
weight_acc_lim_x: 250
weight_acc_lim_y: 250
weight_acc_lim_theta: 280
weight_kinematics_nh: 5400 # My robot is holonomic but i want to prefer staying tangent to the path
weight_kinematics_forward_drive: 550 # I definitely prefer going forward
weight_optimaltime: 500 # I dont particularly care how long the path takes within reason but higher ...
Have you tried the via-point feature with strict point ordering enabled? Refer to the planner tutorials (the strict order parameter ist not yet mentioned there). Note, a short horizon ist not recommended if additional obstacle avoidance is needed. Please let me know if it still fails.
By the way, you can disable frequent requests for new global plans by setting parameter planner_frequency to 0 (move_base parameter)
Thank you. I attached my configuration file with comments for you so hopefully my goals/reasoning are clear. is the strict point ordering you mentioned via_points_ordered? If so, currently it does not solve the issue. I would like a longer horizon, but that seems to find local minim worse..
Hi, Stephen, I am also learning the coverage path planning. What is the algorithm you have implemented? Online planning or not? If ok, would you like to share your code? Thank you!
I have described my process here: http://answers.ros.org/question/21261... . The planner is not online in the sense that it updates the plan continuously but it does run on the ros system as a standard ros planner besides that.
I apologize but I can not make my code public at this time because it is for a private company.
Hi, Thank you very much for your reply. For me, online planning is planning with unknown map. So the coverage path planning is running with a mapping process. off-line planning is planning with a known map. Can your algorithm work with unknown map? thanks!
My current algorithm requires a complete 2d map of the desired environment to plan the path. This map can be found using the gmapping node, and must be obtained prior to running the robot. However, real time replanning could be added by keeping track of the completed coverage, and rerunning the ...