ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

Use RTAB-Map with ORB_SLAM2 in ROS

asked 2019-03-18 07:17:03 -0500

eMrazSVK gravatar image

Hello everyone,

I successfully compiled RTAB-Map with Orb-Slam2, so I can now choose ORB-SLAM2 as an odometry strategy in RTAB-Map standalone app. Now I would like to use it inside ROS. I guess that maybe it is not implemented yet? Logically, I would expect it to be one of the parameters in rgbd_odometry node. But there is nothing like it in documentation. Or maybe I am wrong and it exists somewhere and I do not know where...

What do you recommend then? Should I launch orb slam 2 in ros and get odometry from tf, which is published by orbslam2 node and use it in rtabmap? Kind of a puzzle for me.

Thank you for any help!

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2019-03-22 20:24:19 -0500

matlabbe gravatar image

If you have successfully built ORB_SLAM2 inside RTAB-Map library and that you could use it with the standalone, you should be also able to use it in ROS through rtabmap_ros/rgbd_odometry and rtabmap_ros/stereo_odometry nodes. Just set Odom/Strategy to 5 and set ORB_SLAM2 vocabulary path with OdomORBSLAM2/VocPath:

<node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry">
   ...
   <param name="Odom/Strategy" value="5"/>
   <param name="OdomORBSLAM2/VocPath" value="PATH/TO/ORB_SLAM2/Vocabulary/ORBvoc.txt"/>
</node>

To see more parameters related to ORB_SLAM2 in RTAB-Map, see here or do

$ rtabmap --params | grep ORBSLAM2

cheers,
Mathieu

edit flag offensive delete link more
0

answered 2019-04-05 05:10:56 -0500

thibs-sigma gravatar image

updated 2019-04-05 06:23:52 -0500

Hi everyone,

I'm trying to launch RTAB-MAP with ORB-SLAM2 in ROS too. The compilation with ORB-SLAM2 went well, I can launch it with the standalone app, and then I followed your answer, Mathieu, by adding these lines in my launch file. However, I get the following error when RTAB-MAP pops up on screen :

OdometryORBSLAM2.cpp:874::computeTransform() Invalid camera model!

And indeed, no Camera Parameters pass through the launch file, and I don't know how to pass it through ROS.

I also recompiled the rtabmap-ros workspace with ORB-SLAM2.


Standalone : rtabmap --Rtabmap/DetectionRate 2 --ORB/Gpu True --Odom/Strategy 5 --OdomORBSLAM2/VocPath /home/thib/ORB_SLAM2/Vocabulary/ORBvoc.txt

Camera Parameters: 
- fx: 614.703
- fy: 614.971
- cx: 322.49
- cy: 246.067
- k1: 0
- k2: 0
- p1: 0
- p2: 0
- fps: 30
- color order: RGB (ignored if grayscale)

ORB Extractor Parameters: 
- Number of Features: 1000
- Scale Levels: 8
- Scale Factor: 1.2
- Initial Fast Threshold: 20
- Minimum Fast Threshold: 7

Launch file :

<launch>

  <!-- Multi-cameras demo with 3 D435 -->

  <!-- Choose visualization -->
  <arg name="rviz"       default="false" />
  <arg name="rtabmapviz" default="true" /> 

  <!-- Enable HW Sync via RS2 API -->
  <!-- <arg name="hw_sync" default="false"/>
  <group if="$(arg hw_sync)">
    <include file="/home/thib/realsenseTests_ws/src/hw_sync/launch/hw_sync.launch" />
  </group> -->

  <!-- Cameras -->
  <include file="$(find realsense2_camera)/launch/rs_rgbd.launch">
    <arg name="camera" value="camera1" />
    <arg name="serial_no" value="829212071075" />
  </include>

  <include file="$(find realsense2_camera)/launch/rs_rgbd.launch">
    <arg name="camera" value="camera2" />
    <arg name="serial_no" value="828112072892" />
  </include>

  <include file="$(find realsense2_camera)/launch/rs_rgbd.launch">
    <arg name="camera" value="camera3" />
    <arg name="serial_no" value="828112072458" />
  </include>

  <!-- Frames: Cameras are placed on the Intel x6 RS mounting support -->
  <!-- Use quaternions for static TF, corresponding on mounting on Intel x6 RS mounting support -->
  <node pkg="tf" type="static_transform_publisher" name="base_to_camera1_tf"
      args="0.0
            0.0 
            0.0 
            0.707 
            0.0 
            0.0 
            0.707 
            /base_link 
            /camera1_link 
            100" /> 
  <node pkg="tf" type="static_transform_publisher" name="base_to_camera2_tf"
      args="0.0 
            0.0 
            0.0 
            0.612 
            0.354 
            0.354 
            0.612 
            /base_link 
            /camera2_link 
            100" />
  <node pkg="tf" type="static_transform_publisher" name="base_to_camera3_tf"
      args="0.0 
            0.0 
            0.0 
            0.354 
            0.612 
            0.612 
            0.354 
            /base_link 
            /camera3_link 
            100" />

   <!-- sync rgb/depth images per camera -->
  <group ns="camera1">
    <node pkg="nodelet" type="nodelet" name="nodelet_manager1" args="manager"/>
    <node pkg="nodelet" type="nodelet" name="rgbd_sync1" args="load rtabmap_ros/rgbd_sync nodelet_manager1">
      <remap from="rgb/image"       to="color/image_rect_color"/>
      <remap from="depth/image"     to="aligned_depth_to_color/image_raw"/>
      <remap from="rgb/camera_info" to="color/camera_info"/>
      <param name="approx"          value="false"/>
    </node>
  </group>

  <group ns="camera2">
    <node pkg="nodelet" type="nodelet" name="nodelet_manager2" args="manager"/>
    <node pkg="nodelet" type="nodelet" name="rgbd_sync2" args="load rtabmap_ros/rgbd_sync nodelet_manager2">
      <remap from="rgb/image"       to="color/image_rect_color"/>
      <remap from="depth/image"     to="aligned_depth_to_color/image_raw"/>
      <remap from="rgb/camera_info" to="color/camera_info"/>
      <param name="approx"          value="false"/>
    </node>
  </group>

  <group ns="camera3">
    <node pkg="nodelet" type="nodelet" name="nodelet_manager3" args="manager"/>
    <node pkg="nodelet" type="nodelet" name="rgbd_sync3" args="load rtabmap_ros/rgbd_sync nodelet_manager3">
      <remap from="rgb/image ...
(more)
edit flag offensive delete link more

Comments

You would have been better to post a new question referring this one. Referring to this line from which the error is coming from, ORB_SLAM2 integration in RTAB-Map supports only one camera. For rgbd_odometry, set rgbd_cameras to 1 and use one camera with <remap from="rgbd_image" to="/camera1/rgbd_image"/>. For rtabmap node, you should be able to use all cameras. For info, the camera calibration is not coming from a config file, it is used directly from the camera_info topics.

matlabbe gravatar image matlabbe  ( 2019-04-09 22:35:15 -0500 )edit

Thank you for your precious help Mathieu! Indeed, it works with 1 camera. However, isn't there a workaround for making it work with 3 cameras (by modifing the script you refer me to)? Or is it just impossible for the moment with that implementation of ORB_SLAM2 with RTAB-Map? Cheers, Thibaud

thibs-sigma gravatar image thibs-sigma  ( 2019-04-10 04:03:41 -0500 )edit

I don't think ORB_SLAM2 supports more than one camera, so it is not possible even integrated with RTAB-Map.

matlabbe gravatar image matlabbe  ( 2019-04-12 20:57:24 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-03-18 07:17:03 -0500

Seen: 2,062 times

Last updated: Apr 05 '19