本節(jié)介紹如何在ROS 2環(huán)境中同時(shí)配置和使用多個(gè)Orbbec攝像頭。
要確定攝像頭連接到哪些USB端口,您可以使用以下bash腳本。該腳本列出了連接到系統(tǒng)的所有Orbbec設(shè)備及其USB端口和序列號(hào)。
#!/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) # 產(chǎn)品名稱
serial=$(cat "$dev/serial" 2>/dev/null) # 序列號(hào)
echo "發(fā)現(xiàn)Orbbec設(shè)備 $product,usb端口 $port,序列號(hào) $serial"
fi
fi
done
將此腳本保存為一個(gè)文件,并在您的終端中執(zhí)行,以輸出連接的攝像頭列表。
您可以通過(guò)為每個(gè)攝像頭指定不同的USB端口來(lái)啟動(dòng)多個(gè)攝像頭。下面是一個(gè)使用ROS 2啟動(dòng)系統(tǒng)啟動(dòng)兩個(gè)攝像頭的Python腳本示例。
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction, ExecuteProcess
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
import os
def generate_launch_description():
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, 'gemini_330_series.launch.py')),
launch_arguments={'camera_name': 'camera_01', 'usb_port': '2-3.4.4.4.1', 'device_num': '2', 'sync_mode': 'free_run'}.items()
)
launch2_include = IncludeLaunchDescription(
PythonLaunchDescriptionSource(os.path.join(launch_file_dir, 'gemini_330_series.launch.py')),
launch_arguments={'camera_name': 'camera_02', 'usb_port': '2-3.4.4.4.3', 'device_num': '2', 'sync_mode': 'free_run'}.items()
)
ld = LaunchDescription([
GroupAction([launch1_include]),
GroupAction([launch2_include])
])
return ld
要執(zhí)行多攝像頭的啟動(dòng)配置,請(qǐng)使用命令:
ros2 launch orbbec_camera multi_camera.launch.py
使用多個(gè)攝像頭時(shí),校準(zhǔn)它們并為每個(gè)攝像頭發(fā)布靜態(tài)TF樹是必不可少的。以下Python腳本基于您的校準(zhǔn)結(jié)果配置TF樹:
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
ld = LaunchDescription([
Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_01_tf',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'camera_01_link'],
output='screen'
),
Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_02_tf',
arguments=['0', '0', '0', '0', '0', '0', 'base_link', 'camera_02_link'],
output='screen'
)
])
return ld
將此配置保存為 在Orbbec攝像頭包的啟動(dòng)目錄中。運(yùn)行它,請(qǐng)使用:
ros2 launch orbbec_camera multi_camera_tf.launch.py