Package Summary

The cob_3d_mapping_geometry_map_v2 package provides a node for processing and visualization of 3D environment data.

Overview

The node subscribes to messages of type PlaneScene, handling shapes of types polygon. The shapes are transformed to a common target frame by /tf. Reoccuring shapes are associated and merged accordingly. For every input message the resulting aggregated geometric map is published and ready for visualization in rviz.

cob_3d_mapping_geometry_map_v2

Subscribed Topics

scene (cob_3d_mapping_msgs/PlaneScene)
  • Input topic with geometric scene including shapes.
color_image (sensor_msgs/Image)
  • optional: Input topic for environment with images for more details.
depth_image (sensor_msgs/Image)
  • optional: Input topic for environment with images for more details.
/tf (/tf)
  • Transformations, connecting target frames
camera_info (sensor_msgs/CameraInfo)
  • Description of camera configuration for projection matrix.

Published Topics

/geometry_map/map_array (cob_3d_mapping_msgs/ShapeArray)
  • Array with geometric shapes
scan (sensor_msgs/LaserScan)
  • Virtual laser scan of the geometry map (excluding floor and ceiling) which can be used for obstacle avoidance.
cartons (cob_object_detection_msgs/DetectionArray)
  • Annotated objects of the geometry map.

Services

reset (std_srvs/Trigger)
  • Clears the geometry map.

Parameters

~target_frame (string)
  • Target frame the map is supposed to be transformed to. Make sure, that the corresponding transformation is available as /tf topic in the input data.
~floor_height (float, default: 0.0)
  • Expected height of the floor. Used for classifier to distinct floor and non-floor geometries.
~image_callback (bool)
  • Flag to enable texture mode.

Usage

The geometry map node can be started using the corresponding launch file:

roslaunch cob_3d_mapping_geometry_map_v2 start.launch

Software Architecture

"types"

In "types" data containers are implemented which holds data representing map. They can be divided in objects of the map and the map container (and it derivates) itself.

Containers:

  • "GlobalContext" is the map itself (containing "Context")

  • "Context" is a scene or snapshot of the (geometrical) objects
  • "Context2D" is projected "Context" on to a plane for intersection/visbility tests

Objects:

  • "Object" is most abstract representation
  • "Object3D" is an object in space (6 DoF pose)
  • "ObjectVolume" is an object in space with 3 extensions

  • "Plane" is an "ObjectVolume" with outlines and holes (polygons)

  • "Image" is an "Object3D" and contains a texture captured at certain pose

Classifiers:

  • "Classifier" is an abstract class which can classify objects
  • "Classifier_Floor" detects planes belonging to the floor
  • "Classifier_Carton" detects cartons in the geometrical map

"visualization"

In "visualization" methods are implemented which allows to convert the map objects into a representation which can be used to visualize the maps. The default implementation are rviz markers which can be used in rviz from ROS.

Wiki: cob_3d_mapping_geometry_map_v2 (last edited 2018-01-24 11:54:07 by josh)