# RTAB-Map SLAM Node

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
with dai.Pipeline() as pipeline:
    slam = pipeline.create(dai.node.RTABMapSLAM)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto slam = pipeline.create<dai::node::RTABMapSLAM>();
```

## Inputs and Outputs

## Usage

#### Python

```python
with dai.Pipeline() as pipeline:
    stereo = pipeline.create(dai.node.StereoDepth)
    odom = pipeline.create(dai.node.BasaltVIO)
    slam = pipeline.create(dai.node.RTABMapSLAM)

    slam.setParams({
        "RGBD/CreateOccupancyGrid": "true",
        "Grid/3D": "true",
    })
    slam.setFreq(1.0)

    odom.transform.link(slam.odom)
    stereo.rectifiedLeft.link(slam.rect)
    stereo.depth.link(slam.depth)

    # Optional when tracked features are available:
    # slam.setUseFeatures(True)
    # featureTracker.outputFeatures.link(slam.features)
```

#### C++

```cpp
dai::Pipeline pipeline;
auto stereo = pipeline.create<dai::node::StereoDepth>();
auto odom = pipeline.create<dai::node::BasaltVIO>();
auto slam = pipeline.create<dai::node::RTABMapSLAM>();

slam->setParams({
    {"RGBD/CreateOccupancyGrid", "true"},
    {"Grid/3D", "true"},
});
slam->setFreq(1.0f);

odom->transform.link(slam->odom);
stereo->rectifiedLeft.link(slam->rect);
stereo->depth.link(slam->depth);

// Optional when tracked features are available:
// slam->setUseFeatures(true);
// featureTracker->outputFeatures.link(slam->features);
```

## Examples of functionality

 * [RTAB-Map VIO SLAM](https://docs.luxonis.com/software-v3/depthai/examples/rvc2/vslam/rtab_map_vio_slam.md)
 * [RTAB-Map VIO](https://docs.luxonis.com/software-v3/depthai/examples/rvc2/vslam/rtab_map_vio.md)

## Reference

### dai::node::RTABMapSLAM

Kind: class

RTABMap SLAM node. Performs SLAM on given odometry pose, rectified frame and depth frame.

#### Subnode < node::Sync > sync

Kind: variable

#### InputMap & inputs

Kind: variable

#### std::string rectInputName

Kind: variable

#### std::string depthInputName

Kind: variable

#### std::string featuresInputName

Kind: variable

#### Input & rect

Kind: variable

Input rectified image on which SLAM is performed.

#### Input & depth

Kind: variable

Input depth image on which SLAM is performed.

#### Input features

Kind: variable

Input tracked features on which SLAM is performed (optional).

#### Input odom

Kind: variable

Input odometry pose.

#### Output transform

Kind: variable

Output transform.

#### Output odomCorrection

Kind: variable

Output odometry correction (map to odom).

#### Output obstaclePCL

Kind: variable

Output obstacle point cloud.

#### Output groundPCL

Kind: variable

Output ground point cloud.

#### Output occupancyGridMap

Kind: variable

Output occupancy grid map.

#### Output passthroughRect

Kind: variable

Output passthrough rectified image.

#### Output passthroughDepth

Kind: variable

Output passthrough depth image.

#### Output passthroughFeatures

Kind: variable

Output passthrough features.

#### Output passthroughOdom

Kind: variable

Output passthrough odometry pose.

#### RTABMapSLAM()

Kind: function

#### ~RTABMapSLAM()

Kind: function

#### void setParams(const std::map< std::string, std::string > & params)

Kind: function

Set RTABMap parameters. For the list of all parameters visit

#### void setDatabasePath(const std::string & path)

Kind: function

Set RTABMap database path. "/tmp/rtabmap.tmp.db" by default.

#### void setLoadDatabaseOnStart(bool load)

Kind: function

Whether to load the database on start. False by default.

#### void setSaveDatabaseOnClose(bool save)

Kind: function

Whether to save the database on close. False by default.

#### void saveDatabase()

Kind: function

#### void setSaveDatabasePeriodically(bool save)

Kind: function

Whether to save the database periodically. False by default.

#### void setSaveDatabasePeriod(double interval)

Kind: function

Set the interval at which the database is saved. 30.0s by default.

#### void setPublishObstacleCloud(bool publish)

Kind: function

Whether to publish the obstacle point cloud. True by default.

#### void setPublishGroundCloud(bool publish)

Kind: function

Whether to publish the ground point cloud. True by default.

#### void setPublishGrid(bool publish)

Kind: function

Whether to publish the ground point cloud. True by default.

#### void setFreq(float f)

Kind: function

Set the frequency at which the node processes data. 1Hz by default.

#### void setAlphaScaling(float alpha)

Kind: function

Set the alpha scaling factor for the camera model.

#### void setUseFeatures(bool use)

Kind: function

Whether to use input features for SLAM. False by default.

#### void setLocalTransform(std::shared_ptr< TransformData > transform)

Kind: function

#### std::shared_ptr< TransformData > getLocalTransform()

Kind: function

#### void triggerNewMap()

Kind: function

Trigger a new map.

#### void buildInternal()

Kind: function

Function called from within the

### Need assistance?

Head over to [Discussion Forum](https://discuss.luxonis.com/) for technical support or any other questions you might have.
