== 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. {{{ #!clearsilver CS/NodeAPI name = registration_nodelet desc = The `registration_nodelet` nodelet takes in <> 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. goal{ 0.name=trigger_mapping/goal 0.type=cob_3d_mapping_msgs/TriggerMappingActionGoal 0.desc=empty } result{ 0.name=trigger_mapping/result 0.type=cob_3d_mapping_msgs/TriggerMappingActionResult 0.desc=empty } feedback{ 0.name=trigger_mapping/feedback 0.type=cob_3d_mapping_msgs/TriggerMappingActionFeedback 0.desc=empty } sub{ 0.name = /point_cloud2 0.type = sensor_msgs/PointCloud2 0.desc = The input point cloud } pub{ 0.name = /point_cloud2_aligned 0.type = sensor_msgs/PointCloud2 0.desc = The aligned point cloud } srv{ 1.name = trigger_keyframe 1.type = cob_srvs/Trigger 1.desc = Triggers a map update } param{ 0.name = ~world_frame_id 0.type = string 0.default = /map 0.desc = Specifies frame id for which odometry is looked up. 1.name = ~algo 1.type = string 1.default = icp 1.desc = For registration different algorithms can be used. Allowed values are: [[http://ros.org/wiki/cob_3d_registration/icp|icp]], icp_lm, gicp, icp_moments, icp_fpfh, icp_narf, icp_edges, rgbdslam, [[http://ros.org/wiki/cob_3d_registration/info|info]], cor 2.name = ~voxelsize 2.type = double 2.default = 0.04 2.desc = Sets the cubic voxelsize in meter for preprocessing. Only needed for "icp", "icp_moments" and"icp_fpfh". } req_tf{ } prov_tf{ } }}} == Usage/Examples == {{{ roslaunch cob_3d_registration registration.launch }}} Trigger mapping by calling {{{ rosrun cob_3d_mapping_point_map trigger_mapping.py }}}