introlab / rtabmap_ros

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

Remote mapping Ros2 Intel D455 Connects for 1 frame and stops #950

Open UNkownBob opened 1 year ago

UNkownBob commented 1 year ago

New to ros, attempting to use SLAM with a robot. No need for autonomous movement. have no problems with rgbd handheld mapping tried to follow remote mapping tutorial with limited luck. ran this launch file on robots pc

<launch>

  <!-- Realsense: -->
      <include file="$(find-pkg-share realsense2_camera)/launch/rs_launch.py">
      <arg name="align_depth.enable" value="true"/>
      <arg name="enable_sync" value="true"/>
    </include>

  <group>
    <node pkg="rtabmap_sync" exec="rgbd_sync" name="rgbd_sync" output="screen">
      <remap from="rgb/image"         to="camera/color/image_raw"/>
      <remap from="depth/image"       to="camera/aligned_depth_to_color/image_raw"/>
      <remap from="rgb/camera_info"   to="camera/color/camera_info"/>
      <param name="approx_sync" value="true" />
      <param name="queue_size"  value="100" />
      <param name="compressed_rate" value="0.0"/>
    </node>
  </group>

</launch>

Ran this on the main pc terminal 1

ros2 launch rtabmap_launch rtabmap.launch.py subscribe:=true rgbd_topic:=/rgbd_image compressed:=true rtambap_args:="--delete_db_on_start" queue_size:=50 approx_ sync:=true

terminal 2

ros2 run rtabmap_util rtabrgbd_relay --ros-args -p uncompress:=true

In order to get a single frame and mapping to display i would run the terminal 2, terminal 1, launch files in that order. I suspect its an sync issue with the host and remote pc. as rerunning the program at the right time will update the visuals on the main host pc

UNkownBob commented 1 year ago

launch files

  <!-- Realsense: -->
      <include file="$(find-pkg-share realsense2_camera)/launch/rs_launch.py">
      <arg name="align_depth.enable" value="true"/>
      <arg name="enable_sync" value="true"/>
    </include>

    <node pkg="rtabmap_sync" exec="rgbd_sync" name="rgbd_sync" output="screen">
      <remap from="rgb/image"         to="camera/color/image_raw"/>
      <remap from="depth/image"       to="camera/aligned_depth_to_color/image_raw"/>
      <remap from="rgb/camera_info"   to="camera/color/camera_info"/>
      <param name="approx_sync" value="true" />
      <param name="queue_size"  value="100" />
      <param name="compressed_rate" value="0.0"/>
    </node>
matlabbe commented 1 year ago

Hi,

You may compare the frame rate of the rgbd_image topic on terminals on the host and the remote PC:

ros2 topic hz /rgbd_image/compressed

Are rates similar?

UNkownBob commented 1 year ago

Hi sorry for the long delay was working on another project.

i am having trouble comparing the frame rate of the host and remote PC

this is the following error i get The message type 'rtabmap_msgs/msg/RGBDImage' is invalid

UNkownBob commented 1 year ago

rosgraph

matlabbe commented 1 year ago

If you have topic checksum error or topic definition not existing, make sure you use same rtabmap_ros version between the computers.

UNkownBob commented 1 year ago

Reinstalled the package using debian again to ensure same versions, same problem still persist however when attempting to check the hz of the ros topic, rgbd_sync stops and throws our an error. Below is the log just as "ros2 topic hz /rgbd_image/compressed" is called

[rgbd_sync-2] terminate called after throwing an instance of 'std::runtime_error' [rgbd_sync-2] what(): can't compare times with different time sources [ERROR] [rgbd_sync-2]: process has died [pid 22905, exit code -6, cmd '/opt/ros/humble/lib/rtabmap_sync/rgbd_sync --ros-args -r __node:=rgbd_sync --params-file /tmp/launch_params_rsjdqijn --params-file /tmp/launch_params_0fjmhgui --params-file /tmp/launch_params_3du_jses -r rgb/image:=camera/color/image_raw -r depth/image:=camera/depth/image_rect_raw -r rgb/camera_info:=camera/color/camera_info -r rgbd_image:=rtabmap/rgbd_image/compressed']. ^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)

[realsense2_camera_node-1] [INFO] [1684472371.579917505] [camera.camera]: Stop Sensor: Stereo Module [realsense2_camera_node-1] [INFO] [1684472371.579952358] [camera.camera]: Close Sensor. [realsense2_camera_node-1] [INFO] [1684472371.730470688] [camera.camera]: Close Sensor - Done. [realsense2_camera_node-1] [INFO] [1684472371.730504976] [camera.camera]: Stop Sensor: RGB Camera [realsense2_camera_node-1] [INFO] [1684472371.730521164] [camera.camera]: Close Sensor. [realsense2_camera_node-1] 19/05 13:59:31,728 ERROR [139825663432256] (ds5-thermal-monitor.cpp:94) Error during thermal compensation handling: query is available during streaming only [realsense2_camera_node-1] [INFO] [1684472372.685108832] [camera.camera]: Close Sensor - Done. [INFO] [realsense2_camera_node-1]: process has finished cleanly [pid 22903]

matlabbe commented 1 year ago
 what(): can't compare times with different time sources

Interesting, similar articles:

I tried with my D435i realsense and could not reproduce your problem. Note I did ros2 topic hz on same computer, maybe there is a clock sync issue between the computers, this issue would be then more related to ROS2, not rtabmap.

$ ros2 launch realsense2_camera rs_launch.py \
   enable_gyro:=true \
   enable_accel:=true unite_imu_method:=1 \
   enable_infra1:=true \
   enable_infra2:=true \
   enable_sync:=true

$ ros2 param set /camera/camera depth_module.emitter_enabled 0

$ ros2 launch rtabmap_launch rtabmap.launch.py \
   args:="-d" \
   frame_id:=camera_link \
   approx_sync:=false \
   rgbd_sync:=true \
   rgb_topic:=/camera/infra1/image_rect_raw \
   depth_topic:=/camera/depth/image_rect_raw \
   camera_info_topic:=/camera/infra1/camera_info

$ ros2 topic hz /rtabmap/rgbd_image/compressed
average rate: 29.075
    min: 0.030s max: 0.066s std dev: 0.00606s window: 31
average rate: 29.507
    min: 0.022s max: 0.066s std dev: 0.00478s window: 61
...