rst-tu-dortmund / teb_local_planner

An optimal trajectory planner considering distinctive topologies for mobile robots based on Timed-Elastic-Bands (ROS Package)
http://wiki.ros.org/teb_local_planner
BSD 3-Clause "New" or "Revised" License
1.05k stars 549 forks source link

dt_ref setting problem #194

Open Longyouspongecake opened 4 years ago

Longyouspongecake commented 4 years ago

Here are two dt_ref related issues.(Sorry this is my first time using this feature, and my native language is not English, thank you all.) First of all, when dt_ref is 0.02, the vehicle released by teb cannot move forward normally and will be stuck in place. If it is moved by other path tracking algorithms (such as mpc), a long reverse trajectory will appear.

2020-03-03 10-56-48屏幕截图

Here are the parameters where this happens:

TebLocalPlannerROS:

odom_topic: /odom #/odometry/filtered

Trajectory

teb_autosize: True dt_ref: 0.02 dt_hysteresis: 0.01 global_plan_overwrite_orientation: True allow_init_with_backwards_motion: False max_global_plan_lookahead_dist: 4 feasibility_check_no_poses: 0

global_plan_viapoint_sep: 1

Robot

max_vel_x: 5 max_vel_x_backwards: 0.0000000001 #0.2 max_vel_y: 0 max_vel_theta: 3 #0.3 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega) acc_lim_x: 30 acc_lim_y: 0 acc_lim_theta: 20

** Carlike robot parameters ****

min_turning_radius: 0.73 # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually) wheelbase: 0.34 # Wheelbase of our robot cmd_angle_instead_rotvel: True # stage simulator takes the angle instead of the rotvel as input (twist message)

****

footprint_model: # types: "point", "circular", "two_circles", "line", "polygon" type: "line" radius: 0.2 # for type "circular" line_start: [0.0, 0.0] # for type "line" line_end: [0.34, 0.0] # for type "line" front_offset: 0.2 # for type "two_circles" front_radius: 0.2 # for type "two_circles" rear_offset: 0.2 # for type "two_circles" rear_radius: 0.2 # for type "two_circles" vertices: [ [-0.075,-0.17], [0.415,-0.17], [0.415,0.17], [-0.075,0.17] ]# for type "polygon"

is_footprint_dynamic: True

obstacle_association_force_inclusion_factor: 5

legacy_obstacle_association: True

switching_blocking_period: 10

GoalTolerance

xy_goal_tolerance: 0.5 yaw_goal_tolerance: 3 free_goal_vel: False

Obstacles

inflation_dist: 0.5 weight_inflation: 10 min_obstacle_dist: 0.27 #0.27 # This value must also include our robot's expansion, since footprint_model is set to "line". include_costmap_obstacles: True costmap_obstacles_behind_robot_dist: 1.0 obstacle_poses_affected: 60

costmap_converter_plugin: ""

costmap_converter_spin_thread: True

costmap_converter_rate: 20

Optimization

no_inner_iterations: 5 no_outer_iterations: 4 optimization_activate: True optimization_verbose: False penalty_epsilon: 0.0000000001 #0.1 weight_max_vel_x: 10000000 weight_max_vel_theta: 1 weight_acc_lim_x: 1 weight_acc_lim_theta: 1 weight_kinematics_nh: 1000 weight_kinematics_forward_drive: 1000 weight_kinematics_turning_radius: 1 weight_optimaltime: 5 #nice!!! weight_obstacle: 1000 weight_dynamic_obstacle: 10 # not in use yet

weight_viapoint: 2

Homotopy Class Planner

enable_homotopy_class_planning: False enable_multithreading: True simple_exploration: False max_number_classes: 2 selection_cost_hysteresis: 1.0 selection_obst_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: False

force_reinit_new_goal_dist: 1

The second problem is that when dt_ref is 0.1, if the speed is set to 5m / s, the planned path will sometimes pass through obstacles, and the curve will become like a polyline.However, after a period of time, it will stretch back to the path that does not pass through the obstacle, but this period is too long.

2020-03-03 11-05-25屏幕截图

Here are the parameters where this happens:

TebLocalPlannerROS:

odom_topic: /odom #/odometry/filtered

Trajectory

teb_autosize: True dt_ref: 0.1 dt_hysteresis: 0.01 global_plan_overwrite_orientation: True allow_init_with_backwards_motion: False max_global_plan_lookahead_dist: 4 feasibility_check_no_poses: 0

global_plan_viapoint_sep: 1

Robot

max_vel_x: 5 max_vel_x_backwards: 0.0000000001 #0.2 max_vel_y: 0 max_vel_theta: 3 #0.3 # the angular velocity is also bounded by min_turning_radius in case of a carlike robot (r = v / omega) acc_lim_x: 30 acc_lim_y: 0 acc_lim_theta: 20

** Carlike robot parameters ****

min_turning_radius: 0.73 # Min turning radius of the carlike robot (compute value using a model or adjust with rqt_reconfigure manually) wheelbase: 0.34 # Wheelbase of our robot cmd_angle_instead_rotvel: True # stage simulator takes the angle instead of the rotvel as input (twist message)

****

footprint_model: # types: "point", "circular", "two_circles", "line", "polygon" type: "line" radius: 0.2 # for type "circular" line_start: [0.0, 0.0] # for type "line" line_end: [0.34, 0.0] # for type "line" front_offset: 0.2 # for type "two_circles" front_radius: 0.2 # for type "two_circles" rear_offset: 0.2 # for type "two_circles" rear_radius: 0.2 # for type "two_circles" vertices: [ [-0.075,-0.17], [0.415,-0.17], [0.415,0.17], [-0.075,0.17] ]# for type "polygon"

is_footprint_dynamic: True

obstacle_association_force_inclusion_factor: 5

legacy_obstacle_association: True

switching_blocking_period: 10

GoalTolerance

xy_goal_tolerance: 0.5 yaw_goal_tolerance: 3 free_goal_vel: False

Obstacles

inflation_dist: 0.5 weight_inflation: 10 min_obstacle_dist: 0.27 #0.27 # This value must also include our robot's expansion, since footprint_model is set to "line". include_costmap_obstacles: True costmap_obstacles_behind_robot_dist: 1.0 obstacle_poses_affected: 60

costmap_converter_plugin: ""

costmap_converter_spin_thread: True

costmap_converter_rate: 20

Optimization

no_inner_iterations: 5 no_outer_iterations: 4 optimization_activate: True optimization_verbose: False penalty_epsilon: 0.0000000001 #0.1 weight_max_vel_x: 10000000 weight_max_vel_theta: 1 weight_acc_lim_x: 1 weight_acc_lim_theta: 1 weight_kinematics_nh: 1000 weight_kinematics_forward_drive: 1000 weight_kinematics_turning_radius: 1 weight_optimaltime: 5 #nice!!! weight_obstacle: 1000 weight_dynamic_obstacle: 10 # not in use yet

weight_viapoint: 2

Homotopy Class Planner

enable_homotopy_class_planning: False enable_multithreading: True simple_exploration: False max_number_classes: 2 selection_cost_hysteresis: 1.0 selection_obst_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: False

force_reinit_new_goal_dist: 1

jjKeyLite commented 4 years ago

why enable_homotopy_class_planning:false ? If you use optimal planner,there will be only one choice, which is not reasonable if you can have more. By the way, the weights also need to be adjusted.