CeleX5-ROS: CeleX5-MIPI 事件相机的一个完善的 ROS 工具包
我在前段时间为 CeleX5-MIPI 系列相机开发了一套完善的 ROS 下的驱动。CeleX5-MIPI 是一款国产的事件相机,具有 1280x800 的分辨率。项目已开源在:https://github.com/kehanXue/CeleX5-ROS 。
视频 demo:
本篇是项目在 Github 的中文版 README.md,所以本文中的链接是相对链接,这将导致它们在本文中不可用。请移步项目的 地址,非常感谢!
CeleX5-ROS
The ROS packages for CeleX™ CeleX5-MIPI Dynamic Vision Sensor.
本仓库提供了 CeleX5-MIPI 相机在 ROS 下多个功能包和示例,包括有:
celex5_ros
:提供了 CeleX5-MIPI 相机的 ROS 下的较为完善驱动。celex5_msgs
:为 CeleX5-MIPI 相机定制的 ROS 消息类型。celex5_calibration
:提供了有关于celex5_calibration
基于 Events 数据进行标定相关的工具和教程。
本仓库代码主要遵从 Google C++ 编程风格
介绍
CeleX™ 是针对机器视觉而设计的智能图像传感器系列。传感器中的每一像素点能够独立自主地监测相对光强的变化,并在到达阈值时被激发发出被读出信号。行和列仲裁电路实时处理像素激发信号,并确保即使同时接收到多个请求时能够按有序的方式逐一处理。传感器依据被激发的事件,输出连续的异步数据流,而不是图像帧。CeleX™ 传感器监测的运动物体速度不再受传统的曝光时间和帧速率限制。它可以侦测高达万帧 / 秒昂贵高速相机才能获取到的高速物体运动信息,而且还能大幅降低后端处理量。
CeleX-5 是一款多功能智能图像传感器,具有一百万像素(分辨率为:1280*800)和片上集成的一些附加功能(如光流)。传感器支持几种不同的输出格式:纯二进制地址事件,具有像素强度信息或定时信息的地址事件。此外,传感器的读出方案可以是异步数据流或同步全帧。输出格式和读出方案的不同组合使该传感器具有很大的灵活性,总共支持 6 种独立的操作模式(但是其中有一种未在 sdk 中提供相应接口)。为了进一步满足不同应用的要求,传感器还可以配置为 Loop 模式,可以在三种不同模式之间自动切换。
ROS 是目前很主流的实验平台,提供了丰富的开发接口和资源。但在 CeleX™官方开源仓库 中,关于 ROS 下的示例非常的不完善:
-
官方的 SDK 版本已经更新到了 v2.0 版本,然而其 ROS-Sample 支持的版本仍停留在 v1.6 版本。
-
官方的 ROS-Sample 仅为一个简单的示例,只输出一个工作模式下的一种图像,未提供全面且方便的调参功能和界面。
因此,为了更为方便的利用 ROS 提供的资源,我开发了这个仓库中的内容。
概要
本仓库提供了 CeleX5-MIPI 相机在 ROS 下多个功能包和示例,包括有:
-
celex5_ros
:提供了 CeleX5-MIPI 相机的 ROS 下的较为完善驱动,可根据用户需求自由配置输出多路数据(原始 Event 数据、IMU 数据、灰度帧、光流信息等),并提供了rqt_reconfigure
调参面板以支持动态调参。更多细节。目前仅仅在 CeleX5-MIPI 设备上测试通过,由于手里没有 CeleX5 系列的其他产品所以无法测试。
-
celex5_msgs
:为 CeleX5-MIPI 相机定制的 ROS 消息类型。 -
celex5_calibration
:提供了有关于celex5_calibration
基于 Events 数据进行标定相关的工具和教程,包括标定板生成(目前仅支持闪烁的棋盘格,其他类型待加入)、内参标定、与传统相机进行外参标定(使用 Kalibr)、同步收集与定制发布标定所需的图像数据、与传统相机进行时间戳对齐(TODO,目前存在问题)等工具。更多细节
建议在使用前,请首先认真阅读 CeleX 官方提供的 快速入门手册和 API 文档的概念部分,对基本名词术语有大概认识。
编译与运行
-
编译
1
2
3
4
5
6
7
8mkdir -p ~/celex_ws/src
cd ~/celex_ws/src
git clone git@github.com:kehanXue/CeleX5-ROS.git
git submodule update --init --recursive
# Or with http: `git clone https://github.com/kehanXue/CeleX5-ROS.git`
cd ..
rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO
catkin_make # Or use `catkin build`如果过程中报少哪些依赖库的错误,安装即可。
-
运行
celex5_ros
更多细节首先将相机连接到电脑上。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54source ~/celex_ws/devel/setup.bash # Or source setup.zsh when you use zsh
roslaunch celex5_ros celex5_ros_node.launch
# In a new Terminal
rosrun rqt_reconfigure rqt_reconfigure # Open rqt_reconfigure to config
```无报错即正常运行。使用`rostopic list`即可看到发布的话题,使用`rivz`或者`image_view`订阅相对应图像话题即可看到发布的图像。某图像话题中是否发布数据由参数配置、上表的相机工作模式所共同决定。```bash
$ rostopic list
/celex5_mipi/display/accumulated_img/camera_info
/celex5_mipi/display/accumulated_img/raw_image
/celex5_mipi/display/binary_img/camera_info
/celex5_mipi/display/binary_img/raw_image
/celex5_mipi/display/count_img/camera_info
/celex5_mipi/display/count_img/raw_image
/celex5_mipi/display/denoised_binary_img/camera_info
/celex5_mipi/display/denoised_binary_img/raw_image
/celex5_mipi/display/full_frame_img/camera_info
/celex5_mipi/display/full_frame_img/raw_image
/celex5_mipi/display/gray_img/camera_info
/celex5_mipi/display/gray_img/raw_image
/celex5_mipi/display/in_pixel_img/camera_info
/celex5_mipi/display/in_pixel_img/raw_image
/celex5_mipi/display/optical_flow_direction_img/camera_info
/celex5_mipi/display/optical_flow_direction_img/raw_image
/celex5_mipi/display/optical_flow_img/camera_info
/celex5_mipi/display/optical_flow_img/raw_image
/celex5_mipi/display/optical_flow_speed_img/camera_info
/celex5_mipi/display/optical_flow_speed_img/raw_image
/celex5_mipi/display/parameter_descriptions
/celex5_mipi/display/parameter_updates
/celex5_mipi/display/superimposed_img/camera_info
/celex5_mipi/display/superimposed_img/raw_image
/celex5_mipi/events
/celex5_mipi/imu_data
/celex5_mipi/polarity_img/camera_info
/celex5_mipi/polarity_img/raw_image
/celex5_mipi/sensor/parameter_descriptions
/celex5_mipi/sensor/parameter_updates
/rosout
/rosout_agg
```其中原始 event 数据的话题:`/celex5_mipi/events`imu 数据的话题(注意由于 CeleX5 原始 imu 数据获取的方式,导致 imu 话题与 ROS 中标准的 IMU 话题的消息类型不同):`/celex5_mipi/imu_data`通过`image_view`查看某一图像:```bash
rosrun image_view image_view image:=/celex5_mipi/display/binary_img/raw_image
```3. 使用`celex5_calibration`
更多细节:[链接](celex5_calibration)
提供了一系列基于 Events 数据进行相机参数标定的办法。
- 标定工具的生成
运行:
```bash
rosrun celex5_ros pattern_generator_node
# In a new Terminal
rosrun rqt_reconfigure rqt_reconfigure # Open rqt_reconfigure to config更多细节:链接
-
基于 ROS 中的 camera_calibration 工具包进行的内参标定。(如果要标定与其他相机的外参,ROS 中的这个工具仅支持分辨率一样的…)
安装:
1
sudo apt install ros-$ROS_DISTRO-camera-calibration
CeleX5-MIPI 进行基于该方法进行标定的具体过程:链接
-
基于 Kalibr 的标定,支持同时进行内参、与传统相机的外参标定。基于 Event 数据。
更多细节:链接
同时提供了收集标定数据的一系列工具。
-
与其他相机进行时间戳的标定。
TODO,目前仍存在问题。链接
-
仍存在问题
celex5_ros
- 实现的 Nodelet 接口仍存在问题(不过 ros node 版本是完全正常工作的)。在通过 nodelet 加载相机的参数文件的过程中,解析 xml 文件会出现乱码。调了好久都没找到问题,如果大家提供解决建议的话我会非常感谢。
- 关于文档中的
Multi_Read_Optical_Flow_Mode
模式,未在 SDK 中找到相关接口。// TODO - 暂未添加生成 FPN 的功能,请仍使用 CeleX 官方提供的 GUI Demo 进行 FPN 的生成(其 Linux 下的 Demo 运行可能会直接报段错误,Windows 下的较为稳定一些)。
- 暂未提供 CeleX SDK 里的有关录制 bin 文件的功能,但 ROS 下我们可以使用 ROS bag 来进行录制。
celex5_calibration
- 关于与其他相机进行时间戳标定的相关功能还未完成。