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

Revision history [back]

click to hide/show revision 1
initial version

map_assembler is not subscribing to right mapData, you have to remap the topic or create the node in rtabmap namespace:

<node pkg="rtabmap_ros" type="map_assembler" name="map_assembler">
    <remap from="mapData"to="/rtabmap/mapData"/>
</node>
OR
<group ns="rtabmap">
    <node pkg="rtabmap_ros" type="map_assembler" name="map_assembler"/>
</group>

You may change Grid/VoxelSize value (default 0.05 m) if you want a more dense cloud. To save a point cloud message, you can use pointcloud_to_pcd:

$ rosrun pcl_ros pointcloud_to_pcd input:=/map_assembler/cloud_map

For your final question, if you are using rtabmap standalone to generate the mesh, you don't have to export the point cloud, just open the resulting database (default location is ~/.ros/rtabmap.db) in rtabmap standalone and do the export (like in step 7 of this tutorial):

$ rtabmap ~/.ros/rtabmap.db

You will then have all the options to regenerate the point cloud at the density you want while creating the mesh.

cheers,
Mathieu

map_assembler is not subscribing to right mapData, you have to remap the topic or create the node in rtabmap namespace:

<node pkg="rtabmap_ros" type="map_assembler" name="map_assembler">
    <remap from="mapData"to="/rtabmap/mapData"/>
</node>
OR
<group ns="rtabmap">
    <node pkg="rtabmap_ros" type="map_assembler" name="map_assembler"/>
</group>

You may change Grid/VoxelSize value (default 0.05 m) if you want a more dense cloud. To save a point cloud message, you can use pointcloud_to_pcd:

$ rosrun pcl_ros pointcloud_to_pcd input:=/map_assembler/cloud_map

For your final question, if you are using rtabmap standalone to generate the mesh, you don't have to export the point cloud, just open the resulting database (default location is ~/.ros/rtabmap.db) in rtabmap standalone and do the export (like in step 7 of this tutorial):

$ rtabmap ~/.ros/rtabmap.db

You will then have all the options to regenerate the point cloud at the density you want while creating the mesh.

cheers,
Mathieu

EDIT

For pointcloud_to_pcd, you would have start it only when you want to save the cloud, then kill it after saving one.

The cloud generated in RVIZ with MapCloud plugin can be regenerated identically with the Export options in rtabmap standalone. You can check Regenerate clouds option in Export dialog: image description

If you set voxel size to 0, you will get the most dense cloud that you can get from the depth images contained in the database. You will find all corresponding parameters of MapCloud rviz plugin in this dialog.

map_assembler is not subscribing to right mapData, you have to remap the topic or create the node in rtabmap namespace:

<node pkg="rtabmap_ros" type="map_assembler" name="map_assembler">
    <remap from="mapData"to="/rtabmap/mapData"/>
</node>
OR
<group ns="rtabmap">
    <node pkg="rtabmap_ros" type="map_assembler" name="map_assembler"/>
</group>

You may change Grid/VoxelSize value (default 0.05 m) if you want a more dense cloud. To save a point cloud message, you can use pointcloud_to_pcd:

$ rosrun pcl_ros pointcloud_to_pcd input:=/map_assembler/cloud_map

For your final question, if you are using rtabmap standalone to generate the mesh, you don't have to export the point cloud, just open the resulting database (default location is ~/.ros/rtabmap.db) in rtabmap standalone and do the export (like in step 7 of this tutorial):

$ rtabmap ~/.ros/rtabmap.db

You will then have all the options to regenerate the point cloud at the density you want while creating the mesh.

cheers,
Mathieu

EDIT

For pointcloud_to_pcd, you would have to start it only when you want to save the cloud, then kill it after saving one.

The cloud generated in RVIZ with MapCloud plugin can be regenerated identically with the Export options in rtabmap standalone. You can check Regenerate clouds option in Export dialog: image description

If you set voxel size to 0, you will get the most dense cloud that you can get from the depth images contained in the database. You will find all corresponding parameters of MapCloud rviz plugin in this dialog.