ON THIS PAGE

  • How to place it
  • Inputs and Outputs
  • Usage
  • Examples of functionality
  • Reference

RTAB-Map SLAM Node

Supported on:RVC2
RTABMapSLAM host node is used for host-side SLAM with RTAB-Map. It takes a rectified image, depth image, and upstream odometry as inputs, and outputs corrected transforms together with mapping data such as occupancy grids and point clouds. It can also optionally consume tracked features.

How to place it

Python

Python
1with dai.Pipeline() as pipeline:
2    slam = pipeline.create(dai.node.RTABMapSLAM)

C++

C++
1dai::Pipeline pipeline;
2auto slam = pipeline.create<dai::node::RTABMapSLAM>();

Inputs and Outputs

Usage

Python

Python
1with dai.Pipeline() as pipeline:
2    stereo = pipeline.create(dai.node.StereoDepth)
3    odom = pipeline.create(dai.node.BasaltVIO)
4    slam = pipeline.create(dai.node.RTABMapSLAM)
5
6    slam.setParams({
7        "RGBD/CreateOccupancyGrid": "true",
8        "Grid/3D": "true",
9    })
10    slam.setFreq(1.0)
11
12    odom.transform.link(slam.odom)
13    stereo.rectifiedLeft.link(slam.rect)
14    stereo.depth.link(slam.depth)
15
16    # Optional when tracked features are available:
17    # slam.setUseFeatures(True)
18    # featureTracker.outputFeatures.link(slam.features)

C++

C++
1dai::Pipeline pipeline;
2auto stereo = pipeline.create<dai::node::StereoDepth>();
3auto odom = pipeline.create<dai::node::BasaltVIO>();
4auto slam = pipeline.create<dai::node::RTABMapSLAM>();
5
6slam->setParams({
7    {"RGBD/CreateOccupancyGrid", "true"},
8    {"Grid/3D", "true"},
9});
10slam->setFreq(1.0f);
11
12odom->transform.link(slam->odom);
13stereo->rectifiedLeft.link(slam->rect);
14stereo->depth.link(slam->depth);
15
16// Optional when tracked features are available:
17// slam->setUseFeatures(true);
18// featureTracker->outputFeatures.link(slam->features);

Examples of functionality

Reference

class

dai::node::RTABMapSLAM

#include RTABMapSLAM.hpp
variable
variable
InputMap & inputs
variable
std::string rectInputName
variable
std::string depthInputName
variable
std::string featuresInputName
variable
Input & rect
Input rectified image on which SLAM is performed.
variable
Input & depth
Input depth image on which SLAM is performed.
variable
Input features
Input tracked features on which SLAM is performed (optional).
variable
Input odom
Input odometry pose.
variable
Output transform
Output transform.
variable
Output odomCorrection
Output odometry correction (map to odom).
variable
Output obstaclePCL
Output obstacle point cloud.
variable
Output groundPCL
Output ground point cloud.
variable
Output occupancyGridMap
Output occupancy grid map.
variable
Output passthroughRect
Output passthrough rectified image.
variable
Output passthroughDepth
Output passthrough depth image.
variable
Output passthroughFeatures
Output passthrough features.
variable
Output passthroughOdom
Output passthrough odometry pose.
function
RTABMapSLAM()
function
~RTABMapSLAM()
function
void setParams(const std::map< std::string, std::string > & params)
Set RTABMap parameters. For the list of all parameters visit
inline function
void setDatabasePath(const std::string & path)
Set RTABMap database path. "/tmp/rtabmap.tmp.db" by default.
inline function
void setLoadDatabaseOnStart(bool load)
Whether to load the database on start. False by default.
inline function
void setSaveDatabaseOnClose(bool save)
Whether to save the database on close. False by default.
function
void saveDatabase()
inline function
void setSaveDatabasePeriodically(bool save)
Whether to save the database periodically. False by default.
inline function
void setSaveDatabasePeriod(double interval)
Set the interval at which the database is saved. 30.0s by default.
function
void setPublishObstacleCloud(bool publish)
Whether to publish the obstacle point cloud. True by default.
function
void setPublishGroundCloud(bool publish)
Whether to publish the ground point cloud. True by default.
function
void setPublishGrid(bool publish)
Whether to publish the ground point cloud. True by default.
inline function
void setFreq(float f)
Set the frequency at which the node processes data. 1Hz by default.
inline function
void setAlphaScaling(float alpha)
Set the alpha scaling factor for the camera model.
function
void setUseFeatures(bool use)
Whether to use input features for SLAM. False by default.
function
void setLocalTransform(std::shared_ptr< TransformData > transform)
function
std::shared_ptr< TransformData > getLocalTransform()
function
void triggerNewMap()
Trigger a new map.
function
void buildInternal()

Need assistance?

Head over to Discussion Forum for technical support or any other questions you might have.