ROS API

The cob_3d_registration package provides a configurable node for point cloud registration. Input data is supposed to come from 3-D cameras like Microsoft Kinect.

registration_nodelet

The registration_nodelet nodelet takes in sensor_msgs/PointCloud2 messages and registers successive frames to each other. The register process can be triggered by the key_frame_detector node. Registration is activated by a trigger service.

Action Goal

trigger_mapping/goal (cob_3d_mapping_msgs/TriggerMappingActionGoal)
  • empty

Action Result

trigger_mapping/result (cob_3d_mapping_msgs/TriggerMappingActionResult)
  • empty

Action Feedback

trigger_mapping/feedback (cob_3d_mapping_msgs/TriggerMappingActionFeedback)
  • empty

Subscribed Topics

/point_cloud2 (sensor_msgs/PointCloud2)
  • The input point cloud

Published Topics

/point_cloud2_aligned (sensor_msgs/PointCloud2)
  • The aligned point cloud

Services

trigger_keyframe (cob_srvs/Trigger)
  • Triggers a map update

Parameters

~world_frame_id (string, default: /map)
  • Specifies frame id for which odometry is looked up.
~algo (string, default: icp)
  • For registration different algorithms can be used. Allowed values are: icp, icp_lm, gicp, icp_moments, icp_fpfh, icp_narf, icp_edges, rgbdslam, info, cor
~voxelsize (double, default: 0.04)
  • Sets the cubic voxelsize in meter for preprocessing. Only needed for "icp", "icp_moments" and"icp_fpfh".

Usage/Examples

roslaunch cob_3d_registration registration.launch

Trigger mapping by calling

rosrun cob_3d_mapping_point_map trigger_mapping.py <start|stop>

Wiki: cob_3d_registration (last edited 2012-10-24 11:47:32 by GeorgArbeiter)