orbbec / OrbbecSDK_ROS2

OrbbecSDK ROS2 wrapper
Apache License 2.0
92 stars 36 forks source link

Intermittent Camera Topic Issue with Multi-Camera Setup Using femto bolt (SDK v1.5.8) #48

Closed wataru-okumura closed 4 months ago

wataru-okumura commented 4 months ago

Thanks again. I have a question about using multiple cameras at the same time.

As per readme.md When I run multi_camera.launch.py, I get the following log To confirm that each node is working properly ros topic echo, it is not possible to receive the topic of one of the cameras. This happens about 50% of the time.

Two cameras: femto bolt. sdk version: v1.5.8

teriminal1

ros2 launch orbbec_camera multi_camera.launch.py

terminal2 unable to receive topic

ros2 topic echo /orbbec1/color/camera_info

Note that color/camera_info and color/image_raw fail to echo, and topics such as depth and ir can be obtained.

multi_camera.launch.py

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction, ExecuteProcess
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
import os

def generate_launch_description():
    # Include launch files
    package_dir = get_package_share_directory('orbbec_camera')
    launch_file_dir = os.path.join(package_dir, 'launch')
    launch1_include = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(launch_file_dir, 'femto_bolt.launch.py')
        ),
        launch_arguments={
            'namespace': 'camera1',
            'camera_name': 'orbbec1',
            'serial_number': "CL8K141005S",
            'usb_port': '2-6',
            'device_num': '2',
            #'sync_mode': 'standalone'
        }.items()
    )

    launch2_include = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(launch_file_dir, 'femto_bolt.launch.py')
        ),
        launch_arguments={
            'namespace': 'camera2',
            'camera_name': 'orbbec2',
            'serial_number': "CL8K14101E3",
            'usb_port': '2-5',
            'device_num': '2',
            #'sync_mode': 'standalone'
        }.items()
    )

    # If you need more cameras, just add more launch_include here, and change the usb_port and device_num

    # Launch description
    ld = LaunchDescription([
        GroupAction([launch1_include]),
        GroupAction([launch2_include]),
    ])

    return ld

The following is the log of terminal1 during the run.

ubuntu@rp2_main:~/local_mount/ros2_ws$ ros2 launch orbbec_camera multi_camera.launch.py
[INFO] [launch]: All log files can be found below /home/ubuntu/.ros/log/2024-07-03-08-05-35-885700-rp2_main-49238
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [component_container-1]: process started with pid [49252]
[INFO] [component_container-2]: process started with pid [49254]
[component_container-1] [INFO] [1719993936.280826811] [orbbec1.camera_container]: Load Library: /home/ubuntu/local_mount/ros2_ws/install/orbbec_camera/lib/liborbbec_camera.so
[component_container-2] [INFO] [1719993936.317952325] [orbbec2.camera_container]: Load Library: /home/ubuntu/local_mount/ros2_ws/install/orbbec_camera/lib/liborbbec_camera.so
[component_container-1] [INFO] [1719993936.391276931] [orbbec1.camera_container]: Found class: rclcpp_components::NodeFactoryTemplate<orbbec_camera::OBCameraNodeDriver>
[component_container-1] [INFO] [1719993936.405675020] [orbbec1.camera_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<orbbec_camera::OBCameraNodeDriver>
[component_container-1] [07/03 08:05:36.414434][info][49252][Context.cpp:68] Context created with config: /home/ubuntu/local_mount/ros2_ws/install/orbbec_camera/share/orbbec_camera/config/OrbbecSDKConfig_v1.0.xml
[component_container-1] [07/03 08:05:36.414448][info][49252][Context.cpp:73] Work directory=/home/ubuntu/local_mount/ros2_ws, SDK version=v1.10.8-20240604-d1671a3
[component_container-1] [07/03 08:05:36.414457][info][49252][LinuxPal.cpp:32] createObPal: create LinuxPal!
[component_container-2] [INFO] [1719993936.430093246] [orbbec2.camera_container]: Found class: rclcpp_components::NodeFactoryTemplate<orbbec_camera::OBCameraNodeDriver>
[component_container-2] [INFO] [1719993936.430139928] [orbbec2.camera_container]: Instantiate class: rclcpp_components::NodeFactoryTemplate<orbbec_camera::OBCameraNodeDriver>
[component_container-2] [07/03 08:05:36.446100][info][49254][Context.cpp:68] Context created with config: /home/ubuntu/local_mount/ros2_ws/install/orbbec_camera/share/orbbec_camera/config/OrbbecSDKConfig_v1.0.xml
[component_container-2] [07/03 08:05:36.446113][info][49254][Context.cpp:73] Work directory=/home/ubuntu/local_mount/ros2_ws, SDK version=v1.10.8-20240604-d1671a3
[component_container-2] [07/03 08:05:36.446122][info][49254][LinuxPal.cpp:32] createObPal: create LinuxPal!
[component_container-2] [07/03 08:05:36.583346][info][49254][LinuxPal.cpp:143] Create PollingDeviceWatcher!
[component_container-2] [07/03 08:05:36.583363][info][49254][DeviceManager.cpp:15] Current found device(s): (2)
[component_container-2] [07/03 08:05:36.583366][info][49254][DeviceManager.cpp:24]  - Name: Femto Bolt, PID: 0x066b, SN/ID: CL8K14101E3, Connection: USB3.1
[component_container-2] [07/03 08:05:36.583368][info][49254][DeviceManager.cpp:24]  - Name: Femto Bolt, PID: 0x066b, SN/ID: CL8K141005S, Connection: USB3.1
[component_container-1] [07/03 08:05:36.583386][info][49252][LinuxPal.cpp:143] Create PollingDeviceWatcher!
[component_container-1] [07/03 08:05:36.583398][info][49252][DeviceManager.cpp:15] Current found device(s): (2)
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/orbbec2/orbbec2' in container '/orbbec2/camera_container'
[INFO] [launch_ros.actions.load_composable_nodes]: Loaded node '/orbbec1/orbbec1' in container '/orbbec1/camera_container'
[component_container-1] [07/03 08:05:36.583401][info][49252][DeviceManager.cpp:24]  - Name: Femto Bolt, PID: 0x066b, SN/ID: CL8K14101E3, Connection: USB3.1
[component_container-1] [07/03 08:05:36.583402][info][49252][DeviceManager.cpp:24]  - Name: Femto Bolt, PID: 0x066b, SN/ID: CL8K141005S, Connection: USB3.1
[component_container-2] [INFO] [1719993936.683885654] [orbbec2.orbbec2]: Connecting to device with serial number: CL8K14101E3
[component_container-2] [INFO] [1719993936.683952724] [orbbec2.orbbec2]: Before lock: Select device serial number: CL8K14101E3
[component_container-2] [INFO] [1719993936.683962761] [orbbec2.orbbec2]: After lock: Select device serial number: CL8K14101E3
[component_container-2] [INFO] [1719993936.683984357] [orbbec2.orbbec2]: Device serial number: CL8K14101E3
[component_container-2] [INFO] [1719993936.683991596] [orbbec2.orbbec2]: Device serial number CL8K14101E3 matched
[component_container-2] [INFO] [1719993937.960474911] [orbbec2.orbbec2]: use_hardware_time: true
[component_container-2] [INFO] [1719993937.966728061] [orbbec2.orbbec2]: default_soft_filter_max_diff: 300
[component_container-2] [INFO] [1719993937.966753622] [orbbec2.orbbec2]: default_soft_filter_speckle_size: 25
[component_container-2] [INFO] [1719993937.966844024] [orbbec2.orbbec2]:  stream depth is enabled - width: 640, height: 576, fps: 30, Format: OB_FORMAT_Y16
[component_container-2] [INFO] [1719993937.966899427] [orbbec2.orbbec2]:  stream ir is enabled - width: 640, height: 576, fps: 30, Format: OB_FORMAT_Y16
[component_container-2] [INFO] [1719993937.967080767] [orbbec2.orbbec2]:  stream color is enabled - width: 1280, height: 720, fps: 30, Format: OB_FORMAT_MJPG
[component_container-2] [INFO] [1719993937.967099109] [orbbec2.orbbec2]: stream gyro full scale range 1000dps sample rate 200hz
[component_container-2] [INFO] [1719993937.967111612] [orbbec2.orbbec2]: stream accel full scale range 4g sample rate 200hz
[component_container-2] [INFO] [1719993937.977611309] [orbbec2.orbbec2]: Publish diagnostics every 1 seconds
[component_container-2] [INFO] [1719993938.135380483] [orbbec2.orbbec2]: start accel stream with range: 4g,rate:200hz, and start gyro stream with range:1000dps,rate:200hz
[component_container-2] [INFO] [1719993938.135592164] [orbbec2.orbbec2]: Enable depth stream
[component_container-2] [INFO] [1719993938.135648343] [orbbec2.orbbec2]: Stream depth width: 640 height: 576 fps: 30 format: Y16
[component_container-2] [INFO] [1719993938.135685186] [orbbec2.orbbec2]: Enable ir stream
[component_container-2] [INFO] [1719993938.135715708] [orbbec2.orbbec2]: Stream ir width: 640 height: 576 fps: 30 format: Y16
[component_container-2] [INFO] [1719993938.135744836] [orbbec2.orbbec2]: Enable color stream
[component_container-2] [INFO] [1719993938.135772443] [orbbec2.orbbec2]: Stream color width: 1280 height: 720 fps: 30 format: MJPG
[component_container-2] [INFO] [1719993938.476466275] [orbbec2.orbbec2]: Enable frame sync
[component_container-2] [INFO] [1719993938.476733881] [orbbec2.orbbec2]: Device Femto Bolt connected
[component_container-2] [INFO] [1719993938.476791175] [orbbec2.orbbec2]: Serial number: CL8K14101E3
[component_container-2] [INFO] [1719993938.476827537] [orbbec2.orbbec2]: Firmware version: 1.0.9
[component_container-2] [INFO] [1719993938.476863772] [orbbec2.orbbec2]: Hardware version: 1.2
[component_container-2] [INFO] [1719993938.476891977] [orbbec2.orbbec2]: device unique id: 2-5-23
[component_container-2] [INFO] [1719993938.476925743] [orbbec2.orbbec2]: Current node pid: 49254
[component_container-1] [INFO] [1719993938.477078122] [orbbec1.orbbec1]: Connecting to device with serial number: CL8K141005S
[component_container-1] [INFO] [1719993938.477264087] [orbbec1.orbbec1]: Before lock: Select device serial number: CL8K141005S
[component_container-1] [INFO] [1719993938.477314965] [orbbec1.orbbec1]: After lock: Select device serial number: CL8K141005S
[component_container-1] [INFO] [1719993938.477404857] [orbbec1.orbbec1]: Device serial number: CL8K14101E3
[component_container-1] [INFO] [1719993938.477439540] [orbbec1.orbbec1]: Before lock: Select device serial number: CL8K141005S
[component_container-1] [INFO] [1719993938.477464687] [orbbec1.orbbec1]: After lock: Select device serial number: CL8K141005S
[component_container-1] [INFO] [1719993938.477492481] [orbbec1.orbbec1]: Device serial number CL8K141005S matched
[component_container-2] [INFO] [1719993939.340007027] [orbbec2.orbbec2]: Publishing static transform from orbbec2_link to ir
[component_container-2] [INFO] [1719993939.340041078] [orbbec2.orbbec2]: Translation 0, 0, 0
[component_container-2] [INFO] [1719993939.340051328] [orbbec2.orbbec2]: Rotation 0, 0, 0, 1
[component_container-2] [INFO] [1719993939.340065325] [orbbec2.orbbec2]: Publishing static transform from orbbec2_link to color
[component_container-2] [INFO] [1719993939.340075234] [orbbec2.orbbec2]: Translation 32.5894, 1.18578, -1.87111
[component_container-2] [INFO] [1719993939.340083862] [orbbec2.orbbec2]: Rotation 0.0018755, -0.0530284, 0.00190878, 0.997889
[component_container-2] [INFO] [1719993939.340091726] [orbbec2.orbbec2]: Publishing static transform from orbbec2_link to depth
[component_container-2] [INFO] [1719993939.340099359] [orbbec2.orbbec2]: Translation 0, 0, 0
[component_container-2] [INFO] [1719993939.340106740] [orbbec2.orbbec2]: Rotation 0, 0, 0, 1
[component_container-2] [INFO] [1719993939.340114997] [orbbec2.orbbec2]: Temporary Handling: Initialize with the identity matrix.accel
[component_container-2] [INFO] [1719993939.340121837] [orbbec2.orbbec2]: Publishing static transform from orbbec2_link to accel
[component_container-2] [INFO] [1719993939.340135448] [orbbec2.orbbec2]: Translation 0, 0, 0
[component_container-2] [INFO] [1719993939.340143604] [orbbec2.orbbec2]: Rotation 0, 0, 0, 1
[component_container-2] [INFO] [1719993939.340171863] [orbbec2.orbbec2]: Temporary Handling: Initialize with the identity matrix.gyro
[component_container-2] [INFO] [1719993939.340181558] [orbbec2.orbbec2]: Publishing static transform from orbbec2_link to gyro
[component_container-2] [INFO] [1719993939.340189967] [orbbec2.orbbec2]: Translation 0, 0, 0
[component_container-2] [INFO] [1719993939.340197493] [orbbec2.orbbec2]: Rotation 0, 0, 0, 1
[component_container-2] [WARN] [1719993939.340293864] [orbbec2.orbbec2]: Publishing dynamic camera transforms (/tf) at 10 Hz
[component_container-1] [INFO] [1719993939.755076083] [orbbec1.orbbec1]: use_hardware_time: true
[component_container-1] [INFO] [1719993939.761692827] [orbbec1.orbbec1]: default_soft_filter_max_diff: 300
[component_container-1] [INFO] [1719993939.761736302] [orbbec1.orbbec1]: default_soft_filter_speckle_size: 25
[component_container-1] [INFO] [1719993939.762024691] [orbbec1.orbbec1]:  stream depth is enabled - width: 640, height: 576, fps: 30, Format: OB_FORMAT_Y16
[component_container-1] [INFO] [1719993939.762258515] [orbbec1.orbbec1]:  stream ir is enabled - width: 640, height: 576, fps: 30, Format: OB_FORMAT_Y16
[component_container-1] [INFO] [1719993939.762440014] [orbbec1.orbbec1]:  stream color is enabled - width: 1280, height: 720, fps: 30, Format: OB_FORMAT_MJPG
[component_container-1] [INFO] [1719993939.762463376] [orbbec1.orbbec1]: stream gyro full scale range 1000dps sample rate 200hz
[component_container-1] [INFO] [1719993939.762478594] [orbbec1.orbbec1]: stream accel full scale range 4g sample rate 200hz
[component_container-1] [INFO] [1719993939.776408623] [orbbec1.orbbec1]: Publish diagnostics every 1 seconds
[component_container-1] [INFO] [1719993939.933660456] [orbbec1.orbbec1]: start accel stream with range: 4g,rate:200hz, and start gyro stream with range:1000dps,rate:200hz
[component_container-1] [INFO] [1719993939.933757674] [orbbec1.orbbec1]: Enable depth stream
[component_container-1] [INFO] [1719993939.933775779] [orbbec1.orbbec1]: Stream depth width: 640 height: 576 fps: 30 format: Y16
[component_container-1] [INFO] [1719993939.933783859] [orbbec1.orbbec1]: Enable ir stream
[component_container-1] [INFO] [1719993939.933790670] [orbbec1.orbbec1]: Stream ir width: 640 height: 576 fps: 30 format: Y16
[component_container-1] [INFO] [1719993939.933797112] [orbbec1.orbbec1]: Enable color stream
[component_container-1] [INFO] [1719993939.933803526] [orbbec1.orbbec1]: Stream color width: 1280 height: 720 fps: 30 format: MJPG
[component_container-1] [INFO] [1719993940.272204014] [orbbec1.orbbec1]: Enable frame sync
[component_container-1] [INFO] [1719993940.272290549] [orbbec1.orbbec1]: Device Femto Bolt connected
[component_container-1] [INFO] [1719993940.272303755] [orbbec1.orbbec1]: Serial number: CL8K141005S
[component_container-1] [INFO] [1719993940.272312275] [orbbec1.orbbec1]: Firmware version: 1.1.0
[component_container-1] [INFO] [1719993940.272320410] [orbbec1.orbbec1]: Hardware version: 1.2
[component_container-1] [INFO] [1719993940.272327146] [orbbec1.orbbec1]: device unique id: 2-6-22
[component_container-1] [INFO] [1719993940.272335691] [orbbec1.orbbec1]: Current node pid: 49252
[component_container-1] [INFO] [1719993940.660339300] [orbbec1.orbbec1]: Publishing static transform from orbbec1_link to ir
[component_container-1] [INFO] [1719993940.660374950] [orbbec1.orbbec1]: Translation 0, 0, 0
[component_container-1] [INFO] [1719993940.660384471] [orbbec1.orbbec1]: Rotation 0, 0, 0, 1
[component_container-1] [INFO] [1719993940.660398372] [orbbec1.orbbec1]: Publishing static transform from orbbec1_link to color
[component_container-1] [INFO] [1719993940.660407872] [orbbec1.orbbec1]: Translation 32.3121, 0.939449, -1.97752
[component_container-1] [INFO] [1719993940.660416424] [orbbec1.orbbec1]: Rotation -0.00127365, -0.0554747, 0.00257275, 0.997689
[component_container-1] [INFO] [1719993940.660423555] [orbbec1.orbbec1]: Publishing static transform from orbbec1_link to depth
[component_container-1] [INFO] [1719993940.660430977] [orbbec1.orbbec1]: Translation 0, 0, 0
[component_container-1] [INFO] [1719993940.660438041] [orbbec1.orbbec1]: Rotation 0, 0, 0, 1
[component_container-1] [INFO] [1719993940.660446350] [orbbec1.orbbec1]: Temporary Handling: Initialize with the identity matrix.accel
[component_container-1] [INFO] [1719993940.660473823] [orbbec1.orbbec1]: Publishing static transform from orbbec1_link to accel
[component_container-1] [INFO] [1719993940.660483573] [orbbec1.orbbec1]: Translation 0, 0, 0
[component_container-1] [INFO] [1719993940.660490677] [orbbec1.orbbec1]: Rotation 0, 0, 0, 1
[component_container-1] [INFO] [1719993940.660498741] [orbbec1.orbbec1]: Temporary Handling: Initialize with the identity matrix.gyro
[component_container-1] [INFO] [1719993940.660504635] [orbbec1.orbbec1]: Publishing static transform from orbbec1_link to gyro
[component_container-1] [INFO] [1719993940.660511102] [orbbec1.orbbec1]: Translation 0, 0, 0
[component_container-1] [INFO] [1719993940.660517761] [orbbec1.orbbec1]: Rotation 0, 0, 0, 1
[component_container-1] [WARN] [1719993940.660621769] [orbbec1.orbbec1]: Publishing dynamic camera transforms (/tf) at 10 Hz
wataru-okumura commented 4 months ago

After a little investigation, it seems that color_framequeue.push is not being executed due to color_frame=0 on one of the cameras. Could you please investigate why this is happening?

void OBCameraNode::onNewFrameSetCallback(std::shared_ptr<ob::FrameSet> frame_set) {
  if (!is_running_.load()) {
    return;
  }
  if (!is_camera_node_initialized_.load()) {
    return;
  }
  if (frame_set == nullptr) {
    return;
  }
  try {
    if (!tf_published_) {
      publishStaticTransforms();
      tf_published_ = true;
    }
    depth_frame_ = frame_set->getFrame(OB_FRAME_DEPTH);

    auto device_info = device_->getDeviceInfo();
    CHECK_NOTNULL(device_info.get());
    auto pid = device_info->pid();
    auto color_frame = frame_set->getFrame(OB_FRAME_COLOR); // Sometimes color_frame =0
    if (isGemini335PID(pid)) {
      depth_frame_ = processDepthFrameFilter(depth_frame_);
      if (depth_registration_ && align_filter_ && depth_frame_ && color_frame) {
        auto new_frame = align_filter_->process(frame_set);
        if (new_frame) {
          auto new_frame_set = new_frame->as<ob::FrameSet>();
          CHECK_NOTNULL(new_frame_set.get());
          depth_frame_ = new_frame_set->getFrame(OB_FRAME_DEPTH);
        } else {
          RCLCPP_ERROR(logger_, "Failed to align depth frame to color frame");
        }
      } else {
        RCLCPP_DEBUG(logger_,
                     "Depth registration is disabled or align filter is null or depth frame is "
                     "null or color frame is null");
      }
    }
    if (enable_stream_[COLOR] && color_frame) {  // sometimes it does not fall into this condition.
      std::unique_lock<std::mutex> lock(color_frame_queue_lock_);
      color_frame_queue_.push(frame_set);
      color_frame_queue_cv_.notify_all();
    } else {
      publishPointCloud(frame_set);
    }
jian-dong commented 4 months ago

I suspect that the default usbfs_memory_mb is too small for multiple cameras. You can try changing it from 16 to 128 by running the following command:

sudo vim /sys/module/usbcore/parameters/usbfs_memory_mb

Then, change the value from 16 to 128 and try again.

wataru-okumura commented 4 months ago

I appreciate your comments. I just changed that from 16 to 128 to start, the phenomenon no longer occurs. (0/20 times). Thank you very much for your precise suggestions for improvement.