ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
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)
cheers
2 | No.2 Revision |
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