TROS DataFlow - USB Camera & mipi Sensor - rtsp

TROS DataFlow - USB Camera & mipi Sensor - rtsp

使用TROS的功能,通过USB或者mipi摄像头得到MJPEG数据,推理YOLOv5节点,得到目标检测结果,通过ros_rtsp将nv12数据变成标准的H264/H265码流推出。

DataFlow示意图

mipi

TROS DataFlow - USB Camera & mipi Sensor - rtsp_第1张图片

USB

TROS DataFlow - USB Camera & mipi Sensor - rtsp_第2张图片

H264/H265推流展示

TROS DataFlow - USB Camera & mipi Sensor - rtsp_第3张图片

编译ros_rtsp_server

系统版本 2.1.0, sudo apt update有sunrise.horizon.cc地平线源的情况下, sudo apt upgrade到最新,板端编译耗时约42秒。

sudo apt install -y liblivemedia-dev 
pip install -U colcon-common-extensions
git clone https://github.com/zhukao/ros_rtsp_server.git
source /opt/tros/setup.bash
colcon build --packages-up-to ros_rtsp_server --install-base /opt/tros --merge-install

mipi Camera Node拆解

mipi_cam

Sensor: GC4663

ros2 run mipi_cam mipi_cam \
--ros-args --log-level error \
--ros-args -p  io_method:=shared_mem \
--ros-args -p  out_format:=nv12 \
--ros-args -p  image_width:=2560 \
--ros-args -p  image_height:=1440 

hobot_dnn

ros2 run dnn_node_example example \
--ros-args --log-level warn \
--ros-args -p feed_type:=1 \
--ros-args -p dump_render_img:=0 \
--ros-args -p is_shared_mem_sub:=1 \
--ros-args -p config_file:=/opt/tros/lib/dnn_node_example/config/yolov5workconfig.json  \
--ros-args -p msg_pub_topic_name:=yolov5_results

hobot_codec_A (nv12 to MJPEG)

ros2 run hobot_codec hobot_codec_republish \
--ros-args --log-level warn \
--ros-args -p channel:=2 \
--ros-args -p in_format:=nv12 \
--ros-args -p sub_topic:=hbmem_img \
--ros-args -p in_mode:=shared_mem \
--ros-args -p out_format:=jpeg \
--ros-args -p out_mode:=ros \
--ros-args -p pub_topic:=image

websocket

ros2 run websocket websocket \
--ros-args --log-level error \
--ros-args -p only_show_image:=False \
--ros-args -p image_topic:=image \
--ros-args -p image_type:=mjpeg \
--ros-args -p smart_topic:=yolov5_results

hobot_codec_B (nv12 to H264 or H265)

ros2 run hobot_codec hobot_codec_republish \
--ros-args --log-level warn \
--ros-args -p channel:=3 \
--ros-args -p in_format:=nv12 \
--ros-args -p sub_topic:=hbmem_img \
--ros-args -p in_mode:=shared_mem \
--ros-args -p out_format:=h264 \
--ros-args -p out_mode:=ros \
--ros-args -p pub_topic:=rtsp_string_h264

ros_rtsp

ros2 run ros_rtsp_server ros_rtsp_server \
--ros-args --log-level warn \
--ros-args -p topic_name:=rtsp_string_h264 \
--ros-args -p video_type:=h264 \
--ros-args -p port:=9999 \
--ros-args -p stream_name:=a_name_ch0

推流地址:rtsp://IP:9999/a_name_ch0
例如:rtsp://192.168.1.143:9999/a_name_ch0
测试软件:https://www.videolan.org/vlc/

如何使用launch启动?

借着dnn_node的launch用一用

touch /opt/tros/share/dnn_node_example/launch/mipi_dnn_with_rtsp.launch.py
vim /opt/tros/share/dnn_node_example/launch/mipi_dnn_with_rtsp.launch.py

加入以下内容:


import os
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    mipi_cam = Node(
        package='mipi_cam',
        executable='mipi_cam',
        name='hobot_usb_cam',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'error',
            '--ros-args', '-p', 'io_method:=shared_mem',
            '--ros-args', '-p', 'out_format:=nv12',
            '--ros-args', '-p', 'image_width:=2560',
            '--ros-args', '-p', 'image_height:=1440'
        ]
    )
    dnn_node = Node(
        package='dnn_node_example',
        executable='example',
        name='dnn_node',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'feed_type:=1',
            '--ros-args', '-p', 'dump_render_img:=0',
            '--ros-args', '-p', 'is_shared_mem_sub:=1',
            '--ros-args', '-p', 'config_file:=/opt/tros/lib/dnn_node_example/config/yolov5workconfig.json ',
            '--ros-args', '-p', 'msg_pub_topic_name:=yolov5_results'
        ]
    )
    hobot_codec_A = Node(
        package='hobot_codec',
        executable='hobot_codec_republish',
        name='hobot_codec_A',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'channel:=2',
            '--ros-args', '-p', 'in_format:=nv12',
            '--ros-args', '-p', 'sub_topic:=hbmem_img',
            '--ros-args', '-p', 'in_mode:=shared_mem',
            '--ros-args', '-p', 'out_format:=jpeg',
            '--ros-args', '-p', 'out_mode:=ros',
            '--ros-args', '-p', 'pub_topic:=image'
        ]
    )
    websocket = Node(
        package='websocket',
        executable='websocket',
        name='websocket',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'error',
            '--ros-args', '-p', 'only_show_image:=False',
            '--ros-args', '-p', 'image_topic:=image',
            '--ros-args', '-p', 'image_type:=mjpeg',
            '--ros-args', '-p', 'smart_topic:=yolov5_results'
        ]
    )
    hobot_codec_B = Node(
        package='hobot_codec',
        executable='hobot_codec_republish',
        name='hobot_codec_B',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'channel:=3',
            '--ros-args', '-p', 'in_format:=nv12',
            '--ros-args', '-p', 'sub_topic:=hbmem_img',
            '--ros-args', '-p', 'in_mode:=shared_mem',
            '--ros-args', '-p', 'out_format:=h264',
            '--ros-args', '-p', 'out_mode:=ros',
            '--ros-args', '-p', 'pub_topic:=rtsp_string_h264'
        ]
    )
    ros_rtsp_node = Node(
        package='ros_rtsp_server',
        executable='ros_rtsp_server',
        name='ros_rtsp_node',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'topic_name:=rtsp_string_h264',
            '--ros-args', '-p', 'video_type:=h264',
            '--ros-args', '-p', 'port:=9999',
            '--ros-args', '-p', 'stream_name:=a_name_ch0'
        ]
    )

    return LaunchDescription([
        mipi_cam,
        dnn_node,
        hobot_codec_A,
        websocket,
        hobot_codec_B,
        ros_rtsp_node
    ])

使用以下命令启动即可:

source /opt/tros/setup.bash
ros2 launch dnn_node_example mipi_dnn_with_rtsp.launch.py

USB Camera Node拆解

usb_node

ros2 run hobot_usb_cam hobot_usb_cam \
--ros-args --log-level warn \
--ros-args -p zero_copy:=False \
--ros-args -p io_method:=mmap \
--ros-args -p video_device:=/dev/video8 \
--ros-args -p pixel_format:=mjpeg \
--ros-args -p image_height:=1080 \
--ros-args -p image_width:=1920

hobot_codec_A (MJPEG 2 nv12)

ros2 run hobot_codec hobot_codec_republish \
--ros-args --log-level warn \
--ros-args -p channel:=1 \
--ros-args -p in_format:=jpeg \
--ros-args -p sub_topic:=image \
--ros-args -p in_mode:=ros \
--ros-args -p out_format:=nv12 \
--ros-args -p out_mode:=shared_mem \
--ros-args -p pub_topic:=hbmem_img

hobot_dnn

ros2 run dnn_node_example example \
--ros-args --log-level warn \
--ros-args -p feed_type:=1 \
--ros-args -p dump_render_img:=0 \
--ros-args -p is_shared_mem_sub:=1 \
--ros-args -p config_file:=/opt/tros/lib/dnn_node_example/config/yolov5workconfig.json  \
--ros-args -p msg_pub_topic_name:=yolov5_results

websocket

ros2 run websocket websocket \
--ros-args --log-level error \
--ros-args -p only_show_image:=False \
--ros-args -p image_topic:=image \
--ros-args -p image_type:=mjpeg \
--ros-args -p smart_topic:=yolov5_results

hobot_codec_B (nv12 to H264 or H265)

ros2 run hobot_codec hobot_codec_republish \
--ros-args --log-level warn \
--ros-args -p channel:=2 \
--ros-args -p in_format:=nv12 \
--ros-args -p sub_topic:=hbmem_img \
--ros-args -p in_mode:=shared_mem \
--ros-args -p out_format:=h264 \
--ros-args -p out_mode:=ros \
--ros-args -p pub_topic:=rtsp_string_h264

ros_rtsp

ros2 run ros_rtsp_server ros_rtsp_server \
--ros-args --log-level warn \
--ros-args -p topic_name:=rtsp_string_h264 \
--ros-args -p video_type:=h264 \
--ros-args -p port:=9999 \
--ros-args -p stream_name:=a_name_ch0

推流地址:rtsp://IP:9999/a_name_ch0
例如:rtsp://192.168.1.143:9999/a_name_ch0
测试软件:https://www.videolan.org/vlc/

如何使用launch启动?

借着dnn_node的launch用一用

touch /opt/tros/share/dnn_node_example/launch/usb_dnn_with_rtsp.launch.py
vim /opt/tros/share/dnn_node_example/launch/usb_dnn_with_rtsp.launch.py

加入以下内容:

import os
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    hobot_usb_cam = Node(
        package='hobot_usb_cam',
        executable='hobot_usb_cam',
        name='hobot_usb_cam',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'zero_copy:=False',
            '--ros-args', '-p', 'io_method:=mmap',
            '--ros-args', '-p', 'video_device:=/dev/video8',
            '--ros-args', '-p', 'pixel_format:=mjpeg',
            '--ros-args', '-p', 'image_height:=1080',
            '--ros-args', '-p', 'image_width:=1920'
        ]
    )
    hobot_codec_A = Node(
        package='hobot_codec',
        executable='hobot_codec_republish',
        name='hobot_codec_A',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'in_format:=jpeg',
            '--ros-args', '-p', 'out_format:=nv12',
            '--ros-args', '-p', 'channel:=1',
            '--ros-args', '-p', 'out_mode:=shared_mem',
            '--ros-args', '-p', 'sub_topic:=image',
            '--ros-args', '-p', 'pub_topic:=hbmem_img'
        ]
    )
    dnn_node = Node(
        package='dnn_node_example',
        executable='example',
        name='dnn_node',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'feed_type:=1',
            '--ros-args', '-p', 'dump_render_img:=0',
            '--ros-args', '-p', 'is_shared_mem_sub:=1',
            '--ros-args', '-p', 'config_file:=/opt/tros/lib/dnn_node_example/config/yolov5workconfig.json ',
            '--ros-args', '-p', 'msg_pub_topic_name:=yolov5_results'
        ]
    )
    websocket = Node(
        package='websocket',
        executable='websocket',
        name='websocket',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'error',
            '--ros-args', '-p', 'only_show_image:=False',
            '--ros-args', '-p', 'image_topic:=image',
            '--ros-args', '-p', 'image_type:=mjpeg',
            '--ros-args', '-p', 'smart_topic:=yolov5_results'
        ]
    )
    hobot_codec_B = Node(
        package='hobot_codec',
        executable='hobot_codec_republish',
        name='hobot_codec_B',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'warn',
            '--ros-args', '-p', 'channel:=2',
            '--ros-args', '-p', 'in_format:=nv12',
            '--ros-args', '-p', 'sub_topic:=hbmem_img',
            '--ros-args', '-p', 'in_mode:=shared_mem',
            '--ros-args', '-p', 'out_format:=h264',
            '--ros-args', '-p', 'out_mode:=ros',
            '--ros-args', '-p', 'pub_topic:=rtsp_string_h264'
        ]
    )
    ros_rtsp_node = Node(
        package='ros_rtsp_server',
        executable='ros_rtsp_server',
        name='ros_rtsp_node',
        output='screen',
        arguments=[
            '--ros-args', '--log-level', 'error',
            '--ros-args', '-p', 'topic_name:=rtsp_string_h264',
            '--ros-args', '-p', 'video_type:=h264',
            '--ros-args', '-p', 'port:=9999',
            '--ros-args', '-p', 'stream_name:=a_name_ch0'
        ]
    )

    return LaunchDescription([
        hobot_usb_cam,
        hobot_codec_A,
        dnn_node,
        websocket,
        hobot_codec_B,
        ros_rtsp_node
    ])

使用以下命令启动即可:

source /opt/tros/setup.bash
ros2 launch dnn_node_example usb_dnn_with_rtsp.launch.py

你可能感兴趣的:(地平线RDK,X3系列板卡,RDK,X3,ROS2)