introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
953 stars 556 forks source link

Did not receive data since 5 seconds! #1182

Open whaudrms opened 2 months ago

whaudrms commented 2 months ago

Hello, I am having trouble running rtabmap I'm usuing oak-d-pro and livox avia and I'm trying to use 'subscribe_scan_cloud' parameter but the following error appears.


SUMMARY
========

PARAMETERS
 * /cmdline_file_path: livox_test.lvx
 * /cmdline_str: 100000000000000
 * /common/imu_topic: /livox/imu
 * /common/lid_topic: /livox/lidar
 * /common/time_offset_lidar_to_imu: 0.0
 * /common/time_sync_en: False
 * /cube_side_length: 1000.0
 * /data_src: 0
 * /enable_imu_bag: True
 * /enable_lidar_bag: True
 * /feature_extract_enable: False
 * /filter_size_map: 0.5
 * /filter_size_surf: 0.5
 * /frame_id: livox_frame
 * /livox_repub_online_node/livox_points_message_name: /livox/points
 * /livox_repub_online_node/livox_raw_message_name: /livox/lidar
 * /mapping/acc_cov: 0.1
 * /mapping/b_acc_cov: 0.0001
 * /mapping/b_gyr_cov: 0.0001
 * /mapping/det_range: 450.0
 * /mapping/extrinsic_R: [1, 0, 0, 0, 1, 0...
 * /mapping/extrinsic_T: [0.04165, 0.02326...
 * /mapping/extrinsic_est_en: False
 * /mapping/fov_degree: 90
 * /mapping/gyr_cov: 0.1
 * /max_iteration: 3
 * /multi_topic: 0
 * /oak/camera_i_base_frame: oak-d_frame
 * /oak/camera_i_cam_pitch: 0.0
 * /oak/camera_i_cam_pos_x: 0.0
 * /oak/camera_i_cam_pos_y: 0.0
 * /oak/camera_i_cam_pos_z: 0.0
 * /oak/camera_i_cam_roll: 0.0
 * /oak/camera_i_cam_yaw: 0.0
 * /oak/camera_i_imu_from_descr: False
 * /oak/camera_i_nn_type: none
 * /oak/camera_i_parent_frame: oak-d-base-frame
 * /oak/camera_i_publish_tf_from_calibration: False
 * /oak/robot_description: <?xml version="1....
 * /oak/stereo_i_subpixel: True
 * /output_data_type: 0
 * /pcd_save/interval: -1
 * /pcd_save/pcd_save_en: True
 * /point_filter_num: 3
 * /preprocess/blind: 4
 * /preprocess/lidar_type: 1
 * /preprocess/scan_line: 6
 * /publish/dense_publish_en: True
 * /publish/path_en: False
 * /publish/scan_bodyframe_pub_en: True
 * /publish/scan_publish_en: True
 * /publish_freq: 10.0
 * /rosdistro: noetic
 * /rosversion: 1.16.0
 * /rtabmap/Grid/RangeMax: 0
 * /rtabmap/Icp/CorrespondenceRatio: 0.2
 * /rtabmap/Icp/RangeMax: 0
 * /rtabmap/Icp/VoxelSize: 0.05
 * /rtabmap/RGBD/ProximityBySpace: true
 * /rtabmap/Reg/Force3DoF: true
 * /rtabmap/Reg/Strategy: 1
 * /rtabmap/frame_id: oak
 * /rtabmap/subscribe_depth: False
 * /rtabmap/subscribe_rgb: True
 * /rtabmap/subscribe_rgbd: False
 * /rtabmap/subscribe_scan_cloud: True
 * /runtime_pos_log_enable: False
 * /user_config_path: /home/tony/alpha_...
 * /xfer_format: 1

NODES
  /
    laserMapping (fast_lio/fastlio_mapping)
    livox_lidar_publisher (livox_ros_driver/livox_ros_driver_node)
    livox_repub_online_node (livox_repub/livox_repub_online_node)
    oak (nodelet/nodelet)
    oak_nodelet_manager (nodelet/nodelet)
    oak_state_publisher (robot_state_publisher/robot_state_publisher)
    rtabmap (rtabmap_slam/rtabmap)
    rviz (rviz/rviz)

auto-starting new master
process[master]: started with pid [70372]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to b50c0af0-3d29-11ef-9083-5b1fb87b18f7
process[rosout-1]: started with pid [70382]
started core service [/rosout]
process[oak_state_publisher-2]: started with pid [70389]
process[oak_nodelet_manager-3]: started with pid [70390]
process[oak-4]: started with pid [70391]
process[livox_lidar_publisher-5]: started with pid [70392]
process[laserMapping-6]: started with pid [70398]
[ INFO] [1720443481.908836218]: Loading nodelet /oak of type depthai_ros_driver/Camera to manager oak_nodelet_manager with the following remappings:
process[rviz-7]: started with pid [70404]
[ INFO] [1720443481.911560666]: waitForService: Service [/oak_nodelet_manager/load_nodelet] has not been advertised, waiting...
process[livox_repub_online_node-8]: started with pid [70410]
[ INFO] [1720443481.915534861]: Livox Ros Driver Version: 2.6.0
[ INFO] [1720443481.919735152]: Data Source is raw lidar.
[ INFO] [1720443481.920208121]: Config file : /home/tony/alpha_ws/src/livox_ros_driver/livox_ros_driver/config/livox_lidar_config.json
process[rtabmap-9]: started with pid [70412]
Commandline input bd:100000000000000
Invalid bd:100000000000000!
Livox SDK version 2.3.0
broadcast code[1PQDH5B00100041] : 0 0 0 0 0 0
broadcast code[0TFDG3U99101431] : 0 0 0 0 0 0
Disable timesync
No broadcast code was added to whitelist, swith to automatic connection mode!
Livox-SDK init success!
[ INFO] [1720443481.920933298]: Init lds lidar success!
[ INFO] [1720443481.924036626]: Initializing nodelet with 16 worker threads.
Multi thread started 
p_pre->lidar_type 1
~~~~/home/tony/alpha_ws/src/FAST_LIO/ file opened
[ INFO] [1720443482.039654772]: waitForService: Service [/oak_nodelet_manager/load_nodelet] is now available.
[ INFO] [1720443482.095504924]: Starting node...
[ INFO] [1720443482.125328823]: Initializing nodelet with 16 worker threads.
[ INFO] [1720443482.137146140]: No ip/mxid/usb_id specified, connecting to the next available device.
[ INFO] [1720443482.226508752]: /rtabmap(maps): map_filter_radius          = 0.000000
[ INFO] [1720443482.226532923]: /rtabmap(maps): map_filter_angle           = 30.000000
[ INFO] [1720443482.226538534]: /rtabmap(maps): map_cleanup                = true
[ INFO] [1720443482.226543541]: /rtabmap(maps): map_always_update          = false
[ INFO] [1720443482.226548243]: /rtabmap(maps): map_empty_ray_tracing      = true
[ INFO] [1720443482.226552786]: /rtabmap(maps): cloud_output_voxelized     = true
[ INFO] [1720443482.226557409]: /rtabmap(maps): cloud_subtract_filtering   = false
[ INFO] [1720443482.226562859]: /rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[ INFO] [1720443482.226743175]: /rtabmap(maps): octomap_tree_depth         = 16
[ INFO] [1720443482.239069886]: rtabmap: frame_id      = oak
[ INFO] [1720443482.239133974]: rtabmap: map_frame_id  = map
[ INFO] [1720443482.239158859]: rtabmap: log_to_rosout_level = 4
[ INFO] [1720443482.239165664]: rtabmap: initial_pose  = 
[ INFO] [1720443482.239174014]: rtabmap: use_action_for_goal  = false
[ INFO] [1720443482.239182695]: rtabmap: tf_delay      = 0.050000
[ INFO] [1720443482.239188594]: rtabmap: tf_tolerance  = 0.100000
[ INFO] [1720443482.239194842]: rtabmap: odom_sensor_sync   = false
[ INFO] [1720443482.239200608]: rtabmap: pub_loc_pose_only_when_localizing = false
[ INFO] [1720443482.239534219]: rtabmap: gen_scan  = false
[ INFO] [1720443482.239546788]: rtabmap: gen_depth  = false
[ INFO] [1720443482.239983759]: rtabmap: scan_cloud_max_points = 0
[ INFO] [1720443482.240001307]: rtabmap: scan_cloud_is_2d      = false
[ INFO] [1720443482.280359717]: Setting RTAB-Map parameter "Grid/RangeMax"="0"
[ INFO] [1720443482.290818011]: Setting RTAB-Map parameter "Icp/CorrespondenceRatio"="0.2"
[ INFO] [1720443482.299839620]: Setting RTAB-Map parameter "Icp/RangeMax"="0"
[ INFO] [1720443482.302270055]: Setting RTAB-Map parameter "Icp/VoxelSize"="0.05"
[ INFO] [1720443482.355907214]: Setting RTAB-Map parameter "RGBD/ProximityBySpace"="true"
[ INFO] [1720443482.360724062]: Setting RTAB-Map parameter "Reg/Force3DoF"="true"
[ INFO] [1720443482.361961571]: Setting RTAB-Map parameter "Reg/Strategy"="1"
[ WARN] [1720443482.506137160]: Setting "Grid/Sensor" parameter to 0 (default 1) as "subscribe_scan", "subscribe_scan_cloud" or "gen_scan" is true. The occupancy grid map will be constructed from laser scans. To get occupancy grid map from camera's cloud projection, set "Grid/Sensor" to 1. To suppress this warning, add <param name="Grid/Sensor" type="string" value="0"/>
[ INFO] [1720443482.506225178]: Setting "Icp/PointToPlaneRadius" parameter to 0 (default 0.000000) as "subscribe_scan_cloud" is true.
[ WARN] [1720443482.506277269]: Setting "RGBD/ProximityPathMaxNeighbors" parameter to 1 (default 0) as "subscribe_scan_cloud" is true and "Reg/Strategy" uses ICP. To disable, set "RGBD/ProximityPathMaxNeighbors" to 0. To suppress this warning, add <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="1"/>
[ INFO] [1720443482.506967178]: RTAB-Map detection rate = 1.000000 Hz
[ INFO] [1720443482.507419338]: rtabmap: Deleted database "/home/tony/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[ INFO] [1720443482.507465700]: rtabmap: Using database from "/home/tony/.ros/rtabmap.db" (0 MB).
[ INFO] [1720443482.763379206]: rtabmap: Database version = "0.21.4".
[ INFO] [1720443482.763423648]: rtabmap: SLAM mode (Mem/IncrementalMemory=true)
[ INFO] [1720443482.781326023]: /rtabmap: subscribe_depth = false
[ INFO] [1720443482.781362139]: /rtabmap: subscribe_rgb = true
[ INFO] [1720443482.781381231]: /rtabmap: subscribe_stereo = false
[ INFO] [1720443482.781399394]: /rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[ INFO] [1720443482.781418352]: /rtabmap: subscribe_sensor_data = false
[ INFO] [1720443482.781434719]: /rtabmap: subscribe_odom_info = false
[ INFO] [1720443482.781450866]: /rtabmap: subscribe_user_data = false
[ INFO] [1720443482.781466316]: /rtabmap: subscribe_scan = false
[ INFO] [1720443482.781482911]: /rtabmap: subscribe_scan_cloud = true
[ INFO] [1720443482.781498726]: /rtabmap: subscribe_scan_descriptor = false
[ INFO] [1720443482.781517628]: /rtabmap: queue_size    = 10
[ INFO] [1720443482.781534670]: /rtabmap: approx_sync   = true
[ INFO] [1720443482.781591649]: Setup rgb-only callback
[2024-07-08 21:58:02.793] [console] [info]  Broadcast broadcast code: 3JEDLAL00165511  [device_discovery.cpp] [OnBroadcast] [150]
In automatic connection mode, will connect 3JEDLAL00165511
Could not find raw config, set config to default!
[2024-07-08 21:58:02.793] [console] [info] LocalIP: 192.168.1.50  [device_discovery.cpp] [OnBroadcast] [201]
[2024-07-08 21:58:02.793] [console] [info] DeviceIP: 192.168.1.151  [device_discovery.cpp] [OnBroadcast] [202]
[2024-07-08 21:58:02.793] [console] [info] Command Port: 55501  [device_discovery.cpp] [OnBroadcast] [203]
[2024-07-08 21:58:02.793] [console] [info] Data Port: 56001  [device_discovery.cpp] [OnBroadcast] [204]
[2024-07-08 21:58:02.795] [console] [info] New Device  [device_discovery.cpp] [OnData] [99]
[2024-07-08 21:58:02.795] [console] [info] Handle: 0  [device_discovery.cpp] [OnData] [100]
[2024-07-08 21:58:02.795] [console] [info] Broadcast Code: 3JEDLAL00165511  [device_discovery.cpp] [OnData] [101]
[2024-07-08 21:58:02.795] [console] [info] Type: 7  [device_discovery.cpp] [OnData] [102]
[2024-07-08 21:58:02.795] [console] [info] IP: 192.168.1.151  [device_discovery.cpp] [OnData] [103]
[2024-07-08 21:58:02.795] [console] [info] Command Port: 55501  [device_discovery.cpp] [OnData] [104]
[2024-07-08 21:58:02.795] [console] [info] Data Port: 56001  [device_discovery.cpp] [OnData] [105]
[2024-07-08 21:58:02.795] [console] [info]  Send Command: Set 0 Id 2 Seq 3  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.797] [console] [info]  Recieve Ack: Set 0 Id 2 Seq 3  [command_handler.cpp] [OnCommand] [118]
Lidar[3JEDLAL00165511] status_code[0] working state[5] feature[0]
[2024-07-08 21:58:02.797] [console] [info]  Send Command: Set 0 Id 2 Seq 4  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.799] [console] [info]  Recieve Ack: Set 0 Id 2 Seq 4  [command_handler.cpp] [OnCommand] [118]
firmware version: 11.8.0.6
[2024-07-08 21:58:02.851] [console] [info]  Update State to 1, device connect true  [device_manager.cpp] [UpdateDeviceState] [281]
Lidar[3JEDLAL00165511] status_code[0] working state[1] feature[0]
[2024-07-08 21:58:02.851] [console] [info]  Send Command: Set 0 Id 5 Seq 6  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.851] [console] [info]  Send Command: Set 1 Id 6 Seq 7  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.852] [console] [info]  Send Command: Set 1 Id 8 Seq 8  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.853] [console] [info]  Recieve Ack: Set 0 Id 5 Seq 6  [command_handler.cpp] [OnCommand] [118]
Set coordinate success!
[2024-07-08 21:58:02.853] [console] [info]  Recieve Ack: Set 1 Id 6 Seq 7  [command_handler.cpp] [OnCommand] [118]
Set return mode success!
[2024-07-08 21:58:02.853] [console] [info]  Recieve Ack: Set 1 Id 8 Seq 8  [command_handler.cpp] [OnCommand] [118]
Set imu rate success!
[2024-07-08 21:58:02.853] [console] [info]  Send Command: Set 0 Id 4 Seq 9  [command_channel.cpp] [Send] [243]
[2024-07-08 21:58:02.855] [console] [info]  Recieve Ack: Set 0 Id 4 Seq 9  [command_handler.cpp] [OnCommand] [118]
Lidar start sample success
Lidar[0][3JEDLAL00165511] DataType[2] timestamp_type[0] PacketInterval[400032] PublishPackets[250]
Lidar[0][3JEDLAL00165511] storage queue size : 500 512
Lidar[0][3JEDLAL00165511] imu storage queue size : 256 256
[ INFO] [1720443482.887160765]: 
/rtabmap subscribed to (approx sync):
   /Odometry \
   /oak/rgb/image_raw \
   /rgb/camera_info \
   /livox/points
[ INFO] [1720443482.950778321]: rtabmap 0.21.4 started...
[ INFO] [1720443482.955293247]: Support only one topic.
[ INFO] [1720443482.955790734]: livox/imu publish imu data, set ROS publisher queue size 256
[DEBUG] [1720443482.955809508]: Trying to publish message of type [sensor_msgs/Imu/6a62c6daae103f4ff57a132d6f95cec2] on a publisher with type [sensor_msgs/Imu/6a62c6daae103f4ff57a132d6f95cec2]
[ INFO] [1720443482.977510103]: Support only one topic.
[ INFO] [1720443482.978231354]: livox/lidar publish use livox custom format, set ROS publisher queue size 256
[DEBUG] [1720443482.978251383]: Trying to publish message of type [livox_ros_driver/CustomMsg/e4d6829bdfe657cb6c21a746c86b21a6] on a publisher with type [livox_ros_driver/CustomMsg/e4d6829bdfe657cb6c21a746c86b21a6]
[ INFO] [1720443483.479801457]: IMU Initial Done
[ WARN] [1720443483.482851755]: No point, skip this scan!

[ INFO] [1720443485.149383014]: Camera with MXID: 1844301071F8C71200 and Name: 3.2 connected!
[ INFO] [1720443485.150086584]: USB SPEED: SUPER
[ INFO] [1720443485.197394780]: Device type: OAK-D-PRO
[ INFO] [1720443485.201133620]: Pipeline type: RGBD
[ INFO] [1720443486.026423258]: Finished setting up pipeline.
[ WARN] [1720443486.890467063]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
   /Odometry \
   /rgbd/image \
   /rgb/camera_info \
   /livox/points
[ INFO] [1720443486.944870637]: Camera ready!
[ WARN] [1720443491.890569975]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
   /Odometry \
   /oak/rgb/image_raw \
   /rgb/camera_info \
   /livox/points

my launch files are as follows

<?xml version="1.0"?>
<launch>
    <arg name="name" default="oak" />
    <arg name="params_file" default="$(find depthai_ros_driver)/config/rgbd.yaml" />

    <include file="$(find depthai_ros_driver)/launch/camera.launch">
        <arg name="name" value="$(arg name)"/>
        <arg name="params_file" value="$(arg params_file)"/>
    </include>

    <!-- odom -->

    <include file="$(find livox_ros_driver)/launch/livox_lidar_msg.launch"/>
    <include file="$(find fast_lio)/launch/mapping_avia.launch"/>
    <include file="$(find livox_repub)/launch/livox_repub_online.launch"/>

    <!-- SLAM -->
    <!-- args: "delete_db_on_start" and "udebug" -->
    <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
        <param name="frame_id" type="string" value="$(arg name)"/>

        <param name="subscribe_rgb"   type="bool" value="true"/>
        <param name="subscribe_depth" type="bool" value="false"/>
        <param name="subscribe_rgbd"  type="bool" value="false"/>
        <param name="subscribe_scan_cloud"  type="bool" value="true"/>

        <remap from="scan_cloud" to="/livox/points"/>
        <remap from="rgb/image" to="oak/rgb/image_raw"/>
        <remap from="rgb/camera_info" to="oak/rgb/camera_info"/>
        <remap from="odom" to="/Odometry"/>
        <param name="subscribe_odom_info" type="bool" value="true"/>

        <!-- RTAB-Map's parameters -->
        <param name="Reg/Strategy"       type="string" value="1"/>    <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
        <param name="Reg/Force3DoF"      type="string" value="true"/>
        <param name="RGBD/ProximityBySpace"    type="string" value="true"/>
        <param name="Icp/CorrespondenceRatio"  type="string" value="0.2"/>
        <param name="Icp/VoxelSize"            type="string" value="0.05"/>
        <param name="Icp/RangeMax"             type="string" value="0"/>
        <param name="Grid/RangeMax"            type="string" value="0"/>
    </node>

</launch>

Any help on this is greatly appreciated. thank you :)

matlabbe commented 1 month ago

Not sure why rtabmap switched from rgbd_image to rgb image input between these two logs:

[ WARN] [1720443486.890467063]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
   /Odometry \
   /rgbd/image \
   /rgb/camera_info \
   /livox/points
[ INFO] [1720443486.944870637]: Camera ready!
[ WARN] [1720443491.890569975]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
   /Odometry \
   /oak/rgb/image_raw \
   /rgb/camera_info \
   /livox/points

The camera info is not remapped correctly too. I tried rtabmap part of your launch and this is what should be expected:

/rtabmap subscribed to (approx sync):
   /Odometry \
   /oak/rgb/image_raw \
   /oak/rgb/camera_info \
   /livox/points \
   /odom_info
[ INFO] [1721581756.110587353]: rtabmap 0.21.5 started...
[ WARN] [1721581760.046839697]: /rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10).
/rtabmap subscribed to (approx sync):
   /Odometry \
   /oak/rgb/image_raw \
   /oak/rgb/camera_info \
   /livox/points \
   /odom_info

You would also need to set subscribe_odom_info to false instead of true, as the topic doesn't exist in your case. Do:

    <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
        <param name="frame_id" type="string" value="oak"/>

        <param name="subscribe_rgb"   type="bool" value="true"/>
        <param name="subscribe_depth" type="bool" value="false"/>
        <param name="subscribe_rgbd"  type="bool" value="false"/>
        <param name="subscribe_scan_cloud"  type="bool" value="true"/>

        <remap from="scan_cloud" to="/livox/points"/>
        <remap from="rgb/image" to="oak/rgb/image_raw"/>
        <remap from="rgb/camera_info" to="oak/rgb/camera_info"/>
        <remap from="odom" to="/Odometry"/>
        <param name="subscribe_odom_info" type="bool" value="false"/>

        <!-- RTAB-Map's parameters -->
        <param name="Reg/Strategy"       type="string" value="1"/>    <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
        <param name="Reg/Force3DoF"      type="string" value="true"/>
        <param name="RGBD/ProximityBySpace"    type="string" value="true"/>
        <param name="Icp/CorrespondenceRatio"  type="string" value="0.2"/>
        <param name="Icp/VoxelSize"            type="string" value="0.05"/>
        <param name="Icp/RangeMax"             type="string" value="0"/>
        <param name="Grid/RangeMax"            type="string" value="0"/>
    </node>
matlabbe commented 1 month ago

To get loop closure detection working, I suggest to use depth image of the oak as it is available. To do so, you will need to use RGBDImage interface. Following this example, that would look like this:

    <node pkg="rtabmap_sync" type="rgbd_sync" name="rgbd_sync" output="screen">
      <remap from="rgb/image"         to="oak/rgb/image_raw"/>
      <remap from="depth/image"       to="oak/depth/image"/>
      <remap from="rgb/camera_info"   to="oak/rgb/camera_info"/>
    </node>

    <node name="rtabmap" pkg="rtabmap_slam" type="rtabmap" output="screen" args="--delete_db_on_start">
        <param name="frame_id" type="string" value="oak"/>

        <param name="subscribe_rgb"   type="bool" value="false"/>
        <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="scan_cloud" to="/livox/points"/>
        <remap from="odom" to="/Odometry"/>
        <param name="subscribe_odom_info" type="bool" value="false"/>

        <!-- RTAB-Map's parameters -->
        <param name="Reg/Strategy"       type="string" value="1"/>    <!-- 0=Visual, 1=ICP, 2=Visual+ICP -->
        <param name="Reg/Force3DoF"      type="string" value="true"/>
        <param name="RGBD/ProximityBySpace"    type="string" value="true"/>
        <param name="Icp/CorrespondenceRatio"  type="string" value="0.2"/>
        <param name="Icp/VoxelSize"            type="string" value="0.05"/>
        <param name="Icp/RangeMax"             type="string" value="0"/>
        <param name="Grid/RangeMax"            type="string" value="0"/>
    </node>

You may have to adjust the remap of the oak depth image, I just guessed the name.