This guide describes how to configure and use multiple Orbbec cameras simultaneously in a ROS 1 environment.
First asume that you have already installed the Orbbec ROS package. If not, please refer to the Orbbec ROS Package Installation Guide.
IMPORTANT: This step is crucial for multi-camera setups. Without increasing the usbfs_memory_mb value, you may not receive any data from your cameras.
For multi-camera setups, it's essential to increase the usbfs_memory_mb
value. Set it to 128MB (adjustable based on your system's needs) by running:
echo 128 | sudo tee /sys/module/usbcore/parameters/usbfs_memory_mb
To make this change permanent, refer to this link.
If you skip this step or set the value too low, your cameras may not function properly or may not provide any data at all.
Use this bash script to list all connected Orbbec devices with their USB ports and serial numbers:
#!/bin/bash
VID="2bc5"
for dev in /sys/bus/usb/devices/*; do
if [ -e "$dev/idVendor" ]; then
vid=$(cat "$dev/idVendor")
if [ "$vid" == "${VID}" ]; then
port=$(basename $dev)
product=$(cat "$dev/product" 2>/dev/null)
serial=$(cat "$dev/serial" 2>/dev/null)
echo "Found Orbbec device $product, usb port $port, serial number $serial"
fi
fi
done
Save and execute this script, or use the ROS command:
rosrun orbbec_camera list_ob_devices.sh
Create a launch file (e.g., multi_camera.launch
) with individual configurations for each camera:
<launch>
<include file="$(find orbbec_camera)/launch/gemini_330_series.launch">
<arg name="camera_name" value="camera_01"/>
<arg name="usb_port" value="2-3.4.4.4.1"/>
<arg name="device_num" value="2"/>
<arg name="sync_mode" value="free_run"/>
</include>
<include file="$(find orbbec_camera)/launch/gemini_330_series.launch">
<arg name="camera_name" value="camera_02"/>
<arg name="usb_port" value="2-3.4.4.4.3"/>
<arg name="device_num" value="2"/>
<arg name="sync_mode" value="free_run"/>
</include>
</launch>
Execute the launch configuration with:
roslaunch orbbec_camera multi_camera.launch
Create a TF configuration file (e.g., multi_camera_tf.launch
) for your calibrated camera setup:
<launch>
<node pkg="tf" type="static_transform_publisher" name="camera_01_tf" args="0 0 0 0 0 0 base_link camera_01_link" />
<node pkg="tf" type="static_transform_publisher" name="camera_02_tf" args="0 0 0 0 0 0 base_link camera_02_link" />
</launch>
Run the TF configuration:
roslaunch orbbec_camera multi_camera_tf.launch
This setup allows you to use multiple Orbbec cameras simultaneously in your ROS environment. Remember, the first step of increasing the usbfs_memory_mb value is critical for ensuring your cameras function correctly in a multi-camera setup.