If you use this launch file (slam_rtabmap.launch), I suggest to start from modified version of
https://github.com/microsoft/Azure_Kinect_ROS_Driver/pull/166Your previous post is about the obstacles_detection nodelet, so I would do an example here with that. For rtabmap node, you may use same rtabmap's parameters in args of slam_rtabmap.launch.
<node pkg="nodelet" type="nodelet" name="obstacle_manager" args="manager"/>
<node pkg="nodelet" type="nodelet" name="disparity2cloud" args="load rtabmap_util/point_cloud_xyz obstacle_manager">
<remap from="depth/image" to="/k4a/depth/image_raw"/>
<remap from="depth/camera_info" to="/k4a/depth/camera_info"/>
<remap from="cloud" to="cloudObs"/>
<param name="voxel_size" type="double" value="0.05"/>
<param name="decimation" type="int" value="4"/>
<param name="max_depth" type="double" value="0"/>
</node>
<node pkg="nodelet" type="nodelet" name="obstacles_detection" args="load rtabmap_util/obstacles_detection obstacle_manager">
<remap from="cloud" to="cloudObs"/>
<param name="frame_id" type="string" value="base_footprint"/>
<!-- See rtabmap's parameters Grid/*** -->
<param name="Grid/NormalsSegmentation" type="bool" value="false"/>
<param name="Grid/MaxGroundHeight" type="double" value="0.1"/>
</node>
This assumes that base_footprint is the frame of the robot at ground level, so that the threshold at 0.1 meters work correctly.