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

Hi,

By default rtabmap decimates by 4 RGB-D images to avoid creating very large point clouds. As depth images are already small for Tango, you can set cloud_decimation to 1:

 <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap">
    <param name="cloud_decimation" value="1"/>
    ...
 </node>

If you are only interested on odometry poses, open the database with standalone app $ rtabmap, "File" -> "Open Database..." and click "Edit" -> "Download graph-only" (choose not optimized to get odometry poses without graph corrections), then "File" -> "Export poses...".

You may also like the rtabmap-databaseViewer tool to inspect the odometry (neighbor) links in the database (View->Show Constraints).

cheers

Hi,

By default rtabmap decimates by 4 RGB-D images to avoid creating very large point clouds. As depth images are already small for Tango, you can set cloud_decimation to 1:

 <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap">
    <param name="cloud_decimation" value="1"/>
    ...
 </node>

If you are only interested on odometry poses, open the database with standalone app $ rtabmap, "File" -> "Open Database..." and click "Edit" -> "Download graph-only" (choose not optimized to get odometry poses without graph corrections), then "File" -> "Export poses...".

You may also like the rtabmap-databaseViewer tool to inspect the odometry (neighbor) links in the database (View->Show Constraints).

UPDATE

Thank you for the database. I couldn't reproduce the exact error you have (showing only a part of the map) but it helped me to fix a bug when generating the projection maps with data from Tango (depth and rgb images are not the same size and the calibration wasn't updated).

Workaround for current binaries 0.11.7 (Hack: we subscribe at the same time to cloud_map to create XYZRGB clouds instead of XYZ clouds for the projection):

$ roscore
$ rosrun rtabmap_ros rtabmap _database_path:=~/Downloads/bigmap.db
$ rostopic hz /cloud_map
$ rosrun map_server map_saver map:=proj_map
$ rosservice call /publish_map 1 1 0

With the fix on 0.11.8:

$ roscore
$ rosrun rtabmap_ros rtabmap _database_path:=~/Downloads/bigmap.db
$ rosrun map_server map_saver map:=proj_map
$ rosservice call /publish_map 1 1 0

Note that cloud_decimation can stay at 4 since we apply decimation on the RGB image size instead of the depth image size.

image description

image: map.pgm
resolution: 0.050000
origin: [-37.192123, -27.229282, 0.000000]
negate: 0
occupied_thresh: 0.65
free_thresh: 0.196

cheers