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

teb_local_planner not work

asked 2016-03-30 21:58:22 -0600

SHI.ZP gravatar image

updated 2016-04-07 23:47:19 -0600

Hi,

My pc can run movebase (navfn + dwa) ,(voronoi + dwa)

But when comes to the (navfn + teb_local_planner) on the offline rviz simulation

the behavior of my virtual turtle bot is quite odd,

But I guess the root cause is lack of computational power:

The longest control cycle can reach about 300s with teb O_o

But with dwa_local_planner, my control frequency can reach 100Hz on the same static map.

And I am following the [teb tutorial]...(http://wiki.ros.org/teb_local_planner/Tutorials/Configure%20and%20run%20Robot%20Navigation)

Anyone can help?

Thanks!

Update #1 in 8th April 2016

costmap_common_params.yam:

obstacle_range: 2.5
raytrace_range: 3.0
footprint: [[0.215, 0.215], [-0.215, 0.215], [-0.215, -0.215], [0.215, -0.215]]
footprint_inflation: 0.6
# robot_radius: 0.24
inflation_radius: 0.90
max_obstacle_height: 0.6
min_obstacle_height: 0.0
observation_sources: scan
scan: {data_type: LaserScan, topic: /scan, marking: true, clearing: true, expected_update_rate: 0}

local_costmap_params.yaml

   local_costmap:
   global_frame: /odom
   robot_base_frame: /base_link
   update_frequency: 5.0
   publish_frequency: 0.2
   static_map: true
   rolling_window: false
   width: 6.0
   height: 6.0
   resolution: 0.08
   transform_tolerance: 1.0

global_costmap_params.yaml

global_costmap:
   global_frame: /map
   robot_base_frame: /base_footprint
   update_frequency: 1.0
   publish_frequency: 1.0
   static_map: true
   rolling_window: false
   resolution: 0.08
   transform_tolerance: 1.0
   map_type: costmap

feb_local_planner_params.yaml

TebLocalPlannerROS:

 odom_topic: odom
 map_frame: /map # This parameter will be overridden by local_costmap/global_frame 

 # Trajectory

 teb_autosize: True
 dt_ref: 0.3
 dt_hysteresis: 0.1
 global_plan_overwrite_orientation: True

 # Robot

 max_vel_x: 0.4
 max_vel_x_backwards: 0.2
 max_vel_theta: 0.3
 acc_lim_x: 0.5
 acc_lim_theta: 0.5

 # GoalTolerance

 xy_goal_tolerance: 0.2
 yaw_goal_tolerance: 0.1
 free_goal_vel: False

 # Obstacles

 min_obstacle_dist: 0.5
 costmap_emergency_stop_dist: 0.3
 include_costmap_obstacles: True
 costmap_obstacles_front_only: True
 obstacle_poses_affected: 10
 line_obstacle_poses_affected: 25
 polygon_obstacle_poses_affected: 25

 # Optimization

 no_inner_iterations: 5
 no_outer_iterations: 4
 optimization_activate: True
 optimization_verbose: False
 penalty_scale: 0.1
 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_optimaltime: 1
 weight_point_obstacle: 50
 weight_line_obstacle: 50
 weight_poly_obstacle: 50

 # Parallel Planning in distinctive Topologies

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

map.yaml

image: map_corner_v3.pgm
resolution: 0.025000
#or resolution: 0.01000
origin: [-11.000000, -10.000000, 0.000000]
#or origin: [-5.000000, -5.000000, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196
edit retag flag offensive close merge delete

Comments

Hi, a control cycle with 300s is way too much ;-) Obviously, there must be some issue. Even on our 7-10 years old computers, the planner works within a 10Hz control cycle (for a limited, but reasonable local costmap size).

croesmann gravatar image croesmann  ( 2016-04-01 04:22:58 -0600 )edit

Can you please provide me with more information about your setup and configuration? Did you try the first tutorial: Setup and test Optimization How is your performance here?

croesmann gravatar image croesmann  ( 2016-04-01 04:24:05 -0600 )edit

Hi Croesmann, I tried the 1st tutorial, and my performance looks ok with all default settings. and this vedio shows the problem I asked. also recorded with all default settings.

SHI.ZP gravatar image SHI.ZP  ( 2016-04-05 21:43:28 -0600 )edit

thank you for posting the video. The behavior looks indeed quite ugly. Could you please provide me with your navigation configuration files (you told that you are using the default teb paramaters, but what's about costmap parameters, move_base parameters, ...)?

croesmann gravatar image croesmann  ( 2016-04-07 02:56:32 -0600 )edit

Hi Croesmann, this video shows the comparison among 3 sets of different navigation settings on my PC .And I updated the post with my nav cfgs used in the previous video.Thanks for your help.

SHI.ZP gravatar image SHI.ZP  ( 2016-04-07 23:48:23 -0600 )edit

1 Answer

Sort by ยป oldest newest most voted
3

answered 2016-04-08 08:54:24 -0600

croesmann gravatar image

Thank you for updating your question with content of your parameter files and for posting the video.

After investigating your parameters, I think that your local costmap configuration causes the high computation time. Your local costmap consist of a static map (static map: true) which is not recommended. In that case the width and height parameters are ignored, leading to a local costmap representing your whole environment. The teb_local_planner treats each occupied costmap cell as single point obstacle (if no costmap conversion plugin is activated, which is the default). With that in mind, it is not surprising that the performance is poor, since each obstacle causes a huge amount of distance calculations during optimization.

My current local costmap configuration contains the following parameters:

static_map: false
rolling_window: true
width: 5.5
height: 5.5
resolution: 0.1

I hope this resolves your issue with huge computation times. If you still have problems with your performance afterwards, there are other parameters that influence the computational resources (number of optimization iterations, area/distance behind the robot that should be checked for obstacles, temporal trajectory resolution, ...). Please let me know in that case. Some hints are also given in the tutorials.

PS: A local costmap resolution of 0.025 is not feasible for the planner on most computers, but it is also not necessary. I am running the planner with a resolution of 0.1 (similar to your 3rd example in the video).

PPS: You might try out the new version 0.3 of the planner. Until it is available in the official repos, you can checkout the master branch of the github repository. Parameters and Tutorials are already updated to be compliant with version 0.3 (some minor parameter changes and a new tutorial).

edit flag offensive delete link more

Comments

With the modification of local costmap yaml file, now my virtual turtle bot is much swifter, Thank you! Crosemann.

SHI.ZP gravatar image SHI.ZP  ( 2016-04-10 20:08:58 -0600 )edit

Question Tools

3 followers

Stats

Asked: 2016-03-30 21:58:22 -0600

Seen: 2,482 times

Last updated: Apr 08 '16