Re: RTABMAP to be integrated for two ZED2i cameras

Posted by matlabbe on
URL: http://official-rtab-map-forum.206.s1.nabble.com/RTABMAP-to-be-integrated-for-two-ZED2i-cameras-tp8976p8997.html

Hi,

what you experienced is normal. To use rtabmap.launch directly, you should remap the input topics to those from zed wrapper. You can look at the stereo example here or the RGB-D example here, following the zed instructions.

When you type "rtabmap" in terminal, you will open the standalone version of rtabmap (without ros). If the ros binaries are used, most camera drivers are not available as we assume that you will be using the camera ros drivers, which are outside rtabmap. If you are interested to use zed sdk driver inside the standalone version, you should rebuild rtabmap library from source (cmake should be able to find zed sdk if installed). However the standalone cannot open stream from 2 cameras, you still have to use the ros package.

I don't have official examples with two zed cameras, but we could make one based on this launch file and example from there. You will the need latest version of rtabmap_ros to work with the examples below as I just implemented the correct multi-camera callback for rgbd_odometry. It can work like the kinect demo above, but there could be synchronization issues between the odom and rtabmap nodes.

Here is a launch file working with two zeds (demo_two_zeds.launch):

<!-- -->
<launch>
   
  <!-- Multi-cameras demo with 2 zed cameras -->
  
  <!-- Choose visualization -->
  <arg name="rviz"       default="false" />
  <arg name="rtabmapviz" default="true" /> 
  
  <!-- Set to false to use just one of the cameras for odometry
       Set to 0 to use both cameras for odometry. -->
  <arg name="multicamera_odom" default="true"/>
   
  <!-- Cameras -->
  <param name="/zed1_node/depth_confidence" value="100"/>
  <param name="/zed1_node/depth_texture_conf" value="90"/>
  <include file="$(find zed_wrapper)/launch/zed_no_tf.launch">
    <arg name="camera_name"  value="zed1" />
    <arg name="node_name"    value="zed1_node" />
    <arg name="camera_model" value="zed2i" /> <!-- 'zed' or 'zedm' or 'zed2' or 'zed2i' -->
    <arg name="camera_id"    value="0" />
  </include>

  <param name="/zed2_node/depth_confidence" value="100"/>
  <param name="/zed2_node/depth_texture_conf" value="90"/>
  <include file="$(find zed_wrapper)/launch/zed_no_tf.launch">
    <arg name="camera_name"  value="zed2" />
    <arg name="node_name"    value="zed2_node" />
    <arg name="camera_model" value="zed2i" /> <!-- 'zed' or 'zedm' or 'zed2' or 'zed2i' -->
    <arg name="camera_id"    value="1" />
    
    <!-- Frames: Cameras are placed back to back -->
    <arg name="cam_pos_x" default="-0.06" />
    <arg name="cam_yaw"   default="3.14159265359" />
  </include>
      
  <!-- exact sync rgb/depth images per camera -->
  <group ns="camera1">
   <node pkg="rtabmap_ros" type="rgbd_sync" name="rgbd_sync1">
     <remap from="rgb/image"       to="/zed1_node/rgb/image_rect_color"/>
     <remap from="depth/image"     to="/zed1_node/depth/depth_registered"/>
     <remap from="rgb/camera_info" to="/zed1_node/rgb/camera_info"/>
     <param name="approx_sync"     value="false"/>
   </node>
  </group>
  <group ns="camera2">
   <node pkg="rtabmap_ros" type="rgbd_sync" name="rgbd_sync2">
     <remap from="rgb/image"       to="/zed2_node/rgb/image_rect_color"/>
     <remap from="depth/image"     to="/zed2_node/depth/depth_registered"/>
     <remap from="rgb/camera_info" to="/zed2_node/rgb/camera_info"/>
     <param name="approx_sync"     value="false"/>
   </node>
  </group>
           
  <group ns="rtabmap">
  
    <!-- approx sync cameras together -->
    <node pkg="rtabmap_ros" type="rgbdx_sync" name="rgbdx_sync">
      <remap from="rgbd_image0"  to="/camera1/rgbd_image"/>
      <remap from="rgbd_image1"  to="/camera2/rgbd_image"/>
      <param name="rgbd_cameras" type="int"  value="2"/>  
      <param name="approx_sync"  type="bool" value="true"/>
    </node>
  
    <!-- Odometry -->
    <node pkg="rtabmap_ros" type="rgbd_odometry" name="rgbd_odometry" output="screen">
      <remap from="rgbd_image"  to="/camera1/rgbd_image"/> <!-- for single camera odom, see below -->
      <remap from="rgbd_images" to="rgbd_images"/>         <!-- for multi-camera odom, see below -->
      <remap from="imu"         to="/zed1_node/imu/data"/>
	  
	  <param name="subscribe_rgbd" type="bool"   value="true"/>
	  <param name="frame_id"       type="string" value="base_link"/>
	  <param name="wait_imu_to_init" type="bool" value="true"/> <!-- set to false for "zed" camera model -->
 
	  <param     if="$(arg multicamera_odom)" name="rgbd_cameras" type="int" value="0"/>
	  <param unless="$(arg multicamera_odom)" name="rgbd_cameras" type="int" value="1"/>
	  <!-- Multi-camera required odometry parameters -->
	  <param if="$(arg multicamera_odom)" name="OdomF2M/BundleAdjustment" type="string" value="0"/>
	  <param if="$(arg multicamera_odom)" name="Vis/EstimationType"       type="string" value="0"/> 
	  <param if="$(arg multicamera_odom)" name="Vis/CorGuessWinSize"      type="string" value="0"/>
    </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="0"/> <!-- 0 to use rgbd_images input -->
	  <param name="frame_id"         type="string" value="base_link"/>
	  <param name="approx_symc"      type="bool"   value="false"/>

      <param name="Vis/EstimationType" type="string" value="0"/> <!-- should be 0 for multi-cameras -->
      
      <remap from="imu" to="/zed1_node/imu/data"/>
    </node>
  
    <!-- Visualisation RTAB-Map -->
    <node if="$(arg rtabmapviz)" pkg="rtabmap_ros" type="rtabmapviz" name="rtabmapviz" args="-d $(find rtabmap_ros)/launch/config/rgbd_gui.ini" output="screen">
      <param name="subscribe_depth"     type="bool"   value="false"/>
      <param name="subscribe_rgbd"      type="bool"   value="true"/>
      <param name="subscribe_odom_info" type="bool"   value="true"/>
      <param name="frame_id"            type="string" value="base_link"/>
      <param     if="$(arg multicamera_odom)" name="rgbd_cameras" type="int" value="0"/>
	  <param unless="$(arg multicamera_odom)" name="rgbd_cameras" type="int" value="1"/>
      <param name="approx_symc"         type="bool"   value="false"/>
      
      <remap unless="$(arg multicamera_odom)" from="rgbd_image"  to="/camera1/rgbd_image"/>
    </node>
  
  </group>
  
  <!-- Visualization RVIZ -->
  <node if="$(arg rviz)" pkg="rviz" type="rviz" name="rviz" args="-d $(find rtabmap_ros)/launch/config/rgbd.rviz"/>

</launch>

Note however that we have to patch zed_no_tf.launch file to correctly use it with two cameras (multicamera.patch):

diff --git a/zed_wrapper/launch/zed_no_tf.launch b/zed_wrapper/launch/zed_no_tf.launch
index c6514e7..02832ed 100644
--- a/zed_wrapper/launch/zed_no_tf.launch
+++ b/zed_wrapper/launch/zed_no_tf.launch
@@ -48,7 +48,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
 
     <!-- ROS URDF description of the ZED -->
     <group if="$(arg publish_urdf)">
-        <param name="zed_description"
+        <param name="$(arg node_name)_description"
                command="$(find xacro)/xacro '$(find zed_wrapper)/urdf/zed_descr.urdf.xacro'
                         camera_name:=$(arg camera_name)
                         camera_model:=$(arg camera_model)
@@ -61,8 +61,8 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
                         cam_yaw:=$(arg cam_yaw)"
         />
 
-        <node name="zed_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" required="true">
-            <remap from="robot_description" to="zed_description" />
+        <node name="$(arg node_name)_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" required="true">
+            <remap from="robot_description" to="$(arg node_name)_description" />
         </node>
     </group>
 
diff --git a/zed_wrapper/params/common.yaml b/zed_wrapper/params/common.yaml
index 1088e09..e44e9f0 100644
--- a/zed_wrapper/params/common.yaml
+++ b/zed_wrapper/params/common.yaml
@@ -23,7 +23,7 @@ general:
     camera_name:                zed                             # A name for the camera (can be different from camera model and node name and can be overwritten by the launch file)
     zed_id:                     0
     serial_number:              0
-    resolution:                 2                               # '0': HD2K, '1': HD1080, '2': HD720, '3': VGA
+    resolution:                 3                               # '0': HD2K, '1': HD1080, '2': HD720, '3': VGA
     grab_frame_rate:            15                              # Frequency of frame grabbing for internal SDK operations
     gpu_id:                     -1
     base_frame:                 'base_link'                     # must be equal to the frame_id used in the URDF file
@@ -37,7 +37,7 @@ video:
     extrinsic_in_camera_frame:  true                            # if `false` extrinsic parameter in `camera_info` will use ROS native frame (X FORWARD, Z UP) instead of the camera frame (Z FORWARD, Y DOWN) [`true` use old behavior as for version < v3.1]
 
 depth:
-    quality:                    4                               # '0': NONE, '1': PERFORMANCE, '2': QUALITY, '3': ULTRA, '4': NEURAL
+    quality:                    1                               # '0': NONE, '1': PERFORMANCE, '2': QUALITY, '3': ULTRA, '4': NEURAL
     sensing_mode:               0                               # '0': STANDARD, '1': FILL (not use FILL for robotic applications)
     depth_stabilization:        1                               # `0`: disabled, `1`: enabled
     openni_depth_mode:          false                           # 'false': 32bit float meters, 'true': 16bit uchar millimeters

Usage:

# multicamera odometry
roslaunch demo_two_zeds.launch

# single camera odometry
roslaunch demo_two_zeds.launch multicamera_odom:=false

The resulting tf tree would look like this:
rosrun tf2_tools view_frames

cheers,
Mathieu