rtabmap icon indicating copy to clipboard operation
rtabmap copied to clipboard

How does ORB SLAM work in RTABMAP?

Open MrOCW opened this issue 3 years ago • 8 comments

Hi everyone, apologies if this is a stupid question. I am quite new to robotics and trying to pick it up on my own. Just wondering how does ORB SLAM come into the picture with RTABMAP? Does it provide an additional layer for more accuracy? It runs along side the SLAM algorithm that RTABMAP originally uses or will RTABMAP use only ORB SLAM instead for mapping?

MrOCW avatar Apr 03 '21 16:04 MrOCW

In Figure 1 of this paper, you can see the overall modules used in RTAB-Map. ORB-SLAM has been integrated as an Odometry approach inside RTAB-Map (optional). We use it like a blackbox (the front-end), which outputs the pose of the current frame that is fed to RTAB-Map's graph management (back-end). Loop closure detection done by ORB-SLAM is disabled. Loop closure detection and graph optimization are done by RTAB-Map so that we can correctly update the output occupancy grid or OctoMap. Unlike ORB-SLAM, we don't do global bundle adjustment on loop closure, only poses are optimized (we don't track a global feature map). Final results may be less accurate, but optimization can be done faster (and in real-time). Note that in some sequences in KITTI and EuRoC datasets (in the paper), ORB2-RTAB integration scores better than ORB-SLAM2 alone, though theoretically global bundle adjustment would give always better accuracy than only pose-graph optimization. though will always be slower than optimizing only the poses.

Other differences between ORB-SLAM2 integrated in RTAB-Map and standalone ORB-SLAM2:

  • TF supported directly, which means that if the camera is on the head of the robot, if the head moves, the visual odometry won't move as it can be linked to base frame.
  • Occupancy grid generation: occupancy grid map or OctoMap
  • If your environment is too challenging for visual odometry, you can easily switch to another odometry approach (wheel odometry, lidar odometry....) with rtabmap.

matlabbe avatar Apr 03 '21 20:04 matlabbe

@matlabbe do we have ORB_SLAM3 with IMU integrated with RTABMAP now...coz I was seeing one of the updates which said RTABMAP has ORBSLAM3 but without IMU....I am sorry if I got something wrong

sumitsarkar1 avatar Apr 04 '21 16:04 sumitsarkar1

@matlabbe Thanks for the detailed reply! For the benefit of myself and others trying to install RTAB-Map with ORB-SLAM in the future, can I just check if the following steps are correct to install RTAB-Map with ORB-SLAM2 or 3 integration for ROS using RViz (to avoid issues with Qt, VTK, etc)? I am using a Jetson Xavier NX (JetPack 4.4 DP, L4T 32.4.2) with a Realsense D435i camera.

Will simply getting the package from ROS distribution work with ORB-SLAM already?

Otherwise,

Kindly fill in any steps that I have missed

  1. Install ROS
  2. Install your necessary camera libraries
  3. Build or Install via PPA: GTSAM (optional)
  4. Build OpenCV 3+ with contrib and -D OPENCV_ENABLE_NONFREE=1
  5. Build ORB-SLAM2/3 with ROS integration
    • use sudo make install for Pangolin instead of cmake --build . as it causes an error /usr/bin/ld: cannot find -lpangolin collect2: error: ld returned 1 exit status when running catkin_make on rtabmap_ros
  6. Build RTAB-Map from source with
export ORB_SLAM_ROOT_DIR=/home/...../src/ORB_SLAM2/3
git clone https://github.com/introlab/rtabmap.git rtabmap
cd rtabmap/build
cmake .. -DWITH_G2O=OFF -DWITH_Qt=OFF
make
sudo make install
  1. Make sure opencv folder is in /usr/include, Install ROS move-base
cd ~/catkin_ws
git clone https://github.com/introlab/rtabmap_ros.git src/rtabmap_ros
catkin_make -j1

MrOCW avatar Apr 05 '21 03:04 MrOCW

@matlabbe Do you have any suggestions for the other parameter tuning for ORB-SLAM2 + RTAB-Map besides Odom/Strategy 5 and OdomORBSLAM/VocPath ?

MrOCW avatar Apr 12 '21 10:04 MrOCW

In your install instructions, you may add the following patches: ORB-SLAM2: https://gist.github.com/matlabbe/c10403c5d44af85cc3585c0e1c601a60 ORB-SLAM3: https://gist.github.com/matlabbe/d413beb678432f7250de24bb0d3385fb

ORB_SLAM related parameters:

rtabmap --params  | grep ORBSLAM
Param: OdomORBSLAM/Bf = "0.076"                            [Fake IR projector baseline (m) used only when stereo is not used.]
Param: OdomORBSLAM/Fps = "0.0"                             [Camera FPS.]
Param: OdomORBSLAM/MapSize = "3000"                        [Maximum size of the feature map (0 means infinite).]
Param: OdomORBSLAM/MaxFeatures = "1000"                    [Maximum ORB features extracted per frame.]
Param: OdomORBSLAM/ThDepth = "40.0"                        [Close/Far threshold. Baseline times.]
Param: OdomORBSLAM/VocPath = ""                            [Path to ORB vocabulary (*.txt).]

Also some ORB/FAST related parameters are used in ORB implementation used by ORB_SLAM (the ORBextractor parameters that you see in ORB_SLAM2 config files): https://github.com/introlab/rtabmap/blob/6449302318eef03d52974e5ba6d4165ced498d5c/corelib/src/odometry/OdometryORBSLAM.cpp#L746-L768

matlabbe avatar May 04 '21 01:05 matlabbe

@matlabbe may I know the implications of the -march = native? I am able to run ORB2-RTab even with ORB-SLAM2 compiled with -march = native

MrOCW avatar May 04 '21 09:05 MrOCW

If you can, great! In my experience, I had often problems (rtabmap doing a Segmentation Fault on start) when g2o, gtsam, pcl were not compiled all with or without "-march=native". This flag is related to Eigen.

matlabbe avatar May 04 '21 17:05 matlabbe

Hi, I'm going to implement ORB_slam2 or 3 with rtabmap, are still needed the parches with the most recent rtabmap releases? I have now 0.2.14/15 in ros1/2 I think

FPSychotic avatar Dec 26 '21 18:12 FPSychotic