English| 简体中文
Get image data from USB camera and publish it through the image/hbmem_image topic.
ROS package:
- rclcpp
- sensor_msgs
- hbm_img_msgs
- v4l-utils
hbm_img_msgs is a custom message format used to publish shared memory type image data, defined in hobot_msgs.
- Programming Language: C/C++
- Development Platform: X3/X86
- System Version: Ubuntu 20.04
- Compilation Toolchain: Linux GCC 9.3.0 / Linaro GCC 9.3.0
Supports compilation on X3/X86 Ubuntu system and cross-compilation using docker on X86 Ubuntu.
-
Compilation Environment Confirmation
- Ubuntu system is Ubuntu 20.04.
- 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
-
Compilation
Compilation command: colcon build --packages-select hobot_usb_cam
-
Compilation Environment Confirmation
- Compilation in docker, and TogetherROS is installed in docker. Instructions for docker installation, cross-compilation, TogetherROS compilation, and deployment can be found in the README.md of the robot development platform robot_dev_config repository.
-
Compilation
- Compilation command:
export TARGET_ARCH=aarch64
export TARGET_TRIPLE=aarch64-linux-gnu
export CROSS_COMPILE=/usr/bin/$TARGET_TRIPLE-
colcon build --packages-select hobot_usb_cam \
--merge-install \
--cmake-force-configure \
--cmake-args \
--no-warn-unused-cli \
-DCMAKE_TOOLCHAIN_FILE=`pwd`/robot_dev_config/aarch64_toolchainfile.cmake \
-DTHIRDPARTY=ON \
-DBUILD_TESTING:BOOL=OFF \
-DCMAKE_BUILD_RPATH="`pwd`/build/poco_vendor/poco_external_project_install/lib/;`pwd`/build/libyaml_vendor/libyaml_install/lib/"
WebSocket receives image messages and intelligent result messages, matches them based on timestamps, and then outputs them for rendering on the web interface; it can also display images independently.
Image messages support sensor_msgs::msg::Image
and shared_mem
type hbm_img_msgs::msg::HbmMsg1080P
messages, which must be jpeg-format data output by Hobot codec.
Intelligent result messages support ai_msgs::msg::PerceptionTargets
messages, where header.stamp
must match the timestamp of the image message corresponding to that result; WebSocket uses this field to match messages, and the width and height of the intelligent result must match the resolution of the received image.
The specific dependencies include:
- mipi_cam: starts mipi cam and publishes images in nv12 format
- hobot_codec: encodes nv12 images published by mipi_cam into jpeg format required by WebSocket
- mono2d_body_detection: receives nv12 format data, performs algorithm inference, and publishes perception messages for human body, head, face, and hand bounding boxes
Parameter Name | Explanation | Type | Supported Configuration | Required | Default Value |
---|---|---|---|---|---|
frame_id | Message Identifier | string | Set frame_id name as needed | No | "default_usb_cam" |
framerate | Frame Rate | int | Select based on sensor support | No | 30 |
image_height | Image Height | int | Select based on sensor support | No | 640 |
image_width | Image Width | int | Select based on sensor support | No | 480 |
io_method | I/O Method | string | mmap/read/userptr | No | "mmap" |
pixel_format | Pixel Format | string | Only supports mjpeg | No | "mjpeg" |
video_device | Video Device | string | Device name usually /dev/videox | Yes | "/dev/video0" |
zero_copy | Enable Zero Copy | bool | True/False | No | "True" |
camera_calibration_file_path | Path to Camera Calibration File | string | Configure based on actual path of camera calibration file | No | Empty |
After successful compilation, copy the generated install path to the Horizon X3 development board (ignore copying step if compiling on X3/X86 Ubuntu), and execute the following command to run:
source setup.bash
export COLCON_CURRENT_PREFIX=./install
source ./install/setup.bash
Run hobot_usb_cam using launch
ros2 launch hobot_usb_cam hobot_usb_cam.launch.py
Run hobot_usb_cam using command line
ros2 run hobot_usb_cam hobot_usb_cam --ros-args --log-level info --ros-args -p video_device:="/dev/video8"
Note: Configure the video_device parameter according to the actual situation.
export ROS_LOG_DIR=/userdata/
export LD_LIBRARY_PATH=${LD_LIBRARY_PATH}:./install/lib/
./install/lib/hobot_usb_cam/hobot_usb_cam --ros-args --log-level info --ros-args -p video_device:="/dev/video8"
Currently, using "zero-copy" only supports three resolutions: 19201080, 960540, 640*480. If other resolutions are needed, create corresponding ROS messages.
When the configured resolution is not supported by hardware, a resolution close to the specified one will be automatically chosen for image acquisition.
hobot_usb_cam does not have a default calibration file. The parameter camera_calibration_file_path can be used for specifying one. Camera intrinsic parameters will be published on topic: /camera_info.
If the camera calibration file is not specified, a warning about the inability to publish camera information will appear, but it will not affect the publishing of image messages.
root@ubuntu:~# ros2 run hobot_usb_cam hobot_usb_cam --ros-args --log-level info --ros-args -p video_device:="/dev/video8"
[ERROR] [1661872247.616929290] [hobot_usb_cam]: Camera calibration file: not exist!
[WARN] [1661872247.617759426] [hobot_usb_cam]: get camera calibration parameters failed[INFO] [1661864867.688989561] [hobot_usb_cam]: Set resolution to 640x480
[INFO] [1661864867.718194946] [hobot_usb_cam]: Set framerate to be 30
[WARN] [1661864867.949372256] [hobot_usb_cam]: Unable to publish camera info.
[INFO] [1661864867.949684008] [hobot_usb_cam]: publish image 640x480 encoding:2 size:82225
[WARN] [1661864867.981565221] [hobot_usb_cam]: Unable to publish camera info.
[INFO] [1661864867.981989001] [hobot_usb_cam]: publish image 640x480 encoding:2 size:82194
[WARN] [1661864868.017477066] [hobot_usb_cam]: Unable to publish camera info.
[INFO] [1661864868.017740158] [hobot_usb_cam]: publish image 640x480 encoding:2 size:82427
[WARN] [1661864868.049163958] [hobot_usb_cam]: Unable to publish camera info.
[INFO] [1661864868.049382305] [hobot_usb_cam]: publish image 640x480 encoding:2 size:82302
[WARN] [1661864868.081569634] [hobot_usb_cam]: Unable to publish camera info.
[INFO] [1661864868.082001830] [hobot_usb_cam]: publish image 640x480 encoding:2 size:88354
[WARN] [1661864868.117489411] [hobot_usb_cam]: Unable to publish camera info.
If the camera calibration parameter path is specified, the camera runs successfully and obtains the camera calibration file as follows
[INFO] [1661865235.667735376] [hobot_usb_cam]: [get_cam_calibration]->parse calibration file successfully
[INFO] [1661865235.925195867] [hobot_usb_cam]: Set resolution to 640x480
[INFO] [1661865235.954375056] [hobot_usb_cam]: Set framerate to be 30
[INFO] [1661865236.185936360] [hobot_usb_cam]: publish camera info.
[INFO] [1661865236.186272480] [hobot_usb_cam]: publish image 640x480 encoding:2 size:83446
[INFO] [1661865236.217417891] [hobot_usb_cam]: publish camera info.
[INFO] [1661865236.217865635] [hobot_usb_cam]: publish image 640x480 encoding:2 size:83342
[INFO] [1661865236.252895697] [hobot_usb_cam]: publish camera info.
[INFO] [1661865236.253140610] [hobot_usb_cam]: publish image 640x480 encoding:2 size:83542
[INFO] [1661865236.285348631] [hobot_usb_cam]: publish camera info.
[INFO] [1661865236.285770625] [hobot_usb_cam]: publish image 640x480 encoding:2 size:83430# Frequently Asked Questions