Show EOL distros: 

Package Summary

RTAB-Map's ros-pkg. RTAB-Map is a RGB-D SLAM approach with real-time constraints.

Package Summary

RTAB-Map's ros-pkg. RTAB-Map is a RGB-D SLAM approach with real-time constraints.

Overview

This package is a ROS wrapper of RTAB-Map (Real-Time Appearance-Based Mapping), a RGB-D SLAM approach based on a global loop closure detector with real-time constraints. This package can be used to generate a 3D point clouds of the environment and/or to create a 2D occupancy grid map for navigation. The tutorials and demos show some examples of mapping with RTAB-Map.

Tutorials

  1. RGB-D Handheld Mapping

    This tutorial shows how to use rtabmap_ros out-of-the-box with a Kinect-like sensor in mapping mode or localization mode.

  2. Stereo Handheld Mapping

    This tutorial shows how to use rtabmap_ros out-of-the-box with a stereo camera in mapping mode or localization mode.

  3. Stereo Outdoor Mapping

    This tutorial shows how to do stereo mapping with RTAB-Map.

  4. Stereo Outdoor Navigation

    This tutorial shows how to integrate autonomous navigation with RTAB-Map in context of outdoor stereo mapping.

  5. Mapping and Navigation with Turtlebot

    This tutorial shows how to use RTAB-Map with Turtlebot for mapping and navigation.

  6. Remote Mapping

    This tutorial shows how to do mapping on a remote computer.

  7. Setup RTAB-Map on Your Robot!

    This tutorial shows multiple RTAB-Map configurations that can be used on your robot.

  8. Tango ROS Streamer

    Tutorial to get Tango ROS Streamer working with rtabmap_ros

  9. Wifi Signal Strength Mapping (User Data Usage)

    This tutorial shows how to add user data during mapping that will be saved directly in RTAB-Map's database for convenience.

  10. Advanced Parameter Tuning

    This tutorial tells you which parameter to change to improve performances

Demos

Robot mapping

For this demo, you will need the ROS bag demo_mapping.bag (295 MB, fixed camera TF 2016/06/28, fixed not normalized quaternions 2017/02/24, fixed compressedDepth encoding format 2020/05/27, fixed odom child_frame_id not set 2021/01/22).

Launch: demo_robot_mapping.launch

  • $ roslaunch rtabmap_ros demo_robot_mapping.launch
    $ rosbag play --clock demo_mapping.bag

After mapping, you could try the localization mode:

  • $ roslaunch rtabmap_ros demo_robot_mapping.launch localization:=true
    $ rosbag play --clock demo_mapping.bag
  • Note that the GUI node doesn't download automatically the map when started. You will need to click "Edit->Download Map" on the GUI to download the map from the core node.

Robot mapping with RVIZ

For this demo, you will need the ROS bag demo_mapping.bag (295 MB, fixed camera TF 2016/06/28, fixed not normalized quaternions 2017/02/24, fixed compressedDepth encoding format 2020/05/27, fixed odom child_frame_id not set 2021/01/22).

Launch: demo_robot_mapping.launch

  • $ roslaunch rtabmap_ros demo_robot_mapping.launch rviz:=true rtabmapviz:=false
    $ rosbag play --clock demo_mapping.bag

Multi-session mapping

Detailed results are shown on the Multi-session page on RTAB-Map's wiki.

For this demo, you will need the ROS bags of five mapping sessions:

For the first launch, you can do "Edit->Delete memory" to make sure that you start from a clean memory. You may need to do this after starting the first bag with "--pause" so that rtabmap node is initialized to avoid a "service /reset cannot be called" error.

Launch: demo_multi-session_mapping.launch

  • $ roslaunch rtabmap_ros demo_multi-session_mapping.launch
    $ rosbag play --clock --pause map1.bag
    $ (...)
    $ rosbag play --clock map2.bag
    $ (...)
    $ rosbag play --clock map3.bag
    $ (...)
    $ rosbag play --clock map4.bag
    $ (...)
    $ rosbag play --clock map5.bag

Robot mapping with Find-Object

Find-Object's ros-pkg find_object_2d should be installed.

ROS Bag: demo_find_object.bag (416 MB)

Launch: demo_find_object.launch

  • $ roslaunch rtabmap_ros demo_find_object.launch
    $ rosbag play --clock demo_find_object.bag

IROS 2014 Kinect Challenge

There is no bag recorded for this demo but how to reproduce this setup is described on the page IROS 2014 Kinect Challenge of the RTAB-Map's wiki.

Stereo mapping

Visit the tutorial StereoOutdoorMapping for detailed information. It is also shown how to create 2D occupancy grid map for navigation.

ROS bags:

Launch : demo_stereo_outdoor.launch

  • $ roslaunch rtabmap_ros demo_stereo_outdoor.launch
    $ rosbag play --clock stereo_outdoorA.bag
    [...]
    $ rosbag play --clock stereo_outdoorB.bag

Stereo navigation

There is no bag recorded for this demo but how to reproduce this setup is described in the tutorial StereoOutdoorNavigation.

Appearance-based loop closure detection-only

Data:

  • samples.zip

    • Set video_or_images_path parameter of camera node in the launch file below accordingly.

Launch: demo_appearance_mapping.launch

  • $ roslaunch rtabmap_ros demo_appearance_mapping.launch

The GUI shows a plenty of information about the loop closures detected. If you only need the ID of the matched past image of a loop closure, you can do that:

  • $ rostopic echo /rtabmap/info/loopClosureId
    6
    ---
    0
    ---
    7
    ---

A "0" means no loop closure detected. This can be also used in localization mode:

  • $ roslaunch rtabmap_ros demo_appearance_mapping.launch localization:=true

For more videos and information about the loop closure detection approach used in RTAB-Map, visit RTAB-Map on IntRoLab.

Nodes

All sensor_msgs/Image topics use image_transport.

rtabmap

This is the main node of this package. It is a wrapper of the RTAB-Map Core library. This is where the graph of the map is incrementally built and optimized when a loop closure is detected. The online output of the node is the local graph with the latest added data to the map. The default location of the RTAB-Map database is "~/.ros/rtabmap.db" and the workspace is also set to "~/.ros". To get a 3D point cloud or a 2D occupancy grid of the environment, subscribe to cloud_map or grid_map topics.

  • There are two set of parameters: ROS and RTAB-Map's parameters. The ROS parameters are for connection stuff to interface the RTAB-Map library with ROS. The RTAB-Map's parameters are those from the RTAB-Map library.
    • One way to know RTAB-Map's parameters is to look at this file : Parameters.h. There is a description for each parameter. Here two examples (use string type for all RTAB-Map's parameters) by either using param member or by passing as arguments:

      • <launch>
        <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" args="--Grid/RangeMax 5">
           <param name="Optimizer/Iterations" type="int" value="50"/>
        </node>
        </launch>
    • Another way to show available parameters from the terminal is to call the node with "--params" argument:
      • $ rosrun rtabmap_ros rtabmap --params
        or
        $ rtabmap --params
    • By default, rtabmap is in mapping mode. To set in localization mode with a previously created map, you should set the memory not incremental (make sure that arguments don't contain "--delete_db_on_start" too!):

      • <launch>
        <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" args="">
           <!-- LOCALIZATION MODE -->
           <param name="Mem/IncrementalMemory" type="string" value="false"/>
        </node>
        </launch>

Arguments

  • "--delete_db_on_start" or "-d": Delete the database before starting, otherwise the previous mapping session is loaded.

  • "--udebug": Show RTAB-Map's debug/info/warning/error logs.

  • "--uinfo": Show RTAB-Map's info/warning/error logs.

  • "--params": Show RTAB-Map's parameters related to this node and exit.

Subscribed Topics

odom (nav_msgs/Odometry)
  • Odometry stream. Required if parameters subscribe_depth or subscribe_stereo are true and odom_frame_id is not set.
rgb/image (sensor_msgs/Image)
  • RGB/Mono image. Should be rectified when subscribe_depth is true. Not required if parameter subscribe_stereo is true (use left/image_rect instead).
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata. Not required if parameter subscribe_stereo is true (use left/camera_info instead).
depth/image (sensor_msgs/Image)
  • Registered depth image. Required if parameter subscribe_depth is true.
scan (sensor_msgs/LaserScan)
  • Laser scan stream. Required if parameter subscribe_scan is true.
scan_cloud (sensor_msgs/PointCloud2)
  • Laser scan point cloud stream. Required if parameter subscribe_scan_cloud is true.
left/image_rect (sensor_msgs/Image)
  • Left RGB/Mono rectified image. Required if parameter subscribe_stereo is true.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata. Required if parameter subscribe_stereo is true.
right/image_rect (sensor_msgs/Image)
  • Right Mono rectified image. Required if parameter subscribe_stereo is true.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata. Required if parameter subscribe_stereo is true.
goal (geometry_msgs/PoseStamped)
  • Planning Plan a path to reach this goal using the current online map. The goal should be close enough to the map's graph to be accepted (see RTAB-Map's parameter RGBD/LocalRadius). Note that only nodes in Working Memory are used, for exploration it may be ok, but it would be better to use service set_goal if you are coming back in a previously mapped area. See Planning published topics for corresponding generated outputs.
rgbd_image (rtabmap_ros/RGBDImage)
  • RGB-D synchronized image, only when subscribe_rgbd is true.
imu (sensor_msgs/Imu)
  • Can be used to add gravity constraints in the graph. The whole map will then be aligned with gravity. The quaternion should be already computed (see imu_filter_madgwick to compute it).
gps/fix (sensor_msgs/NavSatFix)
  • Can be used to add GPS constraints in the graph. This could eventually be used to export poses in GPS format. With Optimizer/PriorsIgnored parameter set to false, the graph can be also optimized using the GPS values. See also this page on how GPS can be used to limit loop closure detection radius.
global_pose (geometry_msgs/PoseWithCovarianceStamped)
  • Can be used to add global prior constraints in the graph. With Optimizer/PriorsIgnored parameter set to false, the graph can be optimized using the prior values.
tag_detections (apriltag_ros/AprilTagDetectionArray)
  • Can be used to add landmark constraints in the graph. Landmarks are used in graph optimization and also for loop closure detection. See also apriltag_ros repository.
fiducial_transforms (fiducial_msgs/FiducialTransformArray)
  • Can be used to add landmark constraints in the graph. Landmarks are used in graph optimization and also for loop closure detection. See also fiducials repository.

Published Topics

info (rtabmap_ros/Info)
  • RTAB-Map's info.
mapData (rtabmap_ros/MapData)
  • RTAB-Map's graph and latest node data.
mapGraph (rtabmap_ros/MapGraph)
  • RTAB-Map's graph only.
grid_map (nav_msgs/OccupancyGrid)
  • Mapping Occupancy grid generated with laser scans. Use parameters in Mapping group below and RTAB-Map's parameters starting with Grid/ prefix. Do rtabmap --params | grep Grid/ to see all of them.
proj_map (nav_msgs/OccupancyGrid)
  • Mapping DEPRECATED: use /grid_map topic instead with Grid/FromDepth=true.
cloud_map (sensor_msgs/PointCloud2)
  • Mapping 3D point cloud generated from the assembled local grids. Use parameters with prefixes map_ and cloud_ below.
cloud_obstacles (sensor_msgs/PointCloud2)
  • Mapping 3D point cloud of obstacles generated from the assembled local grids. Use parameters with prefixes map_ and cloud_ below.
cloud_ground (sensor_msgs/PointCloud2)
  • Mapping 3D point cloud of ground generated from the assembled local grids. Use parameters with prefixes map_ and cloud_ below.
scan_map (sensor_msgs/PointCloud2)
  • Mapping 3D point cloud generated with the 2D scans or 3D scans. Use parameters with prefixes map_ and scan_ below.
labels (visualization_msgs/MarkerArray)
  • Convenient way to show graph's labels in RVIZ.
global_path (nav_msgs/Path)
  • Planning Poses of the planned global path. Published only once for each path planned.
local_path (nav_msgs/Path)
  • Planning Upcoming local poses corresponding to those of the global path. Published on every map update.
goal_reached (std_msgs/Bool)
  • Planning Status message if the goal is successfully reached or not.
goal_out (geometry_msgs/PoseStamped)
  • Planning Current metric goal sent from the rtabmap's topological planner. For example, this can be connected to move_base_simple/goal topic of move_base.
octomap_full (octomap_msgs/Octomap)
  • Get an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_binary (octomap_msgs/Octomap)
  • Get an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_occupied_space (sensor_msgs/PointCloud2)
  • A point cloud of the occupied space (obstacles and ground) of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_obstacles (sensor_msgs/PointCloud2)
  • A point cloud of the obstacles of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_ground (sensor_msgs/PointCloud2)
  • A point cloud of the ground of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_empty_space (sensor_msgs/PointCloud2)
  • A point cloud of empty space of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_grid (nav_msgs/OccupancyGrid)
  • The projection of the OctoMap into a 2D occupancy grid map. Available only if rtabmap_ros is built with octomap.

Services

get_map (nav_msgs/GetMap)
  • Call this service to get the standard 2D occupancy grid
get_map_data (rtabmap_ros/GetMap)
  • Call this service to get the map data
publish_map (rtabmap_ros/PublishMap)
  • Call this service to publish the map data
list_labels (rtabmap_ros/ListLabels)
  • Get current labels of the graph.
update_parameters (std_srvs/Empty)
  • The node will update with current parameters of the rosparam server
reset (std_srvs/Empty)
  • Delete the map
pause (std_srvs/Empty)
  • Pause mapping
resume (std_srvs/Empty)
  • Resume mapping
trigger_new_map (std_srvs/Empty)
  • The node will begin a new map
backup (std_srvs/Empty)
  • Backup the database to "database_path.back" (default ~/.ros/rtabmap.db.back)
set_mode_localization (std_srvs/Empty)
  • Set localization mode
set_mode_mapping (std_srvs/Empty)
  • Set mapping mode
set_label (rtabmap_ros/SetLabel)
  • Set a label to latest node or a specified node.
set_goal (rtabmap_ros/SetGoal)
  • Planning Set a topological goal (a node id or a node label in the graph). Plan a path to reach this goal using the whole map contained in memory (including nodes in Long-Term Memory). See Planning published topics for corresponding generated outputs.
octomap_full (octomap_msgs/GetOctomap)
  • Get an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_binary (octomap_msgs/GetOctomap)
  • Get an OctoMap. Available only if rtabmap_ros is built with octomap.

Parameters

~subscribe_depth (bool, default: "true")
  • Subscribe to depth image
~subscribe_scan (bool, default: "false")
  • Subscribe to laser scan
~subscribe_scan_cloud (bool, default: "false")
  • Subscribe to laser scan point cloud
~subscribe_stereo (bool, default: "false")
  • Subscribe to stereo images
~subscribe_rgbd (bool, default: "false")
  • Subsribe to rgbd_image topic.
~frame_id (string, default: "base_link")
  • The frame attached to the mobile base.
~map_frame_id (string, default: "map")
  • The frame attached to the map.
~odom_frame_id (string, default: "")
  • The frame attached to odometry. If empty, rtabmap will subscribe to odom topic to get odometry. If set, odometry is got from tf (in this case, the covariance value is fixed by odom_tf_angular_variance and odom_tf_linear_variance).
~odom_tf_linear_variance (double, default: 0.001)
  • When odom_frame_id is used, the first 3 values of the diagonal of the 6x6 covariance matrix are set to this value.
~odom_tf_angular_variance (double, default: 0.001)
  • When odom_frame_id is used, the last 3 values of the diagonal of the 6x6 covariance matrix are set to this value.
~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~publish_tf (bool, default: "true")
  • Publish TF from /map to /odom.
~tf_delay (double, default: 0.05)
  • Rate at which the TF from /map to /odom is published (20 Hz).
~tf_prefix (string, default: "")
  • Prefix to add to generated tf.
~wait_for_transform (bool, default: "true")
  • Wait (maximum wait_for_transform_duration sec) for transform when a tf transform is not still available.
~wait_for_transform_duration (double, default: 0.1)
  • Wait duration for wait_for_transform.
~config_path (string, default: "")
  • Path of a config files containing RTAB-Map's parameters. Parameters set in the launch file overwrite those in the config file.
~database_path (string, default: "~/.ros/rtabmap.db")
  • Path of the RTAB-Map's database.
~gen_scan (bool, default: "false")
  • Generate laser scans from depth images (using the middle horizontal line of the depth image). Not generated if subscribe_scan or subscribe_scan_cloud are true.
~gen_scan_max_depth (double, default: 4.0)
  • Maximum depth of the laser scans generated.
~approx_sync (bool, default: "false")
  • Use approximate time synchronization of input messages. If false, note that the odometry input must have also exactly the same timestamps than the input images.
~rgbd_cameras (int, default: 1)
  • Number of RGB-D cameras to use (when subscribe_rgbd is true). Well for now, a maximum of 4 cameras can be synchronized at the same time. If > 1, the rgbd_image topics should contain the camera index starting with 0. For example, if we have 2 cameras, you should set rgbd_image0 and rgbd_image1 topics.
~use_action_for_goal (bool, default: "false")
  • Planning Use actionlib to send the metric goals to move_base. The advantage over just connecting goal_out to move_base_simple/goal is that rtabmap can have a feedback if the goal is reached or if move_base has failed. See move_base Action API for more info.
~odom_sensor_sync (bool, default: "false")
  • Adjust image and scan poses relatively to odometry pose for each node added to graph. For example, if an image received at t=1s has been synchronized with a scan at t=1.1s (and our reference stamp is the scan) and the robot is moving forward at 1 m/s, then we will ask TF to know the motion between t=1s and t=1.1s (which would be 0.1 m) for the camera to adjust its local transform (-10 cm) relative to scan frame at scan stamp. This also applies to multi-camera synchronization.
~gen_depth (bool, default: "false")
  • Generate depth image from scan_cloud projection into RGB camera, taking into account displacement of the RGB camera accordingly to odometry and lidar frames. It works like pointcloud_to_depthimage node, but at slam frequency.
~gen_depth_decimation (int, default: 1)
  • Scale down image size of the camera info received (creating smaller depth image).
~gen_depth_fill_holes_size (int, default: 0)
  • Fill holes of empty pixels up to this size. Values are interpolated from neighbor depth values. 0 means disabled.
~gen_depth_fill_iterations (double, default: 0.1)
  • Maximum depth error (m) to interpolate.
~gen_depth_fill_holes_error (int, default: 1)
  • Number of iterations to fill holes.
~map_filter_radius (double, default: 0.0)
  • Mapping Filter nodes before creating the maps. Only load data for one node in the filter radius (the latest data is used) up to filter angle (map_filter_angle). Set to 0.0 to disable node filtering. Used for all published maps.
~map_filter_angle (double, default: 30.0)
  • Mapping Angle used when filtering nodes before creating the maps. See also map_filter_radius. Used for all published maps.
~map_cleanup (bool, default: "true")
  • Mapping If there is no subscription to any map cloud_map, grid_map or proj_map, clear the corresponding data.
~latch (bool, default: "true")
  • Mapping If true, the last message published on the map topics will be saved and sent to new subscribers when they connect.
~map_always_update (bool, default: "false")
  • Mapping Always update the occupancy grid map even if the graph has not been updated (e.g., by default when the robot is not moving, the graph is not growing). For example, if the environment is dynamic, we may want to update the map even when to robot is not moving. Another approach would be to force rtabmap to always update the graph (by setting RGBD/LinearUpdate to 0), which can be not efficient over time as the map will grow even if the robot doesn't move.
~map_empty_ray_tracing (bool, default: "true")
  • Mapping Do ray tracing to fill unknown space for invalid 2D scan's rays (assuming invalid rays to be infinite). Used only when map_always_update is also true.
~cloud_output_voxelized (bool, default: "true")
  • Mapping Do a final voxel filtering after all clouds are assembled with a voxel size equals to Grid/CellSize. Used for cloud_map published topic.
~cloud_subtract_filtering (bool, default: "true")
  • Mapping When appending a new cloud to cloud_map, filter points that have less neighbors than cloud_subtract_filtering_min_neighbors in the radius Grid/CellSize. This will helps to reconstruct the whole map's cloud faster when a loop closure happens. Used for cloud_map published topic.
~cloud_subtract_filtering_min_neighbors (int, default: 2)
  • Mapping See cloud_subtract_filtering parameter's description.

Required tf Transforms

base_link<the frame attached to sensors of incoming data> odombase_link
  • usually provided by the odometry system (e.g., the driver for the mobile base).

Provided tf Transforms

mapodom
  • the current odometry correction.

rtabmapviz

This node starts the visualization interface of RTAB-Map. It is a wrapper of the RTAB-Map GUI library. It has the same purpose as rviz but with specific options for RTAB-Map.

Arguments

  • -d "config.ini": Set a RTAB-Map ini file for GUI interface parameters. Default is "/.ros/rtabmapGUI.ini".

Subscribed Topics

odom (nav_msgs/Odometry)
  • Odometry stream. Required if parameters subscribe_depth or subscribe_stereo are true and odom_frame_id is not set.
rgb/image (sensor_msgs/Image)
  • RGB/Mono image. Should be rectified when subscribe_depth is true. Not required if parameter subscribe_stereo is true (use left/image_rect instead).
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata. Not required if parameter subscribe_stereo is true (use left/camera_info instead).
depth/image (sensor_msgs/Image)
  • Registered depth image. Required if parameter subscribe_depth is true.
scan (sensor_msgs/LaserScan)
  • Laser scan stream. Required if parameter subscribe_scan is true.
scan_cloud (sensor_msgs/PointCloud2)
  • Laser scan stream. Required if parameter subscribe_scan_cloud is true.
left/image_rect (sensor_msgs/Image)
  • Left RGB/Mono rectified image. Required if parameter subscribe_stereo is true.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata. Required if parameter subscribe_stereo is true.
right/image_rect (sensor_msgs/Image)
  • Right Mono rectified image. Required if parameter subscribe_stereo is true.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata. Required if parameter subscribe_stereo is true.
odom_info (rtabmap_ros/OdomInfo)
  • Odometry info. Required if parameter subscribe_odom_info is true.
info (rtabmap_ros/Info)
  • RTAB-Map's statistics info.
mapData (rtabmap_ros/MapData)
  • RTAB-Map's graph and latest node data.
rgbd_image (rtabmap_ros/RGBDImage)
  • RGB-D synchronized image, only when subscribe_rgbd is true.

Parameters

~subscribe_depth (bool, default: "false")
  • Subscribe to depth image
~subscribe_scan (bool, default: "false")
  • Subscribe to laser scan
~subscribe_scan_cloud (bool, default: "false")
  • Subscribe to laser scan point cloud
~subscribe_stereo (bool, default: "false")
  • Subscribe to stereo images
~subscribe_odom_info (bool, default: "false")
  • Subscribe to odometry info messages
~subscribe_rgbd (bool, default: "false")
  • Subsribe to rgbd_image topic.
~frame_id (string, default: "base_link")
  • The frame attached to the mobile base.
~odom_frame_id (string, default: "")
  • The frame attached to odometry. If empty, rtabmapviz will subscribe to odom topic to get odometry. If set, odometry is got from tf.
~tf_prefix (string, default: "")
  • Prefix to add to generated tf.
~wait_for_transform (bool, default: "false")
  • Wait (maximum 1 sec) for transform when a tf transform is not still available.
~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~rgbd_cameras (int, default: 1)
  • Number of RGB-D cameras to use (when subscribe_rgbd is true). Well for now, a maximum of 4 cameras can be synchronized at the same time. If > 1, the rgbd_image topics should contain the camera index starting with 0. For example, if we have 2 cameras, you should set rgbd_image0 and rgbd_image1 topics.

Required tf Transforms

base_link<the frame attached to sensors of incoming data> odombase_link
  • usually provided by the odometry system (e.g., the driver for the mobile base).
mapodom
  • the current odometry correction.

Visual and Lidar Odometry

Common odometry stuff for rgbd_odometry, stereo_odometry and icp_odometry nodes. These nodes wrap the various odometry approaches of RTAB-Map. When a transformation cannot be computed, a null transformation is sent to notify the receiver that odometry is not updated or lost.

  • There are two set of parameters: ROS and RTAB-Map's parameters. The ROS parameters are for connection stuff to interface the RTAB-Map library with ROS. The RTAB-Map's parameters are those from the RTAB-Map library.
    • Parameters available for odometry can be shown from the terminal by using the "--params" argument:
      • $ rosrun rtabmap_ros rgbd_odometry --params
        or
        $ rosrun rtabmap_ros stereo_odometry --params
        or
        $ rosrun rtabmap_ros icp_odometry --params

Arguments

  • "--params": Show RTAB-Map's parameters related to this node and exit.

Published Topics

odom (nav_msgs/Odometry)
  • Odometry stream. Send null odometry if cannot be computed.
odom_info (rtabmap_ros/OdomInfo)
  • Odometry info stream. RTAB-Map's parameter Odom/FillInfoData should be true to fill features information (default is true).
odom_last_frame (sensor_msgs/PointCloud2)
  • 3D features of the last frame used to estimate the transformation.
odom_local_map (sensor_msgs/PointCloud2)
  • Local map of 3D features used as reference to estimate the transformation. Only published if RTAB-Map's parameter Odom/Strategy=0.

Services

reset_odom (std_srvs/Empty)
  • Restart odometry to identity transformation.
reset_odom_to_pose (rtabmap_ros/ResetPose)
  • Restart odometry to specified transformation. Format: "x y z roll pitch yaw".
pause_odom (std_srvs/Empty)
  • Pause odometry.
resume_odom (std_srvs/Empty)
  • Resume odometry.

Parameters

~frame_id (string, default: "base_link")
  • The frame attached to the mobile base.
~odom_frame_id (string, default: "odom")
  • The odometry frame.
~publish_tf (bool, default: "true")
  • Publish TF from /odom to /base_link.
~tf_prefix (bool, default: "")
  • Prefix to add to generated tf.
~wait_for_transform (bool, default: "false")
  • Wait (maximum 1 sec) for transform when a tf transform is not still available.
~initial_pose (string, default: "")
  • The initial pose of the odometry. Format: "x y z roll pitch yaw".
~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~publish_null_when_lost (bool, default: true)
  • Odometry is published with null transform when lost.
~ground_truth_frame_id (string, default: "")
  • This can be used to have odometry initialized at the current ground truth pose.
~ground_truth_base_frame_id (string, default: "")
  • See ground_truth_frame_id description.
~guess_frame_id (string, default: "")
  • Use this frame as guess to compute odometry, otherwise odometry guess is done from a constant motion model. tf published by this node will be the correction of actual odometry. If guess_frame_id is odom_combined, odom_frame_id is odom and frame_id is base_footprint, odom -> odom_combined is published by this node to have a tf tree like this: /odom -> /odom_combined -> /base_link.
~guess_min_translation (float, default: 0.0 m)
  • When guess_frame_id is set, don't update odometry unless the guess moved at least as much as this value.
~guess_min_rotation (float, default: 0.0 rad)
  • When guess_frame_id is set, don't update odometry unless the guess rotated at least as much as this value.
~config_path (string, default: "")
  • A config (ini) file with RTAB-Map's parameters.

Required tf Transforms

base_link<the frame attached to sensors of incoming data>

Provided tf Transforms

odombase_link
  • the current estimate of the robot's pose within the odometry frame.

rgbd_odometry

This node wraps the RGBD odometry approach of RTAB-Map. Using RGBD images, odometry is computed using visual features extracted from the RGB images with their depth information from the depth images. Using the feature correspondences between the images, a RANSAC approach computes the transformation between the consecutive images.

See also Visual Odometry for common odometry stuff used by this node.

Subscribed Topics

rgb/image (sensor_msgs/Image)
  • RGB/Mono rectified image.
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata.
depth/image (sensor_msgs/Image)
  • Registered depth image.
rgbd_image (rtabmap_ros/RGBDImage)
  • RGB-D synchronized image, only when subscribe_rgbd is true.

Parameters

~approx_sync (bool, default: "true")
  • Use approximate time synchronization of rgb and depth messages. If false, the rgb and depth images must have the same timestamps.
~rgbd_cameras (int, default: 1)
  • Number of RGB-D cameras to use (when subscribe_rgbd is true). Well for now, a maximum of 4 cameras can be synchronized at the same time. If > 1, the rgbd_image topics should contain the camera index starting with 0. For example, if we have 2 cameras, you should set rgbd_image0 and rgbd_image1 topics.
~subscribe_rgbd (bool, default: "false")
  • Subsribe to rgbd_image topic.

stereo_odometry

This node wraps the stereo odometry approach of RTAB-Map. Using stereo images, odometry is computed using visual features extracted from the left images with their depth information computed by finding the same features on the right images. Using the feature correspondences, a RANSAC approach computes the transformation between the consecutive left images.

See also Visual Odometry for common odometry stuff used by this node.

Subscribed Topics

left/image_rect (sensor_msgs/Image)
  • Left RGB/Mono rectified image.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata.
right/image_rect (sensor_msgs/Image)
  • Right Mono rectified image.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata.
rgbd_image (rtabmap_ros/RGBDImage)
  • Stereo synchronized image, only when subscribe_rgbd is true. This topic should contain left image in rgb field and right image in depth field (with corresponding camera info).

Parameters

~approx_sync (bool, default: "false")
  • Use approximate time synchronization of stereo messages. If false, the left/right images and the left/right camera infos must have the same timestamps.
~subscribe_rgbd (bool, default: "false")
  • Subsribe to rgbd_image topic.

icp_odometry

This node wraps the icp odometry approach of RTAB-Map. Using laser scan or a point cloud, odometry is computed by Iterative Closest Point (ICP) registration.

See also Visual Odometry for common odometry stuff used by this node.

Subscribed Topics

scan (sensor_msgs/LaserScan)
  • Laser scan, assuming the lidar is installed horizontally. Don't use scan or scan_cloud at the same time.
scan_cloud (sensor_msgs/PointCloud2)
  • Point cloud, which can be 2D or 3D. Don't use scan or scan_cloud at the same time.

Parameters

~scan_cloud_max_points (int, default: 0)
  • Maximum point in laser scan or point cloud. 0 means the maximum is defined by the size of ranges vector for laser scan topic.
~scan_downsampling_step (int, default: 1)
  • Downsample the laser scan or point cloud. <=1 means no downsampling, otherwise one ray/point each step is kept.
~scan_voxel_size (float, default: 0.0 m)
  • Filter the laser scan or point cloud using voxel filter of this size. 0.0 means disabled.
~scan_normal_k (int, default: 0)
  • Estimate normals of the laser scan or point cloud by using k nearest points. Useful only if Icp/Point2Plane parameter is enabled. 0 means disabled.
~scan_normal_radius (float, default: 0.0)
  • Estimate normals of the laser scan or point cloud by using nearest points under this fixed radius. Useful only if Icp/Point2Plane parameter is enabled. 0.0 means disabled.

camera

A node for image acquisition from an USB camera (OpenCV is used). A special option for this node is that it can be configured to read images from a directory or a video file. Parameters can be changed with the dynamic_reconfigure GUI from ROS. For dynamic parameters, see Camera.cfg

Published Topics

image (sensor_msgs/Image)
  • Image stream.

Services

stop_camera (std_srvs/Empty)
  • Stop the camera.
start_camera (rtabmap_ros/ResetPose)
  • Start the camera.

Parameters

~frame_id (string, default: "camera")
  • The frame attached to the camera.

map_assembler

Note: It is recommend to use directly cloud_map or proj_map published topics from rtabmap node instead of using this node.

This node subscribes to rtabmap output topic "mapData" and assembles the 3D map incrementally, then publishes the same maps than rtabmap. See all Mapping related topics and parameters of rtabmap node. You can also use all Grid parameters from rtabmap:

  • $ rosrun rtabmap_ros rtabmap --params | grep Grid/

For example, setting the voxel sixe of the resulting grid/point cloud to 10 cm:

  • <launch>
    <node name="map_assembler" pkg="rtabmap_ros" type="map_assembler">
       <param name="Grid/CellSize" type="double" value="0.1"/>
    </node>
    </launch>

Subscribed Topics

mapData (rtabmap_ros/MapData)
  • RTAB-Map's graph and latest node data.

Services

~reset (std_srvs/Empty)
  • Reset the cache.

Parameters

~regenerate_local_grids (bool, default: "false")
  • (>=0.20.5) If local occupancy grids are already included in mapData, set this to true to regenerate them. For example, this can be used to generate the local occupancy grids with a different sensor (e.g., Grid/FromDepth is different than one used in rtabmap).

map_optimizer

This node is for advanced usage only as it is preferred to use graph optimization already inside rtabmap node (which is the default). See related parameters in rtabmap:

$rosrun rtabmap_ros rtabmap --params | grep Optimize

This node subscribes to rtabmap output topic "mapData" and optimize the graph, then republishes the optimized "mapData".

  • This node can be used to optimize the graph outside rtabmap node. The benefice to do that is that we can keep optimized the global map instead of the local map of rtabmap. You can then connect output mapData_optimized to map_assembler to get the optimized grid, proj and cloud maps assembled again. Note that processing time for map optimization using this node is not bounded (which is the case in rtabmap node).

  • You could also use your own graph optimization approach instead of this node by modifying poses values of the rtabmap_ros/MapData msg. However, implementing your graph optimization approach inside rtabmap is preferred (inherit Optimizer class and add it here with a new number, then you could select it after using the parameter RGBD/OptimizeStrategy).

  • When using graph optimization outside rtabmap node, you should set parameters RGBD/OptimizeIterations to 0, RGBD/OptimizeMaxError to 0 and publish_tf to false for rtabmap node.

  • This node should not be used if rtabmap node is in localization mode.

Subscribed Topics

mapData (rtabmap_ros/MapData)
  • RTAB-Map's graph and latest node data.

Published Topics

[mapData]_optimized (rtabmap_ros/MapData)
  • RTAB-Map's optimized graph and latest node data.
[mapData]Graph_optimized (rtabmap_ros/MapGraph)
  • RTAB-Map's optimized graph.

Parameters

~map_frame_id (string, default: "map")
  • The frame attached to the map.
~odom_frame_id (string, default: "odom")
  • The frame attached to odometry.
~strategy (int, default: 0)
  • Optimization approach used: 0=TORO, 1=g2o and 2=GTSAM.
~slam_2d (bool, default: "false")
  • 3DoF (x,y,yaw) optimization instead of 6DoF (x,y,z,roll,pitch,yaw).
~robust (bool, default: "true")
  • Activate Vertigo robust graph optimization when g2o or GTSAM strategy is used.
~global_optimization (bool, default: "true")
  • Optimize the global map. If false, only the local map is optimized.
~iterations (int, default: 100)
  • Map optimization iterations.
~epsilon (double, default: 0.0)
  • Stop graph optimization when error is less than epsilon (0=ignore epsilon).
~ignore_variance (bool, default: "false")
  • Ignore constraints' variance. If checked, identity information matrix is used for each constraint in TORO. Otherwise, an information matrix is generated from the variance saved in the links.
~optimize_from_last_node (bool, default: "false")
  • Optimize from the last node. If false, the graph is optimized from the oldest node linked to the current map.
~publish_tf (bool, default: "true")
  • Publish TF from /map to /odom.
~tf_delay (double, default: 0.05)
  • Rate at which the TF from /map to /odom is published (20 Hz).

Nodelets

rtabmap_ros/rgbd_sync

Synchronize RGB, depth and camera_info messages into a single message. You can then use subscribe_rgbd to make rtabmap or odometry nodes subscribing to this message instead. This is useful when, for example, rtabmap is subscribed also to a laser scan or odometry topic published at different rate than the image topics. We can then make sure that images are correctly synchronized together. If you have camera publishing on the network, this can be also a good format to synchronize images before sending them on the network, to avoid synchronization issues when the network is lagging.

Subscribed Topics

rgb/image (sensor_msgs/Image)
  • RGB image stream.
depth/image (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Published Topics

rgbd_image (rtabmap_ros/RGBDImage)
  • The RGB-D image topic
rgbd_image/compressed (rtabmap_ros/RGBDImage)
  • The compressed RGB-D image topic (rgb=jpeg, depth=png)

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~approx_sync (bool, default: "True")
  • Use approximate synchronization for the input topics. If false, the RGB and depth images and the camera info must have the same timestamp.
~compressed_rate (double, default: 0)
  • Throttling rate at which rgbd_image/compressed topic will be published. 0 means no throttling.

rtabmap_ros/rgb_sync

Synchronize RGB and camera_info messages into a single message. You can then use subscribe_rgbd to make rtabmap or odometry nodes subscribing to this message instead. This is useful when, for example, rtabmap is subscribed also to a laser scan or odometry topic published at different rate than the image topics. We can then make sure that images are correctly synchronized together. If you have camera publishing on the network, this can be also a good format to synchronize images before sending them on the network, to avoid synchronization issues when the network is lagging.

Subscribed Topics

rgb/image (sensor_msgs/Image)
  • RGB image stream.
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Published Topics

rgbd_image (rtabmap_ros/RGBDImage)
  • The RGB-D image topic
rgbd_image/compressed (rtabmap_ros/RGBDImage)
  • The compressed RGB-D image topic (rgb=jpeg, depth=png)

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~approx_sync (bool, default: "False")
  • Use approximate synchronization for the input topics. If false, the RGB and depth images and the camera info must have the same timestamp.
~compressed_rate (double, default: 0)
  • Throttling rate at which rgbd_image/compressed topic will be published. 0 means no throttling.

rtabmap_ros/stereo_sync

Synchronize left image, right image and camera_info messages into a single message. You can then use subscribe_rgbd to make rtabmap or odometry nodes subscribing to this message instead. This is useful when, for example, rtabmap is subscribed also to a laser scan or odometry topic published at different rate than the image topics. We can then make sure that images are correctly synchronized together. If you have camera publishing on the network, this can be also a good format to synchronize images before sending them on the network, to avoid synchronization issues when the network is lagging.

Subscribed Topics

left/image_rect (sensor_msgs/Image)
  • Left image stream.
right/image_rect (sensor_msgs/Image)
  • Right image stream.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata.

Published Topics

rgbd_image (rtabmap_ros/RGBDImage)
  • The RGB-D image topic. The RGB field is the left image and the depth field is the right image, with corresponding camera info.
rgbd_image/compressed (rtabmap_ros/RGBDImage)
  • The compressed RGB-D image topic (images compressed in jpeg). The RGB field is the left image and the depth field is the right image, with corresponding camera info.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~approx_sync (bool, default: "False")
  • Use approximate synchronization for the input topics. If false, the left image, right image and the camera info must have the same timestamp (which should be always the case for stereo images).
~compressed_rate (double, default: 0)
  • Throttling rate at which rgbd_image/compressed topic will be published. 0 means no throttling.

rtabmap_ros/rgbd_relay

A relay for rtabmap_ros/RGBDImage messages. It works like a topic_tools/relay, but can also compress or uncompress data for convenience.

Subscribed Topics

rgbd_image (rtabmap_ros/RGBDImage)
  • RGB-D image input stream.

Published Topics

[rgbd_image]_relay (rtabmap_ros/RGBDImage)
  • RGB-D image output stream.

Parameters

~queue_size (int, default: 10)
  • Size of message queue.
~compress (bool, default: "False")
  • Publish compressed RGB-D image data.
~uncompress (bool, default: "False")
  • Publish uncompressed RGB-D image data.

rtabmap_ros/data_odom_sync

Synchronize odometry with RGB-D images. Useful to correctly show clouds in RVIZ when odometry refresh rate is low comparatively to clouds to show.

Subscribed Topics

odom_in (nav_msgs/Odometry)
  • Odometry stream.
rgb/image_in (sensor_msgs/Image)
  • RGB image stream.
depth/image_in (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info_in (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Published Topics

odom_out (nav_msgs/Odometry)
  • Odometry stream.
rgb/image_out (sensor_msgs/Image)
  • RGB image stream.
depth/image_out (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info_out (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.

rtabmap_ros/data_throttle

Throttle at a specified rate the OpenNI data. See also rtabmap_ros/rgbd_sync, which is now preferred when publishing remotely.

Subscribed Topics

rgb/image_in (sensor_msgs/Image)
  • RGB image stream.
depth/image_in (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info_in (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Published Topics

rgb/image_out (sensor_msgs/Image)
  • RGB image stream.
depth/image_out (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info_out (sensor_msgs/CameraInfo)
  • RGB camera metadata.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~rate (double, default: 0)
  • Maximum frame rate (Hz).
~approx_sync (bool, default: "True")
  • Use approximate synchronization for the input topics. If false, the RGB and depth images and the camera info must have the same timestamp.
~decimation (double, default: 1)
  • Optional decimation of the RGB and depth images (with corresponding modifications in camera_info_out).

rtabmap_ros/stereo_throttle

Throttle at a specified rate the stereo data.

Subscribed Topics

left/image_rect (sensor_msgs/Image)
  • Left RGB/Mono rectified image.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata.
right/image_rect (sensor_msgs/Image)
  • Right Mono rectified image.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata.

Published Topics

[left/image_rect]_throttle (sensor_msgs/Image)
  • Left RGB/Mono rectified image.
[left/camera_info]_throttle (sensor_msgs/CameraInfo)
  • Left camera metadata.
[right/image_rect]_throttle (sensor_msgs/Image)
  • Right Mono rectified image.
[right/camera_info]_throttle (sensor_msgs/CameraInfo)
  • Right camera metadata.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~rate (double, default: 0)
  • Maximum frame rate (Hz).
~approx_sync (bool, default: "false")
  • Use approximate time synchronization of stereo messages. If false, the left/right images and the left/right camera infos must have the same timestamp.
~decimation (double, default: 1)
  • Optional decimation of the left and right images (with corresponding modifications in camera infos).

rtabmap_ros/point_cloud_xyzrgb

Construct a point cloud from RGB and depth images or stereo images. Optional decimation, depth, voxel and noise filtering can be applied.

Subscribed Topics

rgb/image (sensor_msgs/Image)
  • RGB image stream.
depth/image (sensor_msgs/Image)
  • Registered depth image stream.
rgb/camera_info (sensor_msgs/CameraInfo)
  • RGB camera metadata.
left/image (sensor_msgs/Image)
  • Left RGB/Mono rectified image.
left/camera_info (sensor_msgs/CameraInfo)
  • Left camera metadata.
right/image (sensor_msgs/Image)
  • Right Mono rectified image.
right/camera_info (sensor_msgs/CameraInfo)
  • Right camera metadata.

Published Topics

cloud (sensor_msgs/PointCloud2)
  • Generated RGB point cloud.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~approx_sync (bool, default: "true")
  • Use approximate time synchronization of the input topics. If false, the input topics must have the same timestamp (set to "false" for stereo images).
~decimation (int, default: 1)
  • Decimation of the images before creating the point cloud. Set to 1 to not decimate the images.
~voxel_size (double, default: 0.0)
  • Voxel size (m) of the generated cloud. Set 0.0 to deactivate voxel filtering.
~min_depth (double, default: 0.0)
  • Min depth (m) of the generated cloud.
~max_depth (double, default: 0.0)
  • Max depth (m) of the generated cloud. Set 0.0 to deactivate depth filtering.
~noise_filter_radius (double, default: 0.0)
  • Max radius (m) for searching point neighbors. Set 0.0 to deactivate noise filtering.
~noise_filter_min_neighbors (int, default: 5)
  • Minimum neighbors of a point to keep it.
~normal_k (int, default: 0)
  • Compute normals using k nearest neighbors (0=disabled).
~normal_radius (double, default: 0.0)
  • Compute normals using nearest neighbors inside the radius (m) (0=disabled).
~filter_nans (bool, default: "false")
  • Remove NaNs points from output cloud (convert organized to dense point cloud)
~roi_ratios (string, default: "0.0 0.0 0.0 0.0")
  • Region of interest ratios [left, right, top, bottom] (e.g., "0 0 0 0.2" will cut 20% of the bottom of the image).

rtabmap_ros/point_cloud_xyz

Construct a point cloud from a depth or disparity image. Optional decimation, depth, voxel and noise filtering can be applied.

Subscribed Topics

depth/image (sensor_msgs/Image)
  • Depth image stream.
depth/camera_info (sensor_msgs/CameraInfo)
  • Depth camera metadata.
disparity/image (stereo_msgs/DisparityImage)
  • Disparity image stream.
disparity/camera_info (sensor_msgs/CameraInfo)
  • Disparity camera metadata.

Published Topics

cloud (sensor_msgs/PointCloud2)
  • Generated point cloud.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~approx_sync (bool, default: "true")
  • Use approximate time synchronization of messages. If false, the image and camera info must have the same timestamps.
~decimation (int, default: 1)
  • Decimation of the RGB/depth images before creating the point cloud. Set to 1 to not decimate the images.
~voxel_size (double, default: 0.0)
  • Voxel size (m) of the generated cloud. Set 0.0 to deactivate voxel filtering.
~min_depth (double, default: 0.0)
  • Min depth (m) of the generated cloud.
~max_depth (double, default: 0.0)
  • Max depth (m) of the generated cloud. Set 0.0 to deactivate depth filtering.
~noise_filter_radius (double, default: 0.0)
  • Max radius (m) for searching point neighbors. Set 0.0 to deactivate noise filtering.
~noise_filter_min_neighbors (int, default: 5)
  • Minimum neighbors of a point to keep it.
~normal_k (int, default: 0)
  • Compute normals using k nearest neighbors (0=disabled).
~normal_radius (double, default: 0.0)
  • Compute normals using nearest neighbors inside the radius (m) (0=disabled).
~filter_nans (bool, default: "false")
  • Remove NaNs points from output cloud (convert organized to dense point cloud)
~roi_ratios (string, default: "0.0 0.0 0.0 0.0")
  • Region of interest ratios [left, right, top, bottom] (e.g., "0 0 0 0.2" will cut 20% of the bottom of the image).

rtabmap_ros/disparity_to_depth

Convert a disparity image to a depth image.

Subscribed Topics

disparity (stereo_msgs/DisparityImage)
  • Disparity image stream.

Published Topics

depth (sensor_msgs/Image)
  • Depth image stream in m. Format TYPE_32FC1.
depth_raw (sensor_msgs/Image)
  • Depth image stream in mm. Format TYPE_16UC1.

rtabmap_ros/pointcloud_to_depthimage

Reproject a point cloud into a camera frame to create a depth image. When fixed_frame_id is set (e.g., "odom"), movement is taken into account by transforming the point cloud accordingly to camera timestamp. An example of usage of this nodelet can be found in the Tango ROS Streamer tutorial.

Subscribed Topics

camera_info (stereo_msgs/CameraInfo)
  • Camera info in which we want to reproject the points.
cloud (sensor_msgs/PointCloud2)
  • The cloud to reproject in the camera.

Published Topics

image (sensor_msgs/Image)
  • Depth image stream in m. Format TYPE_32FC1.
image_raw (sensor_msgs/Image)
  • Depth image stream in mm. Format TYPE_16UC1.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~fixed_frame_id (string, default: "")
  • This frame should be set when using approximate time synchronization (approx is true). If the robot is moving, it could be "odom". If not moving, it could be "base_link".
~approx (bool, default: "true")
  • Approximate time synchronization.
~wait_for_transform (double, default: 0.1)
  • Wait duration for transform when a tf transform is not still available.
~decimation (int, default: 1)
  • Scale down image size of the camera info received (creating smaller depth image).
~fill_holes_size (int, default: 0)
  • Fill holes of empty pixels up to this size. Values are interpolated from neighbor depth values. 0 means disabled.
~fill_holes_error (double, default: 0.1)
  • Maximum depth error (m) to interpolate.
~fill_iterations (int, default: 1)
  • Number of iterations to fill holes.

rtabmap_ros/point_cloud_assembler

This nodelet can assemble a number of clouds (max_clouds or for a time assembling_time) coming from the same topic, taking into account the displacement of the robot based on fixed_frame_id, then publish the resulting cloud. If fixed_frame_id is set to "" (empty), the nodelet will subscribe to an odom topic that should have the exact same stamp than to input cloud. The output cloud has the same stamp and frame than the last assembled cloud.

Subscribed Topics

cloud (sensor_msgs/PointCloud2)
  • Point cloud topic to assemble.
odom (nav_msgs/Odometry)
  • Odometry topic used to assembled clouds, when fixed_frame_id is not set. Assuming exact synchronization with input cloud.
odom_info (rtabmap_ros/OdometryInfo)
  • Used to assemble only keyframe scans from icp_odometry, when subscribe_odom_info is true. Assuming exact synchronization with input cloud.

Published Topics

assembled_cloud (sensor_msgs/PointCloud2)
  • The assembled cloud.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~fixed_frame_id (string, default: "odom")
  • The fixed frame used to estimate displacement between assembled clouds. If not set, an odometry topic will be required.
~frame_id (string, default: "")
  • Frame id of the output assembled cloud. If not set, same frame id as input cloud is used.
~max_clouds (int, default: 0)
  • The assembled cloud is published after reaching this number of input clouds received. max_clouds or assembling_time should be set.
~assembling_time (double, default: 0)
  • The assembled cloud is published after the assembling time (seconds). max_clouds or assembling_time should be set.
~skip_clouds (int, default: 0)
  • Number of input clouds to skip.
~circular_buffer (bool, default: "false")
  • Instead of accumulating all the clouds before publishing the assembled cloud, the input clouds are kept in a circular buffer (of size max_clouds or a assembling_time) and the assebmled cloud is published every time a new scan is received. When circular_buffer is false, the temporary buffer to accumulate the clouds is cleared after each publishing.
~linear_update (double, default: 0)
  • If displacement between the last cloud and the new cloud received is under this value (meters), the new cloud is skipped. If circular_buffer is enabled, the assembled cloud is still published with the new cloud, but the new cloud is removed from the circular buffer instead of the oldest one. 0 means disabled.
~angular_update (double, default: 0)
  • If rotation between the last cloud and the new cloud received is under this value (rad), the new cloud is skipped. If circular_buffer is enabled, the assembled cloud is still published with the new cloud, but the new cloud is removed from the circular buffer instead of the oldest one. 0 means disabled.
~wait_for_transform_duration (double, default: 0.1)
  • Time to wait to get TF value between fixed frame and cloud frame at the stamp of the input cloud.
~range_min (double, default: 0)
  • Filter input clouds with a minimum range. 0 means disabled.
~range_max (double, default: 0)
  • Filter input clouds with a maximum range. 0 means disabled.
~voxel_size (double, default: 0)
  • Apply voxel filter to output assembled cloud. 0 means disabled.
~noise_radius (double, default: 0)
  • Apply radius outlier filter to output assembled cloud (meters). 0 means disabled.
~noise_min_neighbors (int, default: 5)
  • Apply radius outlier filter to output assembled cloud (minimum number of neighbors of a point in noise_radius to keep it). 0 means disabled, noise_radius should also be set.
~remove_z (bool, default: "false")

rtabmap_ros/point_cloud_aggregator

Nodelet used to merge point clouds from different sensors into a single assembled cloud. If fixed_frame_id is set and approx_sync is true, the clouds are adjusted to include the displacement of the robot in the output cloud.

Subscribed Topics

cloud1 (sensor_msgs/PointCloud2)
  • Point cloud topic to combine.
cloud2 (sensor_msgs/PointCloud2)
  • Second point cloud topic to combine.
cloud3 (sensor_msgs/PointCloud2)
  • Third point cloud topic to combine. Optional, only if count>=3.
cloud4 (sensor_msgs/PointCloud2)
  • Second point cloud topic to combine. Optional, only if count=4.

Published Topics

combined_cloud (sensor_msgs/PointCloud2)
  • The combined cloud.

Parameters

~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~fixed_frame_id (string, default: "")
  • The fixed frame used to estimate displacement between combined clouds. Recommended if approx_sync is true.
~frame_id (string, default: "")
  • Frame id of the output combined cloud. If not set, same frame id as input cloud is used.
~approx_sync (bool, default: "true")
  • Use approximate time policy to synchronize input topics.
~count (int, default: 2)
  • Number of input topics to combine.
~wait_for_transform_duration (double, default: 0.1)
  • Time to wait to get TF value between fixed frame and cloud frame at the stamp of the input cloud.

rtabmap_ros/obstacles_detection

This nodelet extracts obstacles and the ground from a point cloud. The camera must see the ground to work reliably. Since the ground is not even, the ground is segmented by normal filtering: all points with normal in the +z direction (+- fixed angle) are labelled as ground, all the others are labelled as obstacles. The images below show an example.

Warning: this node will use a lot of CPU ressources if the raw point clouds are fed to it directly. A pcl::VoxelGrid can be used to downsample the raw point cloud (e.g. like 5 cm voxel) or rtabmap_ros/point_cloud_xyz nodelet can be used to generate a downsampled cloud from a depth image (e.g. decimating the depth image by 4 before creating a cloud). That filtered point cloud would be fed to obstacles_detection.

obs1

obs2

obs0

obs4

Subscribed Topics

cloud (sensor_msgs/PointCloud2)
  • A point cloud generated from a RGB-D camera or a stereo camera.

Published Topics

ground (sensor_msgs/PointCloud2)
  • The segmented ground.
obstacles (sensor_msgs/PointCloud2)
  • The segmented obstacles.

Parameters

~frame_id (string, default: "base_link")
  • The frame attached to the mobile base.
~queue_size (int, default: 10)
  • Size of message queue for each synchronized topic.
~normal_estimation_radius (double, default: 0.05)
  • Normal estimation radius (m).
~ground_normal_angle (double, default: PI/4)
  • Maximum angle from the +z axis of the point's normal to be labelled as ground.
~min_cluster_size (int, default: 20)
  • Minimum size of the segmented clusters to keep.
~max_obstacles_height (double, default: 0.0)
  • Maximum height of obstacles.

Required tf Transforms

base_link<the frame attached to sensors of incoming data>

RVIZ plugins

Map Cloud Display

MapCloudType.png

This rviz plugin subscribes to /mapData (rtabmap_ros/MapData) topic. A 3D map cloud will be created incrementally in RVIZ. When the graph is changed, all point clouds added in RVIZ will be transformed to new poses. It has the same properties as PointCloud display but with these new ones:

Properties

Name

Description

Valid Values

Default

Cloud decimation

How the input depth and RGB images are decimated before creating the point cloud

[1-16]

4

Cloud max depth (m)

Maximum depth of each point cloud added to map (0 means no maximum)

[0-9999]

4

Cloud voxel size (m)

Voxel size of the generated point clouds (0 means no voxel)

[0-1]

0.01

Filter floor (m)

Maximum height of the floor filtered (disabled=0).

[0-9999]

0

Node filtering radius (m)

Only keep one node in the specified radius (disabled=0).

[0-1]

0.2

Node filtering angle (degrees)

Only keep one node in the specified angle in the filtering radius (disabled=0).

[0-180]

30

Download Map

Download the map from rtabmap node. This may take a while if the map is big, be patient!

.

.

Download Graph

Download the graph from rtabmap node.

.

.

Map Graph Display

This rviz plugin subscribes to /mapGraph (rtabmap_ros/MapGraph) topic. It will show the RTAB-Map's graph with different colors depending on the links' type. It has the same properties as Path display.

Info Display

This rviz plugin subscribes to /info (rtabmap_ros/Info) topic. Information about loop closures detected are shown in the "Status".

Overview

This package is a ROS wrapper of RTAB-Map (Real-Time Appearance-Based Mapping), a RGB-D SLAM approach based on a global loop closure detector with real-time constraints. This package can be used to generate a 3D point clouds of the environment and/or to create a 2D occupancy grid map for navigation. The tutorials and demos show some examples of mapping with RTAB-Map.

Migration Guide New Interface Noetic/ROS2

rtabmap_ros is now a meta package, all nodes were moved into sub packages matching their function. Documentation for each node/nodelet is moved in respective sub packages linked in this table:

Old Name

New Name

rtabmap_ros

rtabmap.launch

rtabmap_launch

rtabmap.launch

rtabmap_ros

rtabmap

rtabmap_slam

rtabmap

rtabmap_ros

rtabmap_odom

rgbd_odometry

rgbd_odometry

stereo_odometry

stereo_odometry

icp_odometry

icp_odometry

rtabmap_ros

rtabmap_sync

rgb_sync

rgb_sync

rgbd_sync

rgbd_sync

stereo_sync

stereo_sync

rtabmap_ros

rtabmap_util

point_cloud_xyz

point_cloud_xyz

point_cloud_xyzrgb

point_cloud_xyzrgb

map_assembler

map_assembler

map_optimizer

map_optimizer

point_cloud_assembler

point_cloud_assembler

point_cloud_aggregator

point_cloud_aggregator

pointcloud_to_depthimage

pointcloud_to_depthimage

disparity_to_depth

disparity_to_depth

obstacles_detection

obstacles_detection

rgbd_relay

rgbd_relay

rtabmap_ros

rtabmap_legacy

data_odom_sync

data_odom_sync

data_throttle

data_throttle

stereo_throttle

stereo_throttle

camera

camera

rtabmap_ros

rtabmapviz

rtabmap_viz

rtabmap_viz

rtabmap_ros

messages

rtabmap_msgs

messages

rtabmap_ros

rviz plugins

rtabmap_rviz_plugins

rviz plugins

rtabmap_ros

costmap plugins

rtabmap_costmap_plugins

costmap plugins

Tutorials

  1. RGB-D Handheld Mapping

    This tutorial shows how to use rtabmap_ros out-of-the-box with a Kinect-like sensor in mapping mode or localization mode.

  2. Stereo Handheld Mapping

    This tutorial shows how to use rtabmap_ros out-of-the-box with a stereo camera in mapping mode or localization mode.

  3. Remote Mapping

    This tutorial shows how to do mapping on a remote computer.

  4. Stereo Outdoor Mapping

    This tutorial shows how to do stereo mapping with RTAB-Map.

  5. Stereo Outdoor Navigation

    This tutorial shows how to integrate autonomous navigation with RTAB-Map in context of outdoor stereo mapping.

  6. Setup RTAB-Map on Your Robot!

    This tutorial shows multiple RTAB-Map configurations that can be used on your robot.

  7. Mapping and Navigation with Turtlebot

    This tutorial shows how to use RTAB-Map with Turtlebot for mapping and navigation.

  8. Tango ROS Streamer

    Tutorial to get Tango ROS Streamer working with rtabmap_ros

  9. Advanced Parameter Tuning

    This tutorial tells you which parameter to change to improve performances

  10. Wifi Signal Strength Mapping (User Data Usage)

    This tutorial shows how to add user data during mapping that will be saved directly in RTAB-Map's database for convenience.

Demos

Robot mapping

For this demo, you will need the ROS bag demo_mapping.bag (295 MB, fixed camera TF 2016/06/28, fixed not normalized quaternions 2017/02/24, fixed compressedDepth encoding format 2020/05/27, fixed odom child_frame_id not set 2021/01/22).

Launch: demo_robot_mapping.launch

  • $ roslaunch rtabmap_demos demo_robot_mapping.launch
    $ rosbag play --clock demo_mapping.bag

After mapping, you could try the localization mode:

  • $ roslaunch rtabmap_demos demo_robot_mapping.launch localization:=true
    $ rosbag play --clock demo_mapping.bag
  • Note that the GUI node doesn't download automatically the map when started. You will need to click "Edit->Download Map" on the GUI to download the map from the core node.

Robot mapping with RVIZ

For this demo, you will need the ROS bag demo_mapping.bag (295 MB, fixed camera TF 2016/06/28, fixed not normalized quaternions 2017/02/24, fixed compressedDepth encoding format 2020/05/27, fixed odom child_frame_id not set 2021/01/22).

Launch: demo_robot_mapping.launch

  • $ roslaunch rtabmap_demos demo_robot_mapping.launch rviz:=true rtabmapviz:=false
    $ rosbag play --clock demo_mapping.bag

Multi-session mapping

Detailed results are shown on the Multi-session page on RTAB-Map's wiki.

For this demo, you will need the ROS bags of five mapping sessions:

For the first launch, you can do "Edit->Delete memory" to make sure that you start from a clean memory. You may need to do this after starting the first bag with "--pause" so that rtabmap node is initialized to avoid a "service /reset cannot be called" error.

Launch: demo_multi-session_mapping.launch

  • $ roslaunch rtabmap_demos demo_multi-session_mapping.launch
    $ rosbag play --clock --pause map1.bag
    $ (...)
    $ rosbag play --clock map2.bag
    $ (...)
    $ rosbag play --clock map3.bag
    $ (...)
    $ rosbag play --clock map4.bag
    $ (...)
    $ rosbag play --clock map5.bag

Robot mapping with Find-Object

Find-Object's ros-pkg find_object_2d should be installed.

ROS Bag: demo_find_object.bag (416 MB)

Launch: demo_find_object.launch

  • $ roslaunch rtabmap_demos demo_find_object.launch
    $ rosbag play --clock demo_find_object.bag

IROS 2014 Kinect Challenge

There is no bag recorded for this demo but how to reproduce this setup is described on the page IROS 2014 Kinect Challenge of the RTAB-Map's wiki.

Stereo mapping

Visit the tutorial StereoOutdoorMapping for detailed information. It is also shown how to create 2D occupancy grid map for navigation.

ROS bags:

Launch : demo_stereo_outdoor.launch

  • $ roslaunch rtabmap_demos demo_stereo_outdoor.launch
    $ rosbag play --clock stereo_outdoorA.bag
    [...]
    $ rosbag play --clock stereo_outdoorB.bag

Stereo navigation

There is no bag recorded for this demo but how to reproduce this setup is described in the tutorial StereoOutdoorNavigation.

Appearance-based loop closure detection-only

Data:

  • samples.zip

    • Set video_or_images_path parameter of camera node in the launch file below accordingly.

Launch: demo_appearance_mapping.launch

  • $ roslaunch rtabmap_demos demo_appearance_mapping.launch

The GUI shows a plenty of information about the loop closures detected. If you only need the ID of the matched past image of a loop closure, you can do that:

  • $ rostopic echo /rtabmap/info/loopClosureId
    6
    ---
    0
    ---
    7
    ---

A "0" means no loop closure detected. This can be also used in localization mode:

  • $ roslaunch rtabmap_demos demo_appearance_mapping.launch localization:=true

For more videos and information about the loop closure detection approach used in RTAB-Map, visit RTAB-Map on IntRoLab.

Wiki: rtabmap_ros (last edited 2023-12-10 04:38:58 by MathieuLabbe)