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

RTABMAP How to save registered 3D point cloud?

asked 2016-12-21 04:32:32 -0500

schrottulk gravatar image

Hi,

I am building a map with a Kinect 360 and a turtlebot using RTABMAP on Ubuntu 14.04 and ROS Indigo.

Everything works fine, I can see the registered 3D point cloud on RTABMAPVIZ or with RVIZ. Now I want to save the 3D Point cloud to .pcd or .ply . I know there is the option in RTABMAPVIZ with File->Export 3D Cloud descripted here, but is there any option to do this without using RTABMAPVIZ? Is there any service I can call from the command line or from another node? Or to do this in RVIZ?

Any help would be appreciated!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
4

answered 2016-12-22 14:09:54 -0500

matlabbe gravatar image

updated 2017-01-12 16:17:01 -0500

Hi,

It depends on which resolution you need the point cloud. By default, the /rtabmap/cloud_map topic (which is a PointCloud2) is voxelized at 5 cm. You can use pointcloud_to_pcd to export the point cloud to PCD:

$ rosrun pcl_ros pointcloud_to_pcd input:=/rtabmap/cloud_map

If rtabmap is not running (e.g., paused), call this to republish the map after being subscribed to /cloud_map:

$ rosservice call /rtabmap/publish_map 1 1 0

See rtabmap_ros/rtabmap wiki to see parameters related to /cloud_map. Unlike rtabmapviz, options are more limited:

~cloud_decimation (int, default: 4)
~cloud_max_depth (double, default: 4.0)
~cloud_voxel_size (double, default: 0.05)

EDIT

In rtabmap version >= 0.11.11, if you have set subscribe_scan to true, you should explicitly set Grid/FromDepth to true to assemble 3D Kinect clouds for /rtabmap/cloud_map:

<node pkg="rtabmap_ros" type="rtabmap" name="rtabmap">
   ...
   <param name="Grid/FromDepth" type="string" value="true"/>
</node>

cheers

edit flag offensive delete link more

Comments

Thanks a lot!

schrottulk gravatar image schrottulk  ( 2016-12-26 11:48:09 -0500 )edit

Hi matlabbe, sorry for bothering you again! But with cloud_map I only get the 2D projection of the registered 3D Map to the ground. Is it possible to save the registered 3D Point Cloud from the /rtabmap/mapData Topic to .pcd / .ply directly from the command line without using RTABMAPVIZ ?

schrottulk gravatar image schrottulk  ( 2017-01-12 06:34:52 -0500 )edit
3

updated the answer...

matlabbe gravatar image matlabbe  ( 2017-01-12 16:17:12 -0500 )edit

That works perfect! Many Thanks!

schrottulk gravatar image schrottulk  ( 2017-01-14 08:33:25 -0500 )edit

Question Tools

3 followers

Stats

Asked: 2016-12-21 04:32:32 -0500

Seen: 5,609 times

Last updated: Jan 12 '17