You also need static transforms to link your sensors against the base frame of your robot. Assuming the base frame is base_link:
base_link->velodyne
\
-> zed
otherwise, you will get a lot of tf warnings from rtabmap.
Without any parameter tuning, just to feed data to rtabmap, it could be done like this
example but with stereo_sync instead of rgbd_sync and using subscribe_scan_cloud instead of scan:
<launch>
<group ns="rtabmap">
<node pkg="nodelet" type="nodelet" name="stereo_sync" args="standalone rtabmap_ros/stereo_sync" output="screen">
<remap from="left/image_rect" to="/zed/right/image_raw"/>
<remap from="right/image_rect" to="/zed/left/image_raw"/>
<remap from="left/camera_info" to="/zed/left/camera_info"/>
<remap from="right/camera_info" to="/zed/right/camera_info"/>
<remap from="rgbd_image" to="rgbd_image"/> <!-- output -->
<param name="approx_sync" value="false"/> <!-- exac sync for stereo -->
</node>
<node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="--delete_db_on_start">
<param name="frame_id" type="string" value="base_link"/>
<param name="subscribe_depth" type="bool" value="false"/>
<param name="subscribe_rgbd" type="bool" value="true"/>
<param name="subscribe_scan_cloud" type="bool" value="true"/>
<remap from="odom" to="/robot_control/odom "/>
<remap from="scan_cloud" to="/velodyne_points"/>
<remap from="rgbd_image" to="rgbd_image"/>
<param name="queue_size" type="int" value="10"/>
<!-- RTAB-Map's parameters -->
<param name="RGBD/CreateOccupancyGrid" type="string" value="false"/>
</node>
</group>
</launch>
To use velodyne points with ICP registration, I would refer to this launch file:
https://github.com/introlab/rtabmap_ros/blob/master/launch/tests/test_velodyne.launchcheers,
Mathieu