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

Point clouds not generating obstacles in costmap

asked 2016-07-10 19:15:10 -0500

uwleahcim gravatar image

updated 2016-07-11 04:47:39 -0500

I'm having issues trying to generate obstacles for obstacles avoid via the navigation stack. I'm using point cloud sensors

in my costmap_common_params.yaml

observation_sources: point_cloud_sensor

point_cloud_sensor: 
  data_type: PointCloud2
  topic: /points2
  marking: true
  clearing: true
  min_obstacle_height: 0.0
  max_obstacle_height: 2.5
  sensor_frame: depth_left_optical

For local_costmap_params.yaml i have the obstacle plugins

  plugins:
    - {name: obstacle_layer,   type: "costmap_2d::ObstacleLayer"}
    - {name: inflation_layer,  type: "costmap_2d::InflationLayer"}

I once got something to generate in local costmap, but ever since I haven't been able to get any obstacles from my point clouds sources. Any ideas why?

costmap_common_params.yaml

#---standard pioneer footprint---
#---(in meters)---
robot_radius: 0.55

transform_tolerance: 0.2
map_type: costmap

obstacle_layer:
 enabled: true
 obstacle_range: 3.0
 raytrace_range: 5.0
 max_obstacle_height:    20.0            # 2.0 m set to higher than flight height
 min_obstacle_height:    -20.0            # set just below flight height
 inflation_radius: 0.7
 track_unknown_space: true
 combination_method: 1


observation_sources: laser_scan_sensor point_cloud_sensorA point_cloud_sensorB point_cloud_sensorC point_cloud_sensorD
laser_scan_sensor: {data_type: LaserScan, topic: '/scan', marking: true, clearing: true}
point_cloud_sensorA: {data_type: PointCloud2, topic: '/guidance/front/points2', marking: true, clearing: true}
point_cloud_sensorB: {data_type: PointCloud2, topic: '/guidance/right/points2', marking: true, clearing: true}
point_cloud_sensorC: {data_type: PointCloud2, topic: '/guidance/back/points2', marking: true, clearing: true}
point_cloud_sensorD: {data_type: PointCloud2, topic: '/guidance/left/points2', marking: true, clearing: true}

# observation_sources: laser_scan_sensor point_cloud_sensor
# laser_scan_sensor: {data_type: LaserScan, topic: scan, marking: true, clearing: true}


inflation_layer:
  enabled:              true
  cost_scaling_factor:  10.0  # exponential rate at which the obstacle cost drops off (default: 10)
  inflation_radius:     0.7  # max. distance from an obstacle at which costs are incurred for planning paths.

#static_layer:
#  enabled:              true
#  map_topic:            "/map"

global_costmap_params.yaml

global_costmap:
  global_frame: /map
  robot_base_frame: /base_link
  update_frequency: 5.0
  publish_frequency: 2.0
  static_map: true

  transform_tolerance: 0.5
  plugins:
    - {name: static_layer,            type: "costmap_2d::StaticLayer"}
    - {name: obstacle_layer,          type: "costmap_2d::ObstacleLayer"}
    - {name: inflation_layer,         type: "costmap_2d::InflationLayer"}

local_costmap_params.yaml

local_costmap:
  global_frame: /odom
  robot_base_frame: /base_link
  update_frequency: 10.0
  publish_frequency: 10.0
  static_map: false
  rolling_window: true
  width: 8.0
  height: 8.0
  resolution: 0.1
  transform_tolerance: 0.5

  plugins:
   - {name: static_layer,        type: "costmap_2d::StaticLayer"}
   - {name: obstacle_layer,      type: "costmap_2d::ObstacleLayer"}
   - {name: inflation_layer,     type: "costmap_2d::InflationLayer"}

base_ local_planner_params.yaml

TebLocalPlannerROS:

 # 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: 4

 # Robot

 max_vel_x: 10.0
 max_vel_x_backwards: 4.0
 max_vel_y: 10.0
 max_vel_theta: 1.0
 acc_lim_x: 4.0
 acc_lim_y: 4.0
 acc_lim_theta: 1.0
 min_turning_radius: 0.0
 footprint_model: "circular"   
# types: "point", "circular", "two_circles", "line", "polygon"
   radius: 0.6 # for type "circular"
#   line_start: [-0.3, 0.0] # for type "line"
#   line_end: [0.3, 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.25, -0.05], [0.18, -0.05], [0.18, -0.18], [-0.19, -0.18], [-0.25, 0], [-0.19, 0.18], [0.18, 0.18], [0.18, 0.05], [0.25, 0.05] ] # for type "polygon"

 # GoalTolerance

 xy_goal_tolerance: 0.2
 yaw_goal_tolerance: 0.1
 free_goal_vel: False

 # Obstacles

 min_obstacle_dist: 0.6
 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 ...
(more)
edit retag flag offensive close merge delete

Comments

please provide the full configuration files.

mgruhler gravatar image mgruhler  ( 2016-07-11 01:19:53 -0500 )edit

I had a similar problem before because my height range was outside of the scan height. Are you sure your scan height is between 0 and 2.5 meters?

Mehdi. gravatar image Mehdi.  ( 2016-07-11 03:49:22 -0500 )edit

Well my sensor are position at -0.09 from the base_link frame on the z-axix. Thus they start out literally below the z=0 plane. I tried using negative numbers, but it didn't really fix it. I'm going to post my configuration files.

uwleahcim gravatar image uwleahcim  ( 2016-07-11 04:32:01 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2016-07-12 20:36:07 -0500

uwleahcim gravatar image

updated 2016-07-12 20:37:29 -0500

Someone finally pointed out that my observation_sources were not in the right namespace. The correct yaml format is the following. You have to make sure the observation_sources are under the obstacle_layer namespace like the below.

obstacle_layer:  # I was missing this line
  observation_sources: sensorA sensorB sensorC
  sensorA: {}
  sensorB: {}
  sensorC: {}
edit flag offensive delete link more

Comments

on top of that, is worth noticing that obstacler_layer is the name given to the plugin

glm gravatar image glm  ( 2019-09-19 09:46:58 -0500 )edit

We got the similar issue, were wondering if we should set clearing: false, in order to generate obstacle on costmap by a bumper sensor.

lukelu gravatar image lukelu  ( 2020-10-05 21:31:10 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2016-07-10 19:15:10 -0500

Seen: 2,564 times

Last updated: Jul 12 '16