Only released in EOL distros:  

Overview

NOTE: This package is currently unreleased and contains experimental code. The documentation below describes the current version in the arm_navigation_metrics branch of motion_planning_common, which might be released in E-turtle.

collider provides a collision map for tabletop manipulation. Various sources of input data (e.g. laser and textured stereo) are fused and integrated into an octomap with raycasting in 3D. This enables a dynamically updated collision map for manipulation and serves as a drop-in replacement for collision_map. collider supersedes collision_octomap.

ROS API

ROS Parameters

Parameters

~resolution (double, default: 0.1)
  • The smallest resolution of the internal octree in meters. This directly influences the update speed.
~max_range (double, default: -1.0)
  • The maximum beam length that will be inserted into the octree. If a point is further than this distance, freespace will be cleared only up to the distance. The default of -1.0 means the full beam length. This directly influences the update speed.
~pruning_period (int, default: 5)
  • The internal octree will be pruned after every x-th data insertion, where x is the pruning period. There is a tradeoff between pruning too often and not often enough that needs to be found.
cloud_sources (XmlRpcValue, default: none)
  • The PointCloud2 data sources which will be used as inputs to collider. Details below.
sensor_model_hit (double, default: 0.7)
  • Octomap sensor model: probablity for a hit
sensor_model_max (double, default: 0.97)
  • Octomap sensor model: Maximum clamping value
sensor_model_min (double, default: 0.12)
  • Octomap sensor model: Minimum clamping value

cloud_sources parameter

An example of the cloud_sources YAML file is given below. Note that this is the same format used for the regular collision_map.

cloud_sources:
  - name: full_cloud_filtered
    frame_subsample: 1
    point_subsample: 1
    sensor_frame: laser_tilt_mount_link

Published Topics

Data Topics
collision_map_out (mapping_msgs/CollisionMap)
  • The output collision map, defined as a set of boxes with a given center point and edge lengths.
point_cloud_out (sensor_msgs/PointCloud2)
  • The output collision map in point cloud form, which is simply the center points of the collision map boxes. Used for nodes that need a point cloud input topic, but should probably be eliminated in the future.
Visualization Topics
octomap_insertion_info_array (visualization_msgs/MarkerArray)
  • Text information about the latest insertion.
occupied_cells (visualization_msgs/Marker)
  • Box markers of the current occupied cells in the octree. Useful for debugging.
free_cells (visualization_msgs/Marker)
  • Box markers of the current freespace cells in the octree. Useful for debugging - but generates and displays huge amounts of data!

Wiki: collider (last edited 2011-05-07 01:15:40 by ArminHornung)