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

Rtabmap with Multiple RealSense ZR300 cameras

asked 2017-09-22 05:17:46 -0500

Cole gravatar image

updated 2017-09-22 05:20:12 -0500

Hi all,

I am wondering how can I run Rtabmap for mapping using two RealSense ZR300 cameras on ROS platform. It can run with the standalone Rtabmap using single camera, but when it comes to two cameras, I do not know how to write the launch file. Can anyone provide with some hints? Thanks a lot.

edit retag flag offensive close merge delete

Comments

Here is a demo launch file for rtabmapping with 2 kinects. It may help you-, rtabmap supports currently not more than 2 rgbd cameras.

bvbdort gravatar image bvbdort  ( 2017-09-22 05:25:47 -0500 )edit

1 Answer

Sort by » oldest newest most voted
0

answered 2017-09-27 15:37:22 -0500

matlabbe gravatar image

I could not test with two cameras as I have only one, but the launch file would look like below, based on this tutorial for ZR300 and the referred demo launch file for kinect2:

<launch>

  <!-- Multi-cameras demo with 2 ZR300 -->

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

  <!-- Cameras -->
  <include file="$(find realsense_camera)/launch/zr300_nodelet_rgdb.launch">
    <arg name="camera" value="camera1" />
    <arg name="serial_no" value="1111111111" />
  </include>

  <include file="$(find realsense_camera)/launch/zr300_nodelet_rgdb.launch">
    <arg name="camera" value="camera2" />
    <arg name="serial_no" value="2222222222" />
  </include>

  <!-- Frames: Cameras are placed at 90 degrees, clockwise -->
  <node pkg="tf" type="static_transform_publisher" name="base_to_camera1_tf"
      args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /camera1_link 100" />
  <node pkg="tf" type="static_transform_publisher" name="base_to_camera2_tf"
      args="-0.1325 -0.1975 0.0 -1.570796327 0.0 0.0 /base_link /camera2_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="pointcloud_to_depthimage1" args="load rtabmap_ros/pointcloud_to_depthimage nodelet_manager1">
      <remap from="cloud"           to="depth/points"/>           <!-- input -->
      <remap from="camera_info"     to="rgb/camera_info"/>        <!-- input -->
      <remap from="image_raw"       to="depth/points/image_raw"/> <!-- output 16bits -->
      <remap from="image"           to="depth/points/image"/>     <!-- output 32bits -->
      <param name="approx"          value="false"/>
      <param name="fill_holes_size" value="2"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="rgbd_sync1" args="load rtabmap_ros/rgbd_sync nodelet_manager1">
      <remap from="rgb/image"       to="rgb/image_rect_color"/>
      <remap from="depth/image"     to="depth/points/image_raw"/>
      <remap from="rgb/camera_info" to="rgb/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="pointcloud_to_depthimage2" args="load rtabmap_ros/pointcloud_to_depthimage nodelet_manager2">
      <remap from="cloud"           to="depth/points"/>           <!-- input -->
      <remap from="camera_info"     to="rgb/camera_info"/>        <!-- input -->
      <remap from="image_raw"       to="depth/points/image_raw"/> <!-- output 16bits -->
      <remap from="image"           to="depth/points/image"/>     <!-- output 32bits -->
      <param name="approx"          value="false"/>
      <param name="fill_holes_size" value="2"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="rgbd_sync2" args="load rtabmap_ros/rgbd_sync nodelet_manager2">
      <remap from="rgb/image"       to="rgb/image_rect_color"/>
      <remap from="depth/image"     to="depth/points/image_raw"/>
      <remap from="rgb/camera_info" to="rgb/camera_info"/>
      <param name="approx"          value="false"/>
    </node>
   </group>

  <group ns="rtabmap">

    <!-- Odometry -->
    <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
      <remap from="rgbd_image0"       to="/camera1/rgbd_image"/>
      <remap from="rgbd_image1"       to="/camera2/rgbd_image"/>

      <param name="subscribe_rgbd"           type="bool"   value="true"/>
      <param name="frame_id"                 type="string" value="base_link"/>
      <param name="rgbd_cameras"             type="int"    value="2"/>
      <param name="Vis/EstimationType"       type="string" value="0"/> <!-- should be 0 for multi-cameras -->
    </node>

    <!-- Visual SLAM (robot side) -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
      <param name="subscribe_depth"  type="bool"   value="false"/>
      <param name="subscribe_rgbd"   type="bool"   value="true"/>
      <param name="rgbd_cameras"     type="int"    value="2"/>
      <param name="frame_id"         type="string" value="base_link"/>
      <param name="gen_scan"         type="bool"   value="true"/>
      <param name="map_negative_poses_ignored" type="bool"   value="false"/>        <!-- refresh grid map even if we are not moving-->
      <param name="map_negative_scan_empty_ray_tracing" type="bool ...
(more)
edit flag offensive delete link more

Comments

Hi Mathieu,

I know, it has been a while since this post was created, but today, I'm facing the same issue.

I would like to perform V-SLAM mapping thanks to RTAB-MAP, with two D435 cameras. I tried to adapt the code you posted just above, but nothing happens in RTAB-MAP. Maybe the code is not adapted to the new versions of RTAB-MAP?

I precise that everything is working well with only one D435 camera (with the rs-rgbd.launch file).

Many thanks for your help,

Cheers,

Thibaud

thibs-sigma gravatar image thibs-sigma  ( 2019-03-19 11:16:31 -0500 )edit

You may post a new question with the detailed launch file you use. For realsense2, you may not use rtabmap_ros/pointcloud_to_depthimage nodelets for example, as you can have the depth directly. the rest is remapping the correct image topics to rgbd_sync nodelets, and maybe change the frame_id used.

matlabbe gravatar image matlabbe  ( 2019-03-22 21:30:45 -0500 )edit

I am sorry about that... But thanks, just as you said, remapping and avoiding the use of nodelets, I succeeded in launching mapping with two D435 cameras.

thibs-sigma gravatar image thibs-sigma  ( 2019-03-25 04:47:44 -0500 )edit

Hey Thibs-sigma, I am pretty much trying to accomplish the exact same thing as you. Could you maybe post your remapped file for the D435 cameras somewhere. I'm having trouble remapping myself and this would help me a ton!

Corey_Cazes gravatar image Corey_Cazes  ( 2019-04-09 11:56:04 -0500 )edit

Hi Corey Cazes, You can find my launch file working with 3 D435 here. Cheers, Thibaud

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

The link doesn't seem to be working

Corey_Cazes gravatar image Corey_Cazes  ( 2019-04-10 11:59:26 -0500 )edit
1

Sorry, you can actually found it here ;) Hope this will help you.

thibs-sigma gravatar image thibs-sigma  ( 2019-04-11 02:56:05 -0500 )edit

Hi thibs-sigma,Can the"/home/thib/realsenseTests_ws/src/hw_sync/launch/hw_sync.launch" synchronize 3 d435 in your launch file working with 3 d435?Did you write the launch file yourself?I would appreciate it if you could provide me with this launch file.

garand gravatar image garand  ( 2019-06-19 22:57:35 -0500 )edit

Question Tools

Stats

Asked: 2017-09-22 05:17:46 -0500

Seen: 1,552 times

Last updated: Sep 27 '17