3.3. 图像编解码
功能介绍
功能与ROS image_transport package类似,旭日X3派采用硬件单元加速MJPEG/H264/H265与BGR8/RGB8/NV12格式之间转换,可以大幅降低CPU占用的同时提升格式转换效率,X86平台仅支持MJPEG与BGR8/RGB8/NV12格式之间的转换。
支持平台
平台 | 运行方式 | 示例功能 |
---|---|---|
旭日X3派 | Ubuntu 20.04 | 启动MIPI摄像头获取图像,然后进行图像编码,最后通过Web展示 |
X86 | Ubuntu 20.04 | 使用图像发布工具发布YUV图像,然后进行图像编码,最后通过Web展示 |
准备工作
旭日X3派
旭日X3派已烧录好地平线提供的Ubuntu 20.04系统镜像。
旭日X3派已成功安装TogetheROS.Bot。
旭日X3派已连接摄像头F37或其他MIPI摄像头。
X86平台
X86环境已配置Ubuntu 20.04系统镜像。
X86环境已安装X86版本tros.b。
使用方式
下面以 JPEG 编码为例,介绍从摄像头或图像发布工具获取NV12格式图片数据,经过JPEG压缩编码后,实现在PC的Web端预览图片。
获取YUV数据,并启动JPGE编码:
旭日X3派
通过SSH登录旭日X3派,如
/opt/tros/share/hobot_codec/launch/hobot_codec.launch.py
使用mipi_cam作为数据来源,配置hobot_codec输入为NV12格式,输出为JPEG格式,可修改mipi_cam为实际使用的sensor型号。from launch import LaunchDescription from launch_ros.actions import Node def generate_launch_description(): return LaunchDescription([ # 启动图片发布pkg Node( package='mipi_cam', executable='mipi_cam', output='screen', parameters=[ {"out_format": "nv12"}, {"image_width": 960}, {"image_height": 544}, {"io_method": "shared_mem"}, {"video_device": "F37"} ], arguments=['--ros-args', '--log-level', 'error'] ), # 启动JPEG图片编码&发布pkg Node( package='hobot_codec', executable='hobot_codec_republish', output='screen', parameters=[ {"channel": 1}, {"in_mode": "shared_mem"}, {"in_format": "nv12"}, {"out_mode": "ros"}, {"out_format": "jpeg"}, {"sub_topic": "/hbmem_img"}, {"pub_topic": "/image_jpeg"} ], arguments=['--ros-args', '--log-level', 'error'] ) ])
启动应用:
// 配置 tros.b 环境: source /opt/tros/setup.bash // launch 方式启动 ros2 launch hobot_codec hobot_codec.launch.py
X86平台
// 配置 tros.b 环境: source /opt/tros/setup.bash //从tros.b的安装路径中拷贝出运行示例需要的图片文件 cp -r install/lib/hobot_image_publisher/config/ . // 启动图像发布节点 ros2 run hobot_image_publisher hobot_image_pub --ros-args -p image_source:=./config/test1.nv12 -p fps:=20 -p output_image_w:=960 -p output_image_h:=544 -p image_format:=nv12 -p source_image_w:=960 -p source_image_h:=544 //启动JPEG图片编码&发布pkg ros2 run hobot_codec hobot_codec_republish --ros-args -p channel:=1 -p in_mode:=shared_mem -p in_format:=nv12 -p out_mode:=ros -p out_format:=jpeg -p sub_topic:=/hbmem_img -p pub_topic:=/image_jpeg
Web端查看JPEG编码图像,另起一个终端:
source /opt/tros/local_setup.bash ros2 launch websocket hobot_websocket.launch.py ros2 run websocket websocket --ros-args -p image_topic:=/image_jpeg -p image_type:=mjpeg -p only_show_image:=true
PC打开浏览器(chrome/firefox/edge)输入http://IP:8000,IP为旭日X3派/X86设备IP地址,点击左上方Web端展示即可查看JPEG编码的实时画面
注意事项
如遇到 Hobot codec 节点启动异常,可通过下述步骤进行问题排查:
是否设置 tros.b 环境
参数是否正确,具体参考Hobot_codec README.md