English| 简体中文
By reading this document, users can easily capture video stream data from the mipi camera on the Horizon X3 development board, and publish image data that meets the ROS standard through the ROS platform for other ROS Nodes to subscribe to. Currently supports mipi standard devices such as F37, IMX415, GC4663, IMX219, IMX477, OV5647. The Mipi_cam Node package is part of the Horizon Robot Development Platform, based on the Horizon VIO and ROS2 Node for secondary development, providing simple and easy-to-use camera data acquisition functions for application development, avoiding redundant work in obtaining video. Support for sharing memory publishing.
Dependencies: ros package:
- sensor_msgs
- hbm_img_msgs
The hbm_img_msgs package is a custom image message format in hobot_msgs, used for image transmission in shared memory scenarios.
- Programming Language: C/C++
- Development Platform: X3/X86
- Operating System Version: Ubuntu 20.04
- Compilation Toolchain: Linux GCC 9.3.0/Linaro GCC 9.3.0
The source code includes the mipi_cam package. After compiling the mipi_cam, the header files, dynamic libraries, and dependencies are installed in the install/mipi_cam path.
Supports compilation on the X3 Ubuntu system and cross-compilation using docker on the PC, and supports controlling the dependencies and functions of the compiled pkg through compilation options.
- Compilation Environment Verification
- The X3 Ubuntu system is installed on the board.
- The current compilation terminal has set the TogetherROS environment variable:
source PATH/setup.bash
. Where PATH is the installation path of TogetherROS. - ROS2 compilation tool colcon is installed, installation command:
pip install -U colcon-common-extensions
- Dependencies are installed, see Dependency section for details
- Compilation:
colcon build --packages-select mipi_cam
.
- Compilation Environment Verification
- Compilation in docker, with tros already installed in docker. For docker installation, cross-compilation instructions, tros compilation, and deployment instructions, refer to the README.md in the robot development platform robot_dev_config repo.
- The hbm_img_msgs package has been compiled (see Dependency section for compilation method)
- Compilation- Compilation command:
export TARGET_ARCH=aarch64
export TARGET_TRIPLE=aarch64-linux-gnu
export CROSS_COMPILE=/usr/bin/$TARGET_TRIPLE-
colcon build --packages-select mipi_cam \
--merge-install \
--cmake-force-configure \
--cmake-args \
--no-warn-unused-cli \
-DCMAKE_TOOLCHAIN_FILE=`pwd`/robot_dev_config/aarch64_toolchainfile.cmake
To run, users can directly start ros2 with the following command:
export COLCON_CURRENT_PREFIX=./install
source ./install/setup.bash
# Default F37 sensor
ros2 run mipi_cam mipi_cam
Using shared memory communication, only supports publishing images on the hbmem_img topic.
The node will publish on the /image_raw topic, corresponding to images in the rgb8 format, and publish on the shared memory topic: hbmem_img. The camera intrinsics are published on the /camera_info topic.
Using rqt_image_view, you can view the published image topics and also use image-consuming nodes. For example, use the examples in this repo to directly retrieve images for inference and other applications.
You can set the sensor to use, the encoding format, and the resolution for publishing images.
Use the video_device parameter to set the sensor to use. Currently supports F37 (default), IMX415 (set using --ros-args -p video_device:=IMX415), with default resolutions of 1920x1080 for F37 and 3840x2160 for IMX415.
Use the image_width and image_height parameters to set the resolution for publishing images:
ros2 run mipi_cam mipi_cam --ros-args --log-level info --ros-args -p image_width:=960 -p image_height:=540 -p video_device:=F37
Use the out_format parameter to set the encoding format for publishing images, default is in bgr8 format, supports nv12 format (/image_raw topic). For example, to publish nv12 format images with a resolution of 960x540 using the F37 sensor:
ros2 run mipi_cam mipi_cam --ros-args --log-level info --ros-args -p out_format:=nv12 -p image_width:=960 -p image_height:=540 -p video_device:=F37
Use the io_method
parameter to set the method of publishing images. Currently, the topic published by shared_mem
is fixed to: hbmem_img
ros2 run mipi_cam mipi_cam --ros-args -p io_method:=shared_mem
Use the camera_calibration_file_path
parameter to set the path to the camera calibration file. Here, we take the example of using a GC4663 camera and reading the GC4663_calibration.yaml file under the config directory (See Attention below for print information):
# Copy the camera calibration file used for demonstration in the config directory based on the actual installation path
cp -r install/lib/mipi_cam/config/ .
ros2 run mipi_cam mipi_cam --ros-args -p camera_calibration_file_path:=./config/GC4663_calibration.yaml -p video_device:=GC4663
Copy the install
directory cross-compiled in Docker to the Linaro system, for example: /userdata. First, specify the path to the library dependencies, for example:
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:/userdata/install/lib
Modify the path of ROS_LOG_DIR, otherwise it will be created under the /home directory, you need to run mount -o remount,rw /
to create logs under /home
export ROS_LOG_DIR=/userdata/
Run mipi_cam
// Default parameter method
/userdata/install/lib/mipi_cam/mipi_cam
// With parameters
#/userdata/install/lib/mipi_cam/mipi_cam --ros-args -p image_width:=960 -p image_height:=540
Run using launch file:
ros2 launch install/share/mipi_cam/launch/mipi_cam.launch.py
Currently, the data output by the device is in nv12 format, converted to rgb8 format, not using OpenCV, with a performance time of around 100ms for 1920*1080 resolution. Compressed images need to be supported using a relay method:
ros2 run image_transport republish raw compressed --ros-args --remap in:=/image_raw --remap out/compressed:=/image_raw/compressed
This will create a compressed topic, where you can subscribe to compressed image topics using a subscriber at the receiving end, for example:
ros2 run image_subscribe_example subscribe_example --ros-args -p sub_img_topic:=/image_raw/compressed
Log Display:
root@xj3ubuntu:/userdata/cc_ws/tros_ws# ros2 run image_subscribe_example subscribe_example --ros-args -p sub_img_topic:=/image_raw/compressed
[WARN] [1648302887.615608845] [example]: This is image_subscriber example!
[WARN] [1648302887.699318639] [ImageSubscriber]: Update sub_img_topic with topic_name: /image_raw/compressed
[WARN] [1648302887.701353516] [ImageSubscriber]: Update save_dir:
[WARN] [1648302887.701502469] [ImageSubscriber]: Create subscription with topic_name: /image_raw/compressed
```[WARN] [1648302887.705133283] [example]: ImageSubscriber init!
[WARN] [1648302887.706179033] [example]: ImageSubscriber add_node!
[INFO] [1648302889.318928227] [img_sub]: Recv compressed img
[WARN] [1648302889.319329711] [img_sub]: Sub compressed img fps = 1
[INFO] [1648302889.319478247] [img_sub]: Recv compressed img: rgb8; jpeg compressed bgr8, stamp: 1648302889.92334955, tmlaps(ms): 227, data size: 33813
Please note: to enable this feature, you need to install the ROS package image_transport_plugins using the command: sudo apt-get install ros-foxy-image-transport-plugins
If the camera operates successfully and reads the camera calibration file normally, the following information will be output. mipi_cam provides calibration files for two camera models, GC4663 and F37. By default, it reads the F37_calibration.yaml file under the config directory. If using the GC4663 camera, please change the path to read the camera calibration file!
[INFO] [1661863164.454533227] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1544567->laps=102 ms.
[INFO] [1661863164.458727776] [mipi_node]: publish camera info.
[INFO] [1661863164.562431009] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1544674->laps=103 ms.
[INFO] [1661863164.566239194] [mipi_node]: publish camera info.
[INFO] [1661863164.671290847] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1544782->laps=104 ms.
[INFO] [1661863164.675211155] [mipi_node]: publish camera info.
[INFO] [1661863164.780465260] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1544891->laps=104 ms.
[INFO] [1661863164.784429400] [mipi_node]: publish camera info.
[INFO] [1661863164.887891555] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1545000->laps=103 ms.
[INFO] [1661863164.891738656] [mipi_node]: publish camera info.
[INFO] [1661863164.994701993] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1545107->laps=103 ms.
[INFO] [1661863164.998455013] [mipi_node]: publish camera info.
[INFO] [1661863165.100916367] [mipi_cam]: [get_image]->enc=bgr8,step=5760, w:h=1920:1080,sz=3110400,start 1545214->laps=102 ms.
[INFO] [1661863165.104211776] [mipi_node]: publish camera info.