5.2.8 ROS2 MIPI Camera 使用
本章节提供了基于JDK 库的摄像头驱动和一系列 ROS 2 节点,用于获取和处理 MIPI CSI 摄像头数据。JDK 库包含了对摄像头(JdkCamera
)、视频编码(JdkEncoder
)、解码(JdkDecoder
)、视频输出(JdkVo
)等硬件功能的封装,ROS 2 节点则调用这些功能,将数据通过自定义消息在 ROS 2 中发布。系统架构如下:摄像头数据由 camera_node
节点采集并发布到 /camera_frames
;可以通过 venc_node
对原始帧进行 H.264 编码,输出到 /encoded_frames
;vdec_node
可对编码帧解码并发布到 /decoded_frames
;vo_node
节点订阅相机帧并在屏幕上显示(使用硬件加速输出);infer_node
节点对相机帧进行目标检测推理(默认使用 YOLOv8 模型)。用户通过订阅对应话题即可获取帧数据并进一步处理。本说明涵盖了系统背景、安装依赖、编译方式、节点启动及参数、接口说明和示例等内容,帮助用户快速集成使用该包。
1.背景介绍
- 硬件环境:本驱动面向支持 MIPI CSI 摄像头接口的嵌入式系统,典型场景为 Spacemit kx 系列开发板。JDK 库(JDK SDK)直接操作 V4L2 接口,可高效访问摄像头及视频编解码硬件。
- 系统架构:基于 JDK SDK 的功能,本套件定义了 ROS 2 包和节点结构。主要组件包括:
- JDK 库组件:提供对摄像头采集(
JdkCamera
)、帧封装(JdkFrame
)、硬件编码(JdkEncoder
)、解码(JdkDecoder
)、视频输出(JdkVo
)、以及帧的 DMA 传输(JdkDma
)等功能的 C++ 接口。 - ROS 2 接口包:
jdk_interfaces
包定义了用于传递帧数据的自定义消息类型JdkFrameMsg
。 - FD 传输包:
jdk_fd_transmitter
包实现了基于 UNIX Socket 的零拷贝帧传输机制,使多个节点间可以通过共享 DMA 缓冲避免复制开销。 - 功能节点:
jdk_camera_node
、jdk_venc_node
、jdk_vdec_node
、jdk_vo_node
、jdk_infer_node
等节点分别负责采集、编码、解码、显示和推理。摄像头采集节点将帧发布到/camera_frames
,编码节点输出到/encoded_frames
,解码节点输出到/decoded_frames
,显示节点通过硬件直出画面,推理节点对/camera_frames
进行目标检测,使用 YOLOv8 模型进行识别。
- JDK 库组件:提供对摄像头采集(
下面各节将详细介绍安装环境、编译流程、节点启动参数、接口定义及使用示例。
2.安装与依赖说明
- 操作系统:推荐使用 Bianbu 2.2,并安装 ROS 2 Humble(Humble Hawksbill)版本。ROS 2 Humble 官方参考[docs.ros.org](https://docs.ros.org/en/humble/Installation.html#:~:text=* Ubuntu Linux ,04)。确保系统更新并安装 ROS 2 桌面版(
sudo apt install ros-humble-desktop
)。 - 硬件驱动:需有支持 MIPI CSI 摄像头的驱动(例如 bianbu 内核默认支持多路 CSI 接口)。可通过
v4l2-ctl --list-devices
确认摄像头设备节点(如/dev/video0
,/dev/video50
等)。 - 依赖库:安装构建和运行所需的工具及库,例如:
- C/C++ 编译工具:
build-essential
、cmake
等。 - UUID 库:
uuid-dev
(用于生成帧 ID)[docs.ros.org](https://docs.ros.org/en/foxy/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#:~:text=To run the executable you,package creation%2C enter the command)。 - V4L2 相关:
libv4l-dev
(可选,用于 V4L2 头文件)。 - ROS 2 依赖:
ament_cmake
构建工具、rclcpp
、std_msgs
、rosidl_default_generators
等一般 ROS 2 包(通过安装 ROS 2 桌面版已包括)。
2.1安装命令示例(Bianbu 2.2)
sudo apt update
sudo apt install -y ros-humble-desktop build-essential cmake libuuid1 uuid-dev libv4l-dev
安装完成后,按照 ROS 2 官方文档设置软件源、密钥等步骤,可参考文档[docs.ros.org](https://docs.ros.org/en/humble/Installation.html#:~:text=* Ubuntu Linux ,04)。
2.2工作空间准备
在安装好 ROS 2 后,创建一个 ROS 2 工作空间,如 ~/ros2_ws
,并将本项目的代码(jdk
文件夹)放入 src
目录下。例如:
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
cp -r path_to_jdk_folder ./jdk
cd ~/ros2_ws
2.3 JDK SDK 编译(可选)
如果需要将 JDK 库安装到系统中,可参照项目内 jdk_sdk
目录说明,将库安装到 /opt/jdk
。例如:
cd jdk/jdk_ros2_ws/jdk_sdk
cmake -DCMAKE_INSTALL_PREFIX=/opt/jdk .
make install
然后设置环境变量:
export CMAKE_PREFIX_PATH=/opt/jdk:$CMAKE_PREFIX_PATH
export LD_LIBRARY_PATH=/opt/jdk/lib:$LD_LIBRARY_PATH
这样其他程序可通过 find_package(jdk REQUIRED)
链接 JDK 库。
2.4依赖检查
确认已安装的依赖后,即可进行编译。下面列出了常见依赖包,用户可根据需要安装:
ros-humble-rclcpp
、ros-humble-std-msgs
:ROS 2 C++ 客户端库。ros-humble-rosidl-default-generators
:生成自定义消息类型。ros-humble-rcl-interfaces
(已随 ROS 2 安装)。libssl-dev
(根据推理插件可能需要,若使用加密或特定后端)。
3.构建与编译方式
将代码放入工作空间后,使用 colcon
构建所有 ROS 2 包。一般步骤如下:
3.1配置 ROS 2 环境
在新的终端中,先执行
source /opt/ros/humble/setup.bash
以 加载已安装的 ROS 2 环境变量。
3.2进入工作空间
进入包含 src
的工作空间根目录:
cd ~/ros2_ws
3.3 编译接口和传输包
为了先生成消息类型,建议先编译 jdk_interfaces
和 jdk_fd_transmitter
包:
colcon build --packages-select jdk_interfaces
source install/setup.bash
colcon build --packages-select jdk_fd_transmitter
source install/setup.bash
提示:一般可以直接编译全部包,无需分步;下面步骤采用一次性构建所有包。
3.4编译所有包
在工作空间根目录运
colcon build --symlink-install
根据 ROS 官方文档,将工作空间内所有包一起构建[docs.ros.org](https://docs.ros.org/en/foxy/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#:~:text=Putting packages in a workspace,to build each package individually)。构建完成后,目录中应出现 build/
、install/
、log/
等文件夹。
3.5加载工作空间
构建完成后,每次使用前需加载安装的工作空间,例如:
source install/setup.bash
这样可以在环境中找到编译出的包和可执行文件[docs.ros.org](https://docs.ros.org/en/foxy/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#:~:text=To run the executable you,package creation%2C enter the command)。
注意:若在非 ROS 工作空间(例如单独目录)构建,则需在运行时调整 LD_LIBRARY_PATH
包含 JDK 库路径 /opt/jdk/lib
(如果已安装到该目录)。通常将所有包放到一个工作空间并使用 colcon build
是最简便的方法。
4.节点启动方式和参数
项目包含若干 ROS 2 可执行节点,每个节点均可通过 ros2 run
或 ros2 launch
启动,并可通过 参数调节行为。主要节点及其用法如下:
4.1摄像头(采集节点)
- 可执行名:
camera_node
(包名jdk_camera_node
) - 启动方式:
ros2 run jdk_camera_node camera_node [--ros-args -p 参数:=值 ...]
。 - 支持参数:
device
(string):摄像设备路径,默认"/dev/video50"
。根据实际情况调整(例如"/dev/video0"
)。width
(int):图像宽度,默认1280
。height
(int):图像高度,默认720
。socket_path
(string):FD 传输服务器路径,默认"/tmp/jdk_fd_socket"
。此套接字用于帧缓冲区传递。
- 说明:摄像头节点打开
device
所指的 V4L2 设备,获取 NV12 格式帧,并周期性发布至/camera_frames
话题;同时启动一个 UNIX Socket 服务(路径为socket_path
),供帧传输(DMA)使用。可使用参数-p device:=/dev/video0 -p width:=1280 -p height:=720
指定自定义设置。
4.2硬件编码节点(VENC)
- 可执行名:
venc_node
(包名jdk_venc_node
) - 启动方式:
ros2 run jdk_venc_node venc_node [--ros-args -p 参数:=值 ...]
。 - 支持参数:
width
(int):输入帧宽度,默认1920
。height
(int):输入帧高度,默认1080
。payload
(int):编码格式,默认CODING_H264
(H.264)。format
(int):像素格式,默认PIXEL_FORMAT_NV12
(NV12)。use_dma
(bool):是否使用 DMA (默认true
)。venc_fd_socket
(string):编码后帧输出的 FD 套接字路径,默认"/tmp/jdk_fd_enc2out.sock"
。- (注意:还有内部订阅套接字,默认指向
"/tmp/jdk_fd_socket"
,通常无需手动设置。)
- 说明:编码节点订阅
/camera_frames
话题(SensorData QoS),接收原始帧后在内部线程中进行 H.264 编码。编码后通过自定义消息JdkFrameMsg
发布到/encoded_frames
。如需其他编码格式,可调整payload
(例如设为CODING_H265
);use_dma
控制是否使用 DMA 传输方式。
4.3硬件解码节点(VDEC)
- 可执行名:
vdec_node
(包名jdk_vdec_node
) - 启动方式:
ros2 run jdk_vdec_node vdec_node [--ros-args -p 参数:=值 ...]
。 - 支持参数:
width
(int):解码后帧宽度,默认1920
。height
(int):解码后帧高度,默认1080
。payload
(int):编码格式,默认CODING_H264
。format
(int):像素格式,默认PIXEL_FORMAT_NV12
。use_dma
(bool):是否使用 DMA,默认true
。dec_fd_socket
(string):解码后帧输出 FD 套接字路径,默认"/tmp/jdk_fd_dec2out.sock"
。venc_fd_socket
(string):编码节点输出套接字路径,默认"/tmp/jdk_fd_enc2out.sock"
(编码节点的venc_fd_socket
)。
- 说明:解码节点订阅
/encoded_frames
话题,收到编码帧后进行解码,并将解码后的原始帧发布到/decoded_frames
。通常将venc_fd_socket
设置为与编码节点一致,以接收编码后数据;默认参数已匹配编码节点的输出路径。
4.4视频显示节点(VO)
- 可执行名:
vo_node
(包名jdk_vo_node
) - 启动方式:
ros2 run jdk_vo_node vo_node [--ros-args -p 参数:=值 ...]
。 - 支持参数:
width
(int):帧宽度,默认1920
。height
(int):帧高度,默认1080
。format
(int):像素格式,默认PIXEL_FORMAT_NV12
。use_dma
(bool):是否使用 DMA,默认true
。cam_fd_socket
(string):摄像头帧 FD 套接字路径,默认"/tmp/jdk_fd_socket"
。
- 说明:显示节点订阅
/camera_frames
话题,并调用硬件视频输出(JdkVo
)直接在屏幕上显示图像(覆盖层输出)。常用来验证摄像头采集效果。若不需显示功能,可忽略此节点。
4.5推理节点(Infer)
- 可执行名:
infer_node
(包名jdk_infer_node
) - 启动方式:
ros2 run jdk_infer_node infer_node [--ros-args -p 参数:=值 ...]
。 - 支持参数:
socket_path
(string):FD 套接字路径,默认"/tmp/jdk_fd_socket"
(与camera_node
相同)。
- 说明:推理节点订阅
/camera_frames
,使用内置的 YOLOv8 ONNX 模型(yolov8n.q.onnx
)对摄像头数据进行目标检测,并在终端打印识别结果。它通过 FD 方式获取帧数据,无需显示功能。用户可参考示例yolov8n.q.onnx
替换模型。
参数说明汇总:
节点 | 参数 | 类型 | 默认值 | 含义 |
---|---|---|---|---|
camera_node | device | string | "/dev/video50" | 摄像设备节点路径(V4L2) |
width | int | 1280 | 图像宽度(像素) | |
height | int | 720 | 图像高度(像素) | |
socket_path | string | "/tmp/jdk_fd_socket" | FD 传输套接字路径 | |
venc_node | width | int | 1920 | 输入帧宽度 |
height | int | 1080 | 输入帧高度 | |
payload | int | CODING_H264 (H.264) | 编码格式 | |
format | int | PIXEL_FORMAT_NV12 (NV12) | 像素格式FourCC | |
use_dma | bool | true | 是否使用 DMA 传输 | |
venc_fd_socket | string | "/tmp/jdk_fd_enc2out.sock" | 编码输出套接字路径 | |
vdec_node | width | int | 1920 | 解码后帧宽度 |
height | int | 1080 | 解码后帧高度 | |
payload | int | CODING_H264 (H.264) | 编码格式 | |
format | int | PIXEL_FORMAT_NV12 (NV12) | 像素格式FourCC | |
use_dma | bool | true | 是否使用 DMA 传输 | |
dec_fd_socket | string | "/tmp/jdk_fd_dec2out.sock" | 解码输出套接字路径 | |
venc_fd_socket | string | "/tmp/jdk_fd_enc2out.sock" | 编码输入套接字路径 | |
vo_node | width | int | 1920 | 帧宽度 |
height | int | 1080 | 帧高度 | |
format | int | PIXEL_FORMAT_NV12 (NV12) | 像素格式FourCC | |
use_dma | bool | true | 是否使用 DMA | |
cam_fd_socket | string | "/tmp/jdk_fd_socket" | 摄像头输入套接字路径 | |
infer_node | socket_path | string | "/tmp/jdk_fd_socket" | FD 套接字路径 |
(可通过 --ros-args -p 参数:=值
方式修改参数,如 -p device:=/dev/video0
等。)
5.节点接口说明
系统主要使用自定义消息 jdk_interfaces/msg/JdkFrameMsg
在节点之间传输图像帧,典型话题接口如下:
/camera_frames
– 消息类型jdk_interfaces/JdkFrameMsg
发布者:camera_node
。每帧包含原始相机数据(默认 NV12 格式)。帧消息字段包括:时间戳 stamp
、帧ID frame_id
(UUID)、width
、height
、stride
、size
、pix_format
(V4L2 FourCC 码)、is_dma
(是否使用 DMA 传输)、dma_fd
(DMA 文件描述符)和 data
(字节数组)。当 is_dma=true
时,实际图像数据存于 dma_fd
指向的缓冲,data
为空;否则图像字节存在 data
数组中(NV12 排列)。
/encoded_frames
– 消息类型jdk_interfaces/JdkFrameMsg
发布者:venc_node
。包含编码后的帧数据(通常为 H.264 码流),其 pix_format
对应编码类型(如 H264/H265 ),data
中储存编码字节或使用 dma_fd
传输。
/decoded_frames
– 消息类型jdk_interfaces/JdkFrameMsg
发布者:vdec_node
。包含解码后的原始帧(NV12 格式),可供后续处理或显示节点使用。
注:当前未定义任何 ROS 服务(Service)或动作(Action)。节点间全部通过上述话题传输数据。用户可以订阅 /camera_frames
等话题,在回调中获取 JdkFrameMsg
,然后将 NV12 图像数据转换为可视格式(例如使用 OpenCV 转换为 RGB)进行处理或可视化。
6.使用示例
以下示例展示了从编译到运行的典型流程及如何获取摄像头数据:
6.1编译工作空间
按前述步骤构建所有 ROS 包,假设当前工作空间在 ~/ros2_ws
,执行:
cd ~/ros2_ws
source /opt/ros/humble/setup.bash
colcon build --symlink-install
source install/setup.bash
这样所有节点都已编译完成[docs.ros.org](https://docs.ros.org/en/foxy/Tutorials/Beginner-Client-Libraries/Creating-Your-First-ROS2-Package.html#:~:text=Putting packages in a workspace,to build each package individually)。
6.2运行(摄像头节点)
在一个终端中,启动摄像头采集节点:
ros2 run jdk_camera_node camera_node --ros-args \
-p device:=/dev/video50 -p width:=1280 -p height:=720
这会打开 /dev/video0
设备并开始发布 /camera_frames
。根据需要修改 device
、width
、height
等参数。