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

Could not save point cloud map from rtabmap

asked 2020-02-04 21:54:57 -0500

JeffHu7 gravatar image

updated 2020-02-04 22:04:27 -0500

Hi!

I tried to generate a 3D mapping using fetch in gazebo simulation using rtabmap, and I was able to open the rtabmap.db file. Although I could see the map when I open the file with "rtabmap ~/.ros/rtabmap.db," I cannot export as ply. The error is:

Could create clouds for 104 node(s). You may want to activate clouds regeneration option.

When I check the regeneration option in the export console, the error becomes:

Could not create clouds for 188 node(s). The cache may not contain point cloud data. Try re-downloading the map.

The launch file I used for mapping is:

<launch>
  <!-- Kinect cloud to laser scan -->
<node pkg="depthimage_to_laserscan" type="depthimage_to_laserscan" name="depthimage_to_laserscan">
  <remap from="image"       to="/head_camera/depth_registered/image_raw"/>
  <remap from="camera_info" to="/head_camera/depth_registered/camera_info"/>
  <remap from="scan"        to="/base_scan"/>
  <param name="range_max" type="double" value="4"/>
</node>

   <!-- SLAM -->
 <group ns="rtabmap">
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="frame_id" type="string" value="base_link"/>

      <param name="subscribe_depth" type="bool" value="false"/>
      <param name="subscribe_scan_cloud" type="bool" value="true"/>

      <remap from="odom" to="/odom"/>
      <remap from="scan_cloud" to="/head_camera/depth_registered/points"/>

      <remap from="rgb/image"       to="/head_camera/rgb/image_raw"/>
      <remap from="depth/image"     to="/head_camera/depth_registered/image_raw"/>
      <remap from="rgb/camera_info" to="/head_camera/rgb/camera_info"/>

      <param name="queue_size" type="int" value="10"/>

      <!-- RTAB-Map's parameters -->
      <param name="RGBD/ProximityBySpace"     type="string" value="false"/>
      <param name="RGBD/AngularUpdate"        type="string" value="0.01"/>
      <param name="RGBD/LinearUpdate"         type="string" value="0.01"/>
      <param name="RGBD/OptimizeFromGraphEnd" type="string" value="false"/>
      <param name="Reg/Force3DoF"             type="string" value="true"/>
      <param name="Vis/MinInliers"            type="string" value="12"/>
</node>

<node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
  <param name="subscribe_depth" type="bool" value="false"/>
  <param name="subscribe_scan_cloud" type="bool" value="true"/>
  <param name="frame_id"           type="string" value="base_link"/>
  <param name="wait_for_transform" type="bool" value="true"/>

  <remap from="odom" to="/odom"/>
  <remap from="scan_cloud" to="/head_camera/depth_registered/points"/>
  <remap from="rgb/image"       to="/head_camera/rgb/image_raw"/>
  <remap from="depth/image"     to="/head_camera/depth_registered/image_raw"/>
  <remap from="rgb/camera_info" to="/head_camera/rgb/camera_info"/>

</node>

</group>
</launch>

Thank you for your help!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2020-02-05 16:18:52 -0500

matlabbe gravatar image

If the map is totally empty, maybe the depth images are not saved. I see that you set subscribe_depth to false, no depth images will be saved. I would not use subscribe_scan_cloud for the camera cloud, but subscribe_scan to get the fake laser scan you generated from the depth image. Your example seems similar to this one: when subscribing to a laser scan, you should pre-sync the images before rtabmap node using rgbd_sync node.

Could not create clouds for 188 node(s). The cache may not contain point cloud data. Try re-downloading the map.

In rtabmapviz, do "Edit->Download all clouds" to refresh the cache. image description

If for some reasons rtabmapviz cannot call rtabmap service, you can open the database in rtabmap standalone, then export from there:

$ rtabmap ~/.ros/rtabmap.db
edit flag offensive delete link more

Comments

It worked after I adapted a new launch file from the one you linked above! (Although I still have no idea why it didn't let me save before, despite being able to see the map in rtabmapviz.) Thank you so much!!

JeffHu7 gravatar image JeffHu7  ( 2020-02-06 14:56:08 -0500 )edit

Question Tools

Stats

Asked: 2020-02-04 21:54:57 -0500

Seen: 1,189 times

Last updated: Feb 05 '20