0
$\begingroup$

Rosanswers logo

I would like to use rtabmap_ros package to map an indoor environment. However, my robot has only odometry and laserscan data. Can I use, rtabmap_ros as a SLAM algorithm for my case? When I check Setup RTAB_MAP on your Robot, I couldn't see any configuration which uses odom + scan information. It seems I have to have a kinect sensor to use this package, but I would like to be sure.

I have already tried hector_slam, gmapping and cartographer_ros. I am trying hopelessly to find another possible SLAM algorithm which could give better performance for my case.

You can see my other question

Thank you for your help!


Edit: @matlabbe , Thank you very much for your answer. I directly used your launch file with the provided realoguz5.bag file as you mentioned. I also removed map frame from the bagfile and tried with that bagfile, . However, I couldn't see any map in either Rviz or Rtabmap_viz.You can see the terminal output of test.launch below. Could you help me further to solve this issue? Thank you very much!

    SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.13
 * /rtabmap/rtabmap/RGBD/NeighborLinkRefining: True
 * /rtabmap/rtabmap/Reg/Force3DoF: True
 * /rtabmap/rtabmap/Reg/Strategy: 1
 * /rtabmap/rtabmap/frame_id: base_link
 * /rtabmap/rtabmap/odom_frame_id: odom
 * /rtabmap/rtabmap/odom_tf_angular_variance: 0.05
 * /rtabmap/rtabmap/odom_tf_linear_variance: 0.01
 * /rtabmap/rtabmap/subscribe_depth: False
 * /rtabmap/rtabmap/subscribe_rgb: False
 * /rtabmap/rtabmap/subscribe_scan: True
 * /rtabmap/rtabmap/wait_for_transform_duration: 1
 * /use_sim_time: True

NODES
  /rtabmap/
    rtabmap (rtabmap_ros/rtabmap)
    rtabmapviz (rtabmap_ros/rtabmapviz)

ROS_MASTER_URI=http://localhost:11311

process[rtabmap/rtabmap-1]: started with pid [11259]
process[rtabmap/rtabmapviz-2]: started with pid [11260]
[ INFO] [1556631047.098153064]: Starting node...
[ INFO] [1556631047.152156112]: Initializing nodelet with 8 worker threads.
[ INFO] [1556631047.194421357]: Starting node...
[ INFO] [1556631047.305024760]: rtabmapviz: Using configuration from "/home/alperen/.ros/rtabmapGUI.ini"
[ INFO] [1556631048.460661263]: Reading parameters from the ROS server...
[ INFO] [1556631048.609303406]: Parameters read = 0
[ INFO] [1556631049.355704547]: /rtabmap/rtabmapviz: queue_size    = 10
[ INFO] [1556631049.355738290]: /rtabmap/rtabmapviz: rgbd_cameras = 1
[ INFO] [1556631049.355749637]: /rtabmap/rtabmapviz: approx_sync   = true
[ INFO] [1556631049.358946567]: 
/rtabmap/rtabmapviz subscribed to:
   /rtabmap/odom
[ INFO] [1556631049.359086913]: rtabmapviz started.
[ INFO] [1556631072.496810848, 1555961484.412100329]: /rtabmap/rtabmap(maps): map_filter_radius          = 0.000000
[ INFO] [1556631072.496924727, 1555961484.412100329]: /rtabmap/rtabmap(maps): map_filter_angle           = 30.000000
[ INFO] [1556631072.496986324, 1555961484.412100329]: /rtabmap/rtabmap(maps): map_cleanup                = true
[ INFO] [1556631072.497057702, 1555961484.412100329]: /rtabmap/rtabmap(maps): map_negative_poses_ignored = true
[ INFO] [1556631072.497116107, 1555961484.412100329]: /rtabmap/rtabmap(maps): map_negative_scan_ray_tracing = true
[ INFO] [1556631072.497174002, 1555961484.412100329]: /rtabmap/rtabmap(maps): cloud_output_voxelized     = true
[ INFO] [1556631072.497228337, 1555961484.412100329]: /rtabmap/rtabmap(maps): cloud_subtract_filtering   = false
[ INFO] [1556631072.497289089, 1555961484.412100329]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[ INFO] [1556631072.506124736, 1555961484.422174375]: /rtabmap/rtabmap(maps): octomap_tree_depth         = 16
[ INFO] [1556631072.548256477, 1555961484.462396979]: rtabmap: frame_id      = base_link
[ INFO] [1556631072.548287631, 1555961484.462396979]: rtabmap: odom_frame_id = odom
[ INFO] [1556631072.548303426, 1555961484.462396979]: rtabmap: map_frame_id  = map
[ INFO] [1556631072.548327794, 1555961484.462396979]: rtabmap: tf_delay      = 0.050000
[ INFO] [1556631072.548360511, 1555961484.462396979]: rtabmap: tf_tolerance  = 0.100000
[ INFO] [1556631072.548484635, 1555961484.462396979]: rtabmap: odom_sensor_sync   = true
[ INFO] [1556631072.966363444, 1555961484.884980407]: Setting RTAB-Map parameter "RGBD/NeighborLinkRefining"="true"
[ INFO] [1556631072.990358985, 1555961484.905120888]: Setting RTAB-Map parameter "Reg/Force3DoF"="true"
[ INFO] [1556631072.993316060, 1555961484.905120888]: Setting RTAB-Map parameter "Reg/Strategy"="1"
[ WARN] [1556631073.304790820, 1555961485.217051786]: Setting "Grid/FromDepth" parameter to false (default true) as "subscribe_scan" or "subscribe_scan_cloud" is true. The occupancy grid map will be constructed from laser scans. To get occupancy grid map from cloud projection, set "Grid/FromDepth" to true. To suppress this warning, add <param name="Grid/FromDepth" type="string" value="false"/>
[ INFO] [1556631073.304887280, 1555961485.217051786]: Setting "Grid/RangeMax" parameter to 0 (default 5.000000) as "subscribe_scan" or "subscribe_scan_cloud" is true.
[ WARN] [1556631073.304923801, 1555961485.217051786]: Setting "RGBD/ProximityPathMaxNeighbors" parameter to 10 (default 0) as "subscribe_scan" is true and "Reg/Strategy" uses ICP. Proximity detection by space will be also done by merging close scans. To disable, set "RGBD/ProximityPathMaxNeighbors" to 0. To suppress this warning, add <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>
[ INFO] [1556631073.495091214, 1555961485.408431133]: RTAB-Map detection rate = 1.000000 Hz
[ INFO] [1556631073.495247294, 1555961485.408431133]: rtabmap: Deleted database "/home/alperen/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[ INFO] [1556631073.495309505, 1555961485.408431133]: rtabmap: Using database from "/home/alperen/.ros/rtabmap.db" (0 MB).
[ INFO] [1556631074.532128087, 1555961486.450984098]: rtabmap: Database version = "0.17.6".
[ WARN] [1556631074.596041198, 1555961486.511582134]: When subscribing to laser scan, you should subscribe to depth, stereo or rgbd too. Subscribing to depth by default...
[ INFO] [1556631074.604608470, 1555961486.521694744]: /rtabmap/rtabmap: queue_size    = 10
[ INFO] [1556631074.604704264, 1555961486.521694744]: /rtabmap/rtabmap: rgbd_cameras = 1
[ INFO] [1556631074.604748108, 1555961486.521694744]: /rtabmap/rtabmap: approx_sync   = true
[ INFO] [1556631074.604866725, 1555961486.521694744]: Setup depth callback
[ INFO] [1556631074.632802948, 1555961486.551916526]: 
/rtabmap/rtabmap subscribed to (approx sync):
   /rtabmap/rgb/image,
   /rtabmap/depth/image,
   /rtabmap/rgb/camera_info,
   /scan
[ INFO] [1556631074.638748810, 1555961486.551916526]: rtabmap 0.17.6 started...
[ WARN] [1556631079.637634199, 1555961491.557643367]: /rtabmap/rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap/rtabmap subscribed to (approx sync):
   /rtabmap/rgb/image,
   /rtabmap/depth/image,
   /rtabmap/rgb/camera_info,
   /scan

Originally posted by samialperen on ROS Answers with karma: 70 on 2019-04-25

Post score: 1


Original comments

Comment by matlabbe on 2019-04-30:
Note that it is preferred that you edit your question instead of adding new info in a new answer. You are using rtabmap 0.17.6, my example works only with 0.19. You have to build rtabmap/rtabmap_ros from source. I edited my answer with that info.

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Hi,

Yes, we can use rtabmap without a camera, but global loop closure detection will be disabled (local proximity detection still work though, so small loop closures can be detected). EDIT rtabmap 0.19 minimum required. Currently, rtabmap binaries are at 0.17.6, we should build rtabmap/rtabmap_ros from source.

Here is an example following mostly the first setup example but without subscribing to camera:

<launch>
  <param name="use_sim_time" value="true"/> <!-- only with rosbag -->
  
  <group ns="rtabmap">
    <node pkg="rtabmap_ros" type="rtabmap" name="rtabmap" output="screen" args="-d">
      <param name="subscribe_scan"   value="true"/>
      <param name="subscribe_rgb"    value="false"/>
      <param name="subscribe_depth"  value="false"/>
      <param name="frame_id"         value="base_link"/>
      <param name="odom_frame_id"    value="odom"/>
      <param name="wait_for_transform_duration"  value="1"/>
      <param name="odom_tf_linear_variance"  value="0.01"/>
      <param name="odom_tf_angular_variance" value="0.05"/>

      <!-- RTAB-Map parameters -->
      <param name="Reg/Strategy"              value="1"/>    <!-- 1 for lidar -->
      <param name="Reg/Force3DoF"             value="true"/> <!-- 2d slam -->
      <param name="RGBD/NeighborLinkRefining" value="true"/> <!-- odometry correction with scans -->
      
      <remap from="scan"    to="/scan"/>
    </node>

    <!-- just for visualization -->
    <node pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" output="screen"/>
  </group>
</launch>

Example based on the rosbag of your other post:

$ roslaunch test.launch
$ rosbag play --clock -s 20 realoguz5.bag

To avoid warnings about two map frames published (one from the bag and the other one from rtabmap), we can remove the map frame from the bag using this script. Note also that in general wait_for_transform_duration would be lower, but this bag seems to have some TF and topic stamps synchronization latency.

image description

cheers, Mathieu


Originally posted by matlabbe with karma: 6409 on 2019-04-26

This answer was ACCEPTED on the original site

Post score: 3


Original comments

Comment by samialperen on 2019-05-02:
Thanks a lot!

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.