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

Why does the Global planner in connection with amcl not create a new plan when a new obstacle is added in gazebo?

asked 2020-06-20 07:53:57 -0500

Donlouigi91 gravatar image

updated 2020-06-20 08:05:09 -0500

Hello,

i use ros kinetic and the husky robot (version 0.3.6). I have created a map with the GlobalPlaner, teb_local_planer and gmapping. Then I used the map together with amcl (1.14.7) and without gmapping. I can set a goal in rviz and the robot goes there without problems. When I add an obstacle in gazebo, the laser detects it, but the GlobalPlanner does not generate a new plan and the Husky drives against the obstacle. I could see that the new obstacle did not appear in the global costmap. As far as I understand the global costmap uses the created map and there the new obstacle does not exist, so it is not shown in the global costmap. I thought amcl automatically takes care to avoid such obstacles. I don't know where my mistake is...

Can someone explain to me why GlobalPlanner does not create a new path? If you need more information please let me know.

Many thanks in advance!

costmap_common:

robot_base_frame: base_link
obstacle_range: 2.5
raytrace_range: 3.0
footprint: [[-0.24, -0.22], [-0.24, 0.22], [0.24, 0.22], [0.24, -0.22]]
footprint_padding: 0.01
transform_tolerance: 0.3
recovery_behavior_enabled: false
resolution: 0.1

obstacles_laser:
  observation_sources: scan
  scan:
    data_type: LaserScan
    topic: scan
    marking: true
    clearing: true
    inf_is_valid: true

inflation:
  cost_scaling_factor: 2.5
  inflation_radius: 0.3

static:
  map_topic: /map
  subscribe_to_updates: true

local_costmap:

local_costmap:
  global_frame: /odom
  rolling_window: true
  static_map: false
  width: 4
  height: 4
  update_frequency: 3.0
  publish_frequency: 0.0  
  plugins:
  - {name: obstacles_laser,           type: "costmap_2d::ObstacleLayer"}
  - {name: inflation,                 type: "costmap_2d::InflationLayer"}

global_costmap:

global_costmap:
  global_frame: /map
  static_map: true
  rolling_window: false
  update_frequency: 1.0
  publish_frequency: 0.1  
  plugins:
  - {name: static,                  type: "costmap_2d::StaticLayer"}
  - {name: inflation,               type: "costmap_2d::InflationLayer"}

teb_local_planner:

TebLocalPlannerROS:

 odom_topic: /odometry/filtered
 map_frame: /map

 # Trajectory

 teb_autosize: True
 dt_ref: 0.3
 dt_hysteresis: 0.1
 global_plan_overwrite_orientation: True
 max_global_plan_lookahead_dist: 3.0
 feasibility_check_no_poses: 0

 # Robot

 max_vel_x: 0.4
 max_vel_x_backwards: 0.2
 max_vel_theta: 0.3
 acc_lim_x: 1.0
 acc_lim_theta: 0.2
 min_turning_radius: 0.0
 footprint_model: # types: "point", "circular", "two_circles", "line", "polygon"
   type: "polygon"
   vertices: [[-0.24, -0.22], [-0.24, 0.22], [0.24, 0.22], [0.24, -0.22]] # for type "polygon"

 # GoalTolerance

 xy_goal_tolerance: 0.2
 yaw_goal_tolerance: 0.1
 free_goal_vel: False

 # Obstacles

 min_obstacle_dist: 0.1
 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.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: 50
 weight_kinematics_turning_radius: 1
 weight_optimaltime: 1
 weight_obstacle: 50
 weight_dynamic_obstacle: 10 # not in use yet

 # Homotopy Class Planner

 enable_homotopy_class_planning: False
 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

amcl_launch file:

<?xml version="1.0"?>
<launch>
     <arg name="use_map_topic" default="true"/>
     <node pkg="amcl" type="amcl" name="amcl" output="screen">
        <param name="laser_max_range" value="10" />
        <param name="use_map_topic" value="$(arg use_map_topic)"/>
        <param name="base_frame_id" value="base_link"/> 
        <param name="gui_publish_rate" value="5.0"/> <
        <param name="kld_err" value ...
(more)
edit retag flag offensive close merge delete

Comments

I haven't looked at the rest of your question, but:

I thought amcl automatically takes care to avoid such obstacles

AMCL is a localisation algorithm/component. It does not directly affect or take part in path planning.

gvdhoorn gravatar image gvdhoorn  ( 2020-06-20 07:57:29 -0500 )edit

Yes you are right, but I am not sure if amcl has influence on the GlobalPlanner.

Donlouigi91 gravatar image Donlouigi91  ( 2020-06-20 08:05:49 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-06-21 09:25:41 -0500

Dragonslayer gravatar image

updated 2020-06-21 09:34:45 -0500

Obstacle avoidance for variable obstacles is done by the local planner in the local costmap scope. What isnt mapped isnt taken into consideration by the global costmap and planner. It is also not ment to replan as there is no change expected. You can think of the concept analog to a car with navigation system. The navigation system is the global_planner, plans once, and gives rough directions to the driver. The driver is analog to the local_planner who takes care of not crashing into other cars, stay in the lane, etc.

I dont see where you actually upload the costap yaml files to the parameter server in the launchfiles. Also starting the map server before move_base might be better (change position in launchfile). A rosparam dump might be usefull. With all the yaml files and namespaces used to launch the files, quickly something can get messed up. And it seems everybody does it differently. I would expect move_base.launch to be the problem (usually its there where the yamls get uploaded and planners chosen). The discribed behaviour suggest a local problem with either costmap or planner. Most likely the obstacle_layer not marking. Try visualizing the local_costmap and pathplans in rviz. This should give a quick understanding of whats going wrong.

edit flag offensive delete link more

Comments

Hi, thanks for your comment, I got it working. I just had to add the obstacle plugin to the global costmap. global_costmap:

  global_frame: /map
  static_map: true
  rolling_window: false
  update_frequency: 1.0
  publish_frequency: 0.1  
  plugins:
  - {name: static,                  type: "costmap_2d::StaticLayer"}
  - {name: inflation,               type: "costmap_2d::InflationLayer"}
  - {name: obstacles_laser,           type: "costmap_2d::ObstacleLayer"}

Now the GlobalPlanner plans a new path when a new obstacle appears.

Donlouigi91 gravatar image Donlouigi91  ( 2020-06-21 10:23:38 -0500 )edit

Nice. If you are not doing something experimental I would still consider handling variable obstacles in the local scope. Due to its smaller costmap size and more specialized planners you can safe a lot of computational resources and get better results (due to higher frequency for example). You might consider marking. Have fun.

Dragonslayer gravatar image Dragonslayer  ( 2020-06-21 11:37:38 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2020-06-20 07:53:57 -0500

Seen: 361 times

Last updated: Jun 21 '20