diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 6166071..6b3c64b 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -7,6 +7,7 @@ - TensorRT 8.x * - ONNXRuntime * - Tensorflow Lite * +- **CUDA 11** ※ Either one of OpenVINO or TensorRT or ONNXRuntime or Tensorflow Lite is required. @@ -18,106 +19,8 @@ ※ Model convert script is not supported OpenVINO 2022.* -※ YOLOX is not required. +※ Don't use CUDA 12 -※ Jetson + TensorRT docker support (Jetpack 4.6 r32.6.1). Tested with Jetson Nano 4GB. - - - - - ## Clone YOLOX-ROS ```bash diff --git a/yolox_ros_cpp/docker/jetson/README.md b/yolox_ros_cpp/docker/jetson/README.md new file mode 100644 index 0000000..6ccfc6f --- /dev/null +++ b/yolox_ros_cpp/docker/jetson/README.md @@ -0,0 +1,33 @@ +# Jetson + +## Environment + +- Jetson AGX Orin +- Jetpack 5.1 (R35.1.0 @Ubuntu 20.04) +- Docker +- [TIER IV C1 Camera environment](https://github.com/tier4/tier4_automotive_hdr_camera) (When using C1 camera) + +## Build & attach shell + + +```bash +cd ./YOLOX-ROS/yolox_ros_cpp/docker/jetson +bash setup.bash +``` + +## Build (in docker container) + +```bash +source /dependencies/install/setup.bash +colcon build --cmake-args -DJETSON=ON +bash src/YOLOX-ROS/weights/onnx/download.bash yolox_tiny +bash src/YOLOX-ROS/weights/tensorrt/convert.bash yolox_tiny +``` + + +## Run (in docker container) + +```bash +source ./install/setup.bash +ros2 launch yolox_ros_cpp yolox_tensorrt.launch.py +``` diff --git a/yolox_ros_cpp/docker/jetson/docker-compose.yaml b/yolox_ros_cpp/docker/jetson/docker-compose.yaml deleted file mode 100644 index fb56083..0000000 --- a/yolox_ros_cpp/docker/jetson/docker-compose.yaml +++ /dev/null @@ -1,18 +0,0 @@ -version: '3.4' -services: - yolox_ros: - container_name: yolox_ros - # build: - # context: . - image: fateshelled/jetson_yolox_ros:foxy-ros-base-l4t-r32.6.1 - network_mode: host - volumes: - - $HOME/ros2_ws:/root/ros2_ws - # - /tmp/argus_socket:/tmp/argus_socket # for CSI-camera - devices: - - "/dev/video0:/dev/video0" - working_dir: /root/ros2_ws - tty: true - runtime: nvidia - command: bash - diff --git a/yolox_ros_cpp/docker/jetson/dockerfile b/yolox_ros_cpp/docker/jetson/dockerfile index 17a7250..767757d 100644 --- a/yolox_ros_cpp/docker/jetson/dockerfile +++ b/yolox_ros_cpp/docker/jetson/dockerfile @@ -1,65 +1,27 @@ -FROM dustynv/ros:foxy-ros-base-l4t-r32.6.1 +FROM dustynv/ros:humble-ros-base-deepstream-l4t-r35.1.0 ENV DEBIAN_FRONTEND=noninteractive -RUN apt update && \ - apt install -y libeigen3-dev python3-pip && \ - apt -y clean && \ - rm -rf /var/lib/apt/lists/* - -RUN python3 -m pip install -U pip && \ - python3 -m pip install cmake - # add PATH ENV PATH=$PATH:/usr/src/tensorrt/bin -# torch 1.9.0 -WORKDIR /workspace -RUN apt update && \ - apt install -y libopenblas-base libopenmpi-dev && \ - apt -y clean && \ - rm -rf /var/lib/apt/lists/* -RUN wget https://nvidia.box.com/shared/static/h1z9sw4bb1ybi0rm3tu8qdj8hs05ljbm.whl -O torch-1.9.0-cp36-cp36m-linux_aarch64.whl && \ - python3 -m pip install Cython && \ - python3 -m pip install numpy torch-1.9.0-cp36-cp36m-linux_aarch64.whl &&\ - rm torch-1.9.0-cp36-cp36m-linux_aarch64.whl - -# torch2trt -WORKDIR /workspace -RUN git clone https://github.com/NVIDIA-AI-IOT/torch2trt && \ - cd torch2trt && \ - python3 setup.py install - -# torchvision -ENV TORCHVISION_VERSION=0.10.0 -WORKDIR /workspace -RUN apt update && \ - apt install -y libjpeg-dev zlib1g-dev libpython3-dev libavcodec-dev libavformat-dev libswscale-dev && \ - apt -y clean && \ - rm -rf /var/lib/apt/lists/* -RUN git clone --branch v${TORCHVISION_VERSION} https://github.com/pytorch/vision torchvision && \ - cd torchvision && \ - BUILD_VERSION=$TORCHVISION_VERSION && \ - python3 setup.py install - -# YOLOX -WORKDIR /workspace -ENV YOLOX_VERSION=0.2.0 -# matplotlib, onnx-optimizer cannot install by pip -RUN apt update && \ - apt install -y python3-matplotlib && \ - apt -y clean && \ - rm -rf /var/lib/apt/lists/* -RUN python3 -m pip install onnx==1.8.1 onnxruntime==1.8.0 -RUN git clone --recursive https://github.com/onnx/optimizer onnxoptimizer && \ - cd onnxoptimizer && \ - python3 -m pip install -e . - -# bugfix for numpy==1.19.5 -# set OPENBLAS_CORETYPE environment variable to ARMV8 -ENV OPENBLAS_CORETYPE=ARMV8 - -RUN git clone -b $YOLOX_VERSION https://github.com/Megvii-BaseDetection/YOLOX YOLOX && \ - cd YOLOX && \ - python3 -m pip install -e . - +RUN apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 42D5A192B819C5DA && \ + apt-get update && \ + apt-get install -y \ + doxygen \ + libfmt-dev \ + librange-v3-dev \ + python3-pip \ + python3-jinja2 \ + python3-typeguard +RUN mkdir -p /dependencies/src && \ + cd /dependencies/src && \ + git clone https://github.com/PickNikRobotics/RSL.git && \ + git clone https://github.com/PickNikRobotics/cpp_polyfills.git && \ + git clone https://github.com/ros-perception/vision_opencv.git -b humble && \ + git clone https://github.com/PickNikRobotics/generate_parameter_library.git && \ + cd /dependencies/ && \ + . /opt/ros/humble/install/setup.sh && \ + colcon build + +COPY /usr/include/aarch64-linux-gnu/ /usr/include/aarch64-linux-gnu/ \ No newline at end of file diff --git a/yolox_ros_cpp/docker/jetson/setup.bash b/yolox_ros_cpp/docker/jetson/setup.bash new file mode 100644 index 0000000..b8423e8 --- /dev/null +++ b/yolox_ros_cpp/docker/jetson/setup.bash @@ -0,0 +1,13 @@ +SCRIPT_DIR=$(cd $(dirname $0); pwd) +cd ${SCRIPT_DIR} +mkdir ./tensorrt_dir +cp -r /usr/include/aarch64-linux-gnu/* ./tensorrt_dir/ + +docker build -t yolox_ros_jetson:latest -f ./dockerfile . +docker run -it --rm --network host --volume $HOME/ros2_ws:/root/ros2_ws --device /dev/video0:/dev/video0 --workdir /root/ros2_ws --runtime nvidia yolox_ros_jetson /bin/bash + + +# source /dependencies/install/setup.bash +# colcon build --cmake-args -DJETSON=ON +# bash src/YOLOX-ROS/weights/onnx/download.bash yolox_tiny +# bash src/YOLOX-ROS/weights/tensorrt/convert.bash yolox_tiny diff --git a/yolox_ros_cpp/docker/onnxruntime/docker-compose.yaml b/yolox_ros_cpp/docker/onnxruntime/docker-compose.yaml index 0b9fa6f..2314989 100644 --- a/yolox_ros_cpp/docker/onnxruntime/docker-compose.yaml +++ b/yolox_ros_cpp/docker/onnxruntime/docker-compose.yaml @@ -1,11 +1,11 @@ version: '3.4' services: - yolox_ros: + yolox_ros_onnxruntime: container_name: yolox_onnxruntime - # build: - # context: . - # args: - # - BASE_TAB=11.4.2-cudnn8-devel-ubuntu20.04 + build: + context: . + args: + - BASE_TAB=12.1.0-cudnn8-devel-ubuntu22.04 image: fateshelled/onnxruntime_yolox_ros:latest network_mode: host runtime: nvidia diff --git a/yolox_ros_cpp/docker/onnxruntime/dockerfile b/yolox_ros_cpp/docker/onnxruntime/dockerfile index efac5ae..8bf1dbd 100644 --- a/yolox_ros_cpp/docker/onnxruntime/dockerfile +++ b/yolox_ros_cpp/docker/onnxruntime/dockerfile @@ -1,4 +1,4 @@ -ARG BASE_TAG=11.4.2-cudnn8-devel-ubuntu20.04 +ARG BASE_TAG=11.7.1-cudnn8-devel-ubuntu22.04 FROM nvcr.io/nvidia/cuda:${BASE_TAG} ENV DEBIAN_FRONTEND=noninteractive @@ -22,12 +22,9 @@ RUN git clone --depth 1 --recursive https://github.com/microsoft/onnxruntime -b --use_cuda \ --config RelWithDebInfo \ --build_shared_lib \ - --parallel \ - --build_wheel \ --skip_tests && \ cd build/Linux/RelWithDebInfo && \ make install && \ - python3 -m pip install dist/*.whl && \ rm -r /workdir/onnxruntime # Install ROS2 @@ -39,41 +36,26 @@ RUN apt update && apt install locales && \ ENV LANG=en_US.UTF-8 RUN apt update && \ - apt install -y curl gnupg2 lsb-release && \ - curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg && \ + apt install -y git wget curl gnupg2 lsb-release && \ + curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg && \ echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | tee /etc/apt/sources.list.d/ros2.list > /dev/null && \ - sed -i -e 's/ubuntu .* main/ubuntu focal main/g' /etc/apt/sources.list.d/ros2.list && \ + sed -i -e 's/ubuntu .* main/ubuntu jammy main/g' /etc/apt/sources.list.d/ros2.list && \ apt update && \ - apt install -y ros-foxy-ros-base \ - python3-colcon-common-extensions \ - ros-foxy-v4l2-camera \ - ros-foxy-cv-bridge \ - ros-foxy-rqt-graph \ - ros-foxy-rqt-image-view && \ - rm -rf /var/lib/apt/lists/* &&\ + apt install -y ros-dev-tools \ + ros-humble-cv-bridge \ + ros-humble-generate-parameter-library \ + ros-humble-parameter-traits \ + ros-humble-ros-base \ + ros-humble-rqt-image-view \ + ros-humble-v4l2-camera && \ apt -y clean && \ + rm -rf /var/lib/apt/lists/* && \ pip install -U pip && \ pip install catkin_pkg && \ pip install empy && \ pip install lark && \ python3 -m pip cache purge -WORKDIR /workdir -ENV YOLOX_VERSION=0.3.0 -RUN git clone --depth 1 https://github.com/Megvii-BaseDetection/YOLOX -b $YOLOX_VERSION && \ - cd YOLOX && \ - # python3 -m pip install -r requirements.txt && \ - python3 -m pip install -U numpy \ - torch>=1.7 \ - opencv_python \ - loguru \ - tqdm \ - torchvision \ - thop \ - ninja \ - tabulate && \ - python3 -m pip install --no-deps . && \ - python3 -m pip cache purge COPY ./ros_entrypoint.sh /ros_entrypoint.sh RUN echo "source /ros_entrypoint.sh" >> /root/.bashrc diff --git a/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh b/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh index a79cc7a..7a16b1f 100755 --- a/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh +++ b/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh @@ -1,3 +1,3 @@ #!/bin/bash -source /opt/ros/foxy/setup.bash +source /opt/ros/humble/setup.bash source /usr/share/colcon_argcomplete/hook/colcon-argcomplete.bash diff --git a/yolox_ros_cpp/docker/openvino/docker-compose.yaml b/yolox_ros_cpp/docker/openvino/docker-compose.yaml index fea4075..04d1594 100644 --- a/yolox_ros_cpp/docker/openvino/docker-compose.yaml +++ b/yolox_ros_cpp/docker/openvino/docker-compose.yaml @@ -1,15 +1,14 @@ version: '3.4' services: - yolox_ros: + yolox_ros_openvino: container_name: yolox_openvino - # build: - # context: . - image: fateshelled/openvino_yolox_ros:latest + build: + context: . network_mode: host environment: - DISPLAY=$DISPLAY volumes: - - $HOME/ros2_ws:/root/ros2_ws + - ../../../:/root/ros2_ws/src - /tmp/.X11-unix:/tmp/.X11-unix devices: - "/dev/video0:/dev/video0" diff --git a/yolox_ros_cpp/docker/openvino/dockerfile b/yolox_ros_cpp/docker/openvino/dockerfile index aa51382..2eb71bb 100644 --- a/yolox_ros_cpp/docker/openvino/dockerfile +++ b/yolox_ros_cpp/docker/openvino/dockerfile @@ -1,36 +1,34 @@ -FROM openvino/ubuntu20_dev:2021.4.1_20210416 +FROM openvino/ubuntu22_dev:2023.0.1 ENV DEBIAN_FRONTEND=noninteractive USER root -RUN python3 -m pip install --no-cache-dir -U pip && \ - python3 -m pip install --no-cache-dir cmake && \ - python3 -m pip install --no-cache-dir -r /opt/intel/openvino/deployment_tools/model_optimizer/requirements.txt - # Install ROS2 +RUN apt update && apt install locales && \ + locale-gen en_US en_US.UTF-8 && \ + update-locale LC_ALL=en_US.UTF-8 LANG=en_US.UTF-8 && \ + apt -y clean && \ + rm -rf /var/lib/apt/lists/* +ENV LANG=en_US.UTF-8 + RUN apt update && \ apt install -y git wget curl gnupg2 lsb-release && \ - curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg && \ + curl -sSL https://raw.githubusercontent.com/ros/rosdistro/master/ros.key -o /usr/share/keyrings/ros-archive-keyring.gpg && \ echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/ros-archive-keyring.gpg] http://packages.ros.org/ros2/ubuntu $(lsb_release -cs) main" | tee /etc/apt/sources.list.d/ros2.list > /dev/null && \ - sed -i -e 's/ubuntu .* main/ubuntu focal main/g' /etc/apt/sources.list.d/ros2.list && \ + sed -i -e 's/ubuntu .* main/ubuntu jammy main/g' /etc/apt/sources.list.d/ros2.list && \ apt update && \ - apt install -y ros-foxy-ros-base \ - ros-foxy-v4l2-camera \ - ros-foxy-cv-bridge \ - ros-foxy-rqt-graph \ - ros-foxy-rqt-image-view && \ - apt install -y python3-colcon-common-extensions && \ + apt install -y ros-dev-tools \ + ros-humble-cv-bridge \ + ros-humble-generate-parameter-library \ + ros-humble-parameter-traits \ + ros-humble-ros-base \ + ros-humble-rqt-image-view \ + ros-humble-v4l2-camera && \ apt -y clean && \ rm -rf /var/lib/apt/lists/* WORKDIR /workspace -ENV YOLOX_VERSION=0.2.0 -RUN git clone https://github.com/Megvii-BaseDetection/YOLOX -b $YOLOX_VERSION && \ - cd YOLOX && \ - python3 -m pip install --no-cache-dir -r requirements.txt && \ - python3 setup.py install - COPY ./ros_entrypoint.sh /ros_entrypoint.sh RUN echo "source /ros_entrypoint.sh" >> /root/.bashrc # RUN echo "source /opt/intel/openvino/bin/setupvars.sh " >> /root/.bashrc diff --git a/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh b/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh index a79cc7a..aa815af 100755 --- a/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh +++ b/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh @@ -1,3 +1,4 @@ #!/bin/bash -source /opt/ros/foxy/setup.bash +source /opt/ros/humble/setup.bash source /usr/share/colcon_argcomplete/hook/colcon-argcomplete.bash + diff --git a/yolox_ros_cpp/docker/tensorrt/dockerfile b/yolox_ros_cpp/docker/tensorrt/dockerfile index 413d205..db203be 100644 --- a/yolox_ros_cpp/docker/tensorrt/dockerfile +++ b/yolox_ros_cpp/docker/tensorrt/dockerfile @@ -73,12 +73,11 @@ RUN apt update && \ ros-humble-rqt-image-view \ ros-humble-v4l2-camera && \ apt -y clean && \ - rm -rf /var/lib/apt/lists/* &&\ - apt -y clean && \ + rm -rf /var/lib/apt/lists/* && \ pip install -U pip && \ pip install catkin_pkg && \ pip install empy && \ - pip install lark && \ + pip install lark && \ python3 -m pip cache purge COPY ./ros_entrypoint.sh /ros_entrypoint.sh diff --git a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt index 29e5b78..9070482 100644 --- a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt +++ b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt @@ -18,6 +18,12 @@ option(YOLOX_USE_OPENVINO "Use OpenVINO" OFF) option(YOLOX_USE_TENSORRT "Use TensorRT" OFF) option(YOLOX_USE_ONNXRUNTIME "Use ONNXRuntime" OFF) option(YOLOX_USE_TFLITE "Use tflite" OFF) +option(JETSON "Use Jetson" OFF) + +if(JETSON) + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -I/usr/include/aarch64-linux-gnu/ -L/usr/lib/aarch64-linux-gnu/") + set(YOLOX_USE_TENSORRT ON) +endif() if(NOT YOLOX_USE_OPENVINO AND NOT YOLOX_USE_TENSORRT AND NOT YOLOX_USE_ONNXRUNTIME AND NOT YOLOX_USE_TFLITE) message(FATAL_ERROR "YOLOX_USE_OPENVINO, YOLOX_USE_TENSORRT, YOLOX_USE_ONNXRUNTIME, YOLOX_USE_TFLITE must be ON at least one") diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_onnxruntime.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_onnxruntime.launch.py index 5542cfc..49b1538 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_onnxruntime.launch.py +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_onnxruntime.launch.py @@ -1,7 +1,19 @@ -import os -import sys +# Copyright 2023 Ar-Ray-code +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + + import launch -import launch_ros.actions from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -10,141 +22,135 @@ def generate_launch_description(): launch_args = [ DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" + 'video_device', + default_value='/dev/video0', + description='input video source' ), DeclareLaunchArgument( - "model_path", - default_value="./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx", - description="yolox model path." + 'model_path', + default_value='./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx', + description='yolox model path.' ), DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." + 'p6', + default_value='false', + description='with p6.' ), DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " + 'class_labels_path', + default_value='', + description='if use custom model, set class name labels. ' ), DeclareLaunchArgument( - "num_classes", - default_value="80", - description="num classes." + 'num_classes', + default_value='80', + description='num classes.' ), DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." + 'model_version', + default_value='0.1.1rc0', + description='yolox model version.' ), DeclareLaunchArgument( - "onnxruntime/use_cuda", - default_value="true", - description="onnxruntime use cuda." + 'onnxruntime/use_cuda', + default_value='true', + description='onnxruntime use cuda.' ), DeclareLaunchArgument( - "onnxruntime/device_id", - default_value="0", - description="onnxruntime gpu device id." + 'onnxruntime/device_id', + default_value='0', + description='onnxruntime gpu device id.' ), DeclareLaunchArgument( - "onnxruntime/use_parallel", - default_value="false", - description="if use_parallel is true, you can set inter_op_num_threads." + 'onnxruntime/use_parallel', + default_value='false', + description='if use_parallel is true, you can set inter_op_num_threads.' ), DeclareLaunchArgument( - "onnxruntime/inter_op_num_threads", - default_value="1", - description="control the number of threads used to parallelize the execution of the graph (across nodes)." + 'onnxruntime/inter_op_num_threads', + default_value='1' ), DeclareLaunchArgument( - "onnxruntime/intra_op_num_threads", - default_value="1", - description="ontrols the number of threads to use to run the model." + 'onnxruntime/intra_op_num_threads', + default_value='1', + description='ontrols the number of threads to use to run the model.' ), DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." + 'conf', + default_value='0.30', + description='yolox confidence threshold.' ), DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" + 'nms', + default_value='0.45', + description='yolox nms threshold' ), DeclareLaunchArgument( - "imshow_isshow", - default_value="true", - description="" + 'imshow_isshow', + default_value='true', + description='' ), DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" + 'src_image_topic_name', + default_value='/image_raw', + description='topic name for source image' ), DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" + 'publish_image_topic_name', + default_value='/yolox/image_raw', + description='topic name for publishing image with bounding box drawn' ), DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." + 'publish_boundingbox_topic_name', + default_value='/yolox/bounding_boxes', + description='topic name for publishing bounding box message.' ), ] container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }]), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "model_type": "onnxruntime", - "model_version": LaunchConfiguration("model_version"), - "onnxruntime/use_cuda": LaunchConfiguration("onnxruntime/use_cuda"), - "onnxruntime/device_id": LaunchConfiguration("onnxruntime/device_id"), - "onnxruntime/use_parallel": LaunchConfiguration("onnxruntime/use_parallel"), - "onnxruntime/inter_op_num_threads": LaunchConfiguration("onnxruntime/inter_op_num_threads"), - "onnxruntime/intra_op_num_threads": LaunchConfiguration("onnxruntime/intra_op_num_threads"), - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) - - rqt = launch_ros.actions.Node( - package="rqt_graph", executable="rqt_graph", + name='yolox_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='v4l2_camera', + plugin='v4l2_camera::V4L2Camera', + name='v4l2_camera', + parameters=[{ + 'video_device': LaunchConfiguration('video_device'), + 'image_size': [640, 480] + }]), + ComposableNode( + package='yolox_ros_cpp', + plugin='yolox_ros_cpp::YoloXNode', + name='yolox_ros_cpp', + parameters=[{ + 'model_path': LaunchConfiguration('model_path'), + 'p6': LaunchConfiguration('p6'), + 'class_labels_path': LaunchConfiguration('class_labels_path'), + 'num_classes': LaunchConfiguration('num_classes'), + 'model_type': 'onnxruntime', + 'model_version': LaunchConfiguration('model_version'), + 'onnxruntime/use_cuda': LaunchConfiguration('onnxruntime/use_cuda'), + 'onnxruntime/device_id': LaunchConfiguration('onnxruntime/device_id'), + 'onnxruntime/use_parallel': LaunchConfiguration('onnxruntime/use_parallel'), + 'onnxruntime/inter_op_num_threads': LaunchConfiguration('onnxruntime/inter_op_num_threads'), + 'onnxruntime/intra_op_num_threads': LaunchConfiguration('onnxruntime/intra_op_num_threads'), + 'conf': LaunchConfiguration('conf'), + 'nms': LaunchConfiguration('nms'), + 'imshow_isshow': LaunchConfiguration('imshow_isshow'), + 'src_image_topic_name': LaunchConfiguration('src_image_topic_name'), + 'publish_image_topic_name': LaunchConfiguration('publish_image_topic_name'), + 'publish_boundingbox_topic_name': LaunchConfiguration('publish_boundingbox_topic_name'), + }], + ), + ], + output='screen', ) return launch.LaunchDescription( launch_args + [ - container, - # rqt_graph, + container ] ) diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino.launch.py index fb32e39..3342aa9 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino.launch.py +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino.launch.py @@ -1,7 +1,4 @@ -import os -import sys import launch -import launch_ros.actions from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -10,117 +7,112 @@ def generate_launch_description(): launch_args = [ DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" + 'video_device', + default_value='/dev/video0', + description='input video source' ), DeclareLaunchArgument( - "model_path", - default_value="./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx", - description="yolox model path." + 'model_path', + default_value='./src/YOLOX-ROS/weights/onnx/yolox_tiny.onnx', + description='yolox model path.' ), DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." + 'p6', + default_value='false', + description='with p6.' ), DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " + 'class_labels_path', + default_value='', + description='if use custom model, set class name labels. ' ), DeclareLaunchArgument( - "num_classes", - default_value="80", - description="num classes." + 'num_classes', + default_value='80', + description='num classes.' ), DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." + 'model_version', + default_value='0.1.1rc0', + description='yolox model version.' ), DeclareLaunchArgument( - "openvino/device", - default_value="CPU", - description="model device. CPU, GPU, MYRIAD, etc..." + 'openvino/device', + default_value='CPU', + description='model device. CPU, GPU, MYRIAD, etc...' ), DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." + 'conf', + default_value='0.30', + description='yolox confidence threshold.' ), DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" + 'nms', + default_value='0.45', + description='yolox nms threshold' ), DeclareLaunchArgument( - "imshow_isshow", - default_value="true", - description="" + 'imshow_isshow', + default_value='true', + description='' ), DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" + 'src_image_topic_name', + default_value='/image_raw', + description='topic name for source image' ), DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" + 'publish_image_topic_name', + default_value='/yolox/image_raw', + description='topic name for publishing image with bounding box drawn' ), DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." + 'publish_boundingbox_topic_name', + default_value='/yolox/bounding_boxes', + description='topic name for publishing bounding box message.' ), ] container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }]), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "model_type": "openvino", - "model_version": LaunchConfiguration("model_version"), - "openvino/device": LaunchConfiguration("openvino/device"), - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) - - rqt = launch_ros.actions.Node( - package="rqt_graph", executable="rqt_graph", + name='yolox_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='v4l2_camera', + plugin='v4l2_camera::V4L2Camera', + name='v4l2_camera', + parameters=[{ + 'video_device': LaunchConfiguration('video_device'), + 'image_size': [640, 480] + }]), + ComposableNode( + package='yolox_ros_cpp', + plugin='yolox_ros_cpp::YoloXNode', + name='yolox_ros_cpp', + parameters=[{ + 'model_path': LaunchConfiguration('model_path'), + 'p6': LaunchConfiguration('p6'), + 'class_labels_path': LaunchConfiguration('class_labels_path'), + 'num_classes': LaunchConfiguration('num_classes'), + 'model_type': 'openvino', + 'model_version': LaunchConfiguration('model_version'), + 'openvino/device': LaunchConfiguration('openvino/device'), + 'conf': LaunchConfiguration('conf'), + 'nms': LaunchConfiguration('nms'), + 'imshow_isshow': LaunchConfiguration('imshow_isshow'), + 'src_image_topic_name': LaunchConfiguration('src_image_topic_name'), + 'publish_image_topic_name': LaunchConfiguration('publish_image_topic_name'), + 'publish_boundingbox_topic_name': LaunchConfiguration('publish_boundingbox_topic_name'), + }], + ), + ], + output='screen', ) return launch.LaunchDescription( launch_args + [ - container, - # rqt_graph, + container ] ) diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino_ncs2.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino_ncs2.launch.py deleted file mode 100644 index 9b423ad..0000000 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_openvino_ncs2.launch.py +++ /dev/null @@ -1,121 +0,0 @@ -import os -import sys -import launch -import launch_ros.actions -from launch.actions import DeclareLaunchArgument -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode - -def generate_launch_description(): - launch_args = [ - DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" - ), - DeclareLaunchArgument( - "model_path", - default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/openvino/yolox_tiny.xml", - description="yolox model path." - ), - DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." - ), - DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " - ), - DeclareLaunchArgument( - "num_classes", - default_value="80", - description="num classes." - ), - DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." - ), - DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." - ), - DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" - ), - DeclareLaunchArgument( - "imshow_isshow", - default_value="true", - description="" - ), - DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" - ), - DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" - ), - DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." - ), - ] - container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }]), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "model_type": "openvino", - "model_version": LaunchConfiguration("model_version"), - "openvino/device": "MYRIAD", - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) - - rqt = launch_ros.actions.Node( - package="rqt_graph", executable="rqt_graph", - ) - - return launch.LaunchDescription( - launch_args + - [ - container, - # rqt_graph, - ] - ) diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt.launch.py index ac08f95..fabc144 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt.launch.py +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt.launch.py @@ -1,7 +1,4 @@ -import os -import sys import launch -import launch_ros.actions from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer @@ -11,118 +8,110 @@ def generate_launch_description(): launch_args = [ DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" + 'video_device', + default_value='/dev/video0', + description='input video source' ), DeclareLaunchArgument( - "model_path", - default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tensorrt/yolox_nano.trt", - description="yolox model path." + 'model_path', + default_value='./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tensorrt/yolox_nano.trt', + description='yolox model path.' ), DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." + 'p6', + default_value='false', + description='with p6.' ), DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " + 'class_labels_path', + default_value='', + description='if use custom model, set class name labels. ' ), DeclareLaunchArgument( - "num_classes", - default_value="80", - description="num classes." + 'num_classes', + default_value='80', + description='num classes.' ), DeclareLaunchArgument( - "tensorrt/device", - default_value="0", - description="GPU index. Set in string type. ex '0'" + 'tensorrt/device', + default_value='0', + description='GPU index. Set in string type. ex 0' ), DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." + 'model_version', + default_value='0.1.1rc0', + description='yolox model version.' ), DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." + 'conf', + default_value='0.30', + description='yolox confidence threshold.' ), DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" + 'nms', + default_value='0.45', + description='yolox nms threshold' ), DeclareLaunchArgument( - "imshow_isshow", - default_value="true", - description="" + 'imshow_isshow', + default_value='true', + description='' ), DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" + 'src_image_topic_name', + default_value='/image_raw', + description='topic name for source image' ), DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" + 'publish_image_topic_name', + default_value='/yolox/image_raw', + description='topic name for publishing image with bounding box drawn' ), DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." + 'publish_boundingbox_topic_name', + default_value='/yolox/bounding_boxes', + description='topic name for publishing bounding box message.' ), ] container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }] - ), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "model_type": "tensorrt", - "model_version": LaunchConfiguration("model_version"), - "tensorrt/device": LaunchConfiguration("tensorrt/device"), - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) - - rqt = launch_ros.actions.Node( - package="rqt_graph", executable="rqt_graph", + name='yolox_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='v4l2_camera', + plugin='v4l2_camera::V4L2Camera', + name='v4l2_camera', + parameters=[{ + 'video_device': LaunchConfiguration('video_device'), + 'image_size': [640, 480] + }] + ), + ComposableNode( + package='yolox_ros_cpp', + plugin='yolox_ros_cpp::YoloXNode', + name='yolox_ros_cpp', + parameters=[{ + 'model_path': LaunchConfiguration('model_path'), + 'p6': LaunchConfiguration('p6'), + 'class_labels_path': LaunchConfiguration('class_labels_path'), + 'num_classes': LaunchConfiguration('num_classes'), + 'model_type': 'tensorrt', + 'model_version': LaunchConfiguration('model_version'), + 'tensorrt/device': LaunchConfiguration('tensorrt/device'), + 'conf': LaunchConfiguration('conf'), + 'nms': LaunchConfiguration('nms'), + 'imshow_isshow': LaunchConfiguration('imshow_isshow'), + 'src_image_topic_name': LaunchConfiguration('src_image_topic_name'), + 'publish_image_topic_name': LaunchConfiguration('publish_image_topic_name'), + 'publish_boundingbox_topic_name': LaunchConfiguration('publish_boundingbox_topic_name'), + }], + ), + ], + output='screen', ) return launch.LaunchDescription( - launch_args + - [ - container, - # rqt - ] + launch_args + [container] ) diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt_jetson.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt_jetson.launch.py deleted file mode 100644 index 4d9193f..0000000 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tensorrt_jetson.launch.py +++ /dev/null @@ -1,115 +0,0 @@ -import os -import sys -import launch -import launch_ros.actions -from launch.actions import DeclareLaunchArgument -from launch.substitutions import LaunchConfiguration -from launch_ros.actions import ComposableNodeContainer -from launch_ros.descriptions import ComposableNode - -def generate_launch_description(): - - launch_args = [ - DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" - ), - DeclareLaunchArgument( - "model_path", - default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tensorrt/yolox_nano.trt", - description="yolox model path." - ), - DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." - ), - DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " - ), - DeclareLaunchArgument( - "num_classes", - default_value="80", - description="num classes." - ), - DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." - ), - DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." - ), - DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" - ), - DeclareLaunchArgument( - "imshow_isshow", - default_value="false", - description="" - ), - DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" - ), - DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" - ), - DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." - ), - ] - container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }] - ), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "model_type": "tensorrt", - "model_version": LaunchConfiguration("model_version"), - "tensorrt/device": 0, - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) - - return launch.LaunchDescription( - launch_args + [container] - ) diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py index f4622c4..278fb59 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py @@ -1,127 +1,122 @@ -import os -import sys import launch -import launch_ros.actions from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration from launch_ros.actions import ComposableNodeContainer from launch_ros.descriptions import ComposableNode + def generate_launch_description(): launch_args = [ DeclareLaunchArgument( - "video_device", - default_value="/dev/video0", - description="input video source" + 'video_device', + default_value='/dev/video0', + description='input video source' ), DeclareLaunchArgument( - "model_path", - default_value="./src/YOLOX-ROS/weights/tflite/model.tflite", - description="yolox model path." + 'model_path', + default_value='./src/YOLOX-ROS/weights/tflite/model.tflite', + description='yolox model path.' ), DeclareLaunchArgument( - "p6", - default_value="false", - description="with p6." + 'p6', + default_value='false', + description='with p6.' ), DeclareLaunchArgument( - "is_nchw", - default_value="true", - description="model input shape is NCHW or NWHC." + 'is_nchw', + default_value='true', + description='model input shape is NCHW or NWHC.' ), DeclareLaunchArgument( - "class_labels_path", - default_value="''", - description="if use custom model, set class name labels. " + 'class_labels_path', + default_value='', + description='if use custom model, set class name labels. ' ), DeclareLaunchArgument( - "num_classes", - default_value="1", - description="num classes." + 'num_classes', + default_value='1', + description='num classes.' ), DeclareLaunchArgument( - "model_version", - default_value="0.1.1rc0", - description="yolox model version." + 'model_version', + default_value='0.1.1rc0', + description='yolox model version.' ), DeclareLaunchArgument( - "tflite/num_threads", - default_value="1", - description="tflite num_threads." + 'tflite/num_threads', + default_value='1', + description='tflite num_threads.' ), DeclareLaunchArgument( - "conf", - default_value="0.30", - description="yolox confidence threshold." + 'conf', + default_value='0.30', + description='yolox confidence threshold.' ), DeclareLaunchArgument( - "nms", - default_value="0.45", - description="yolox nms threshold" + 'nms', + default_value='0.45', + description='yolox nms threshold' ), DeclareLaunchArgument( - "imshow_isshow", - default_value="true", - description="" + 'imshow_isshow', + default_value='true', + description='' ), DeclareLaunchArgument( - "src_image_topic_name", - default_value="/image_raw", - description="topic name for source image" + 'src_image_topic_name', + default_value='/image_raw', + description='topic name for source image' ), DeclareLaunchArgument( - "publish_image_topic_name", - default_value="/yolox/image_raw", - description="topic name for publishing image with bounding box drawn" + 'publish_image_topic_name', + default_value='/yolox/image_raw', + description='topic name for publishing image with bounding box drawn' ), DeclareLaunchArgument( - "publish_boundingbox_topic_name", - default_value="/yolox/bounding_boxes", - description="topic name for publishing bounding box message." + 'publish_boundingbox_topic_name', + default_value='/yolox/bounding_boxes', + description='topic name for publishing bounding box message.' ), ] container = ComposableNodeContainer( - name='yolox_container', - namespace='', - package='rclcpp_components', - executable='component_container', - composable_node_descriptions=[ - ComposableNode( - package='v4l2_camera', - plugin='v4l2_camera::V4L2Camera', - name='v4l2_camera', - parameters=[{ - "video_device": LaunchConfiguration("video_device"), - "image_size": [640,480] - }]), - ComposableNode( - package='yolox_ros_cpp', - plugin='yolox_ros_cpp::YoloXNode', - name='yolox_ros_cpp', - parameters=[{ - "model_path": LaunchConfiguration("model_path"), - "p6": LaunchConfiguration("p6"), - "class_labels_path": LaunchConfiguration("class_labels_path"), - "num_classes": LaunchConfiguration("num_classes"), - "is_nchw": LaunchConfiguration("is_nchw"), - "model_type": "tflite", - "model_version": LaunchConfiguration("model_version"), - "tflite/num_threads": LaunchConfiguration("tflite/num_threads"), - "conf": LaunchConfiguration("conf"), - "nms": LaunchConfiguration("nms"), - "imshow_isshow": LaunchConfiguration("imshow_isshow"), - "src_image_topic_name": LaunchConfiguration("src_image_topic_name"), - "publish_image_topic_name": LaunchConfiguration("publish_image_topic_name"), - "publish_boundingbox_topic_name": LaunchConfiguration("publish_boundingbox_topic_name"), - }], - ), - ], - output='screen', - ) + name='yolox_container', + namespace='', + package='rclcpp_components', + executable='component_container', + composable_node_descriptions=[ + ComposableNode( + package='v4l2_camera', + plugin='v4l2_camera::V4L2Camera', + name='v4l2_camera', + parameters=[{ + 'video_device': LaunchConfiguration('video_device'), + 'image_size': [640, 480] + }]), + ComposableNode( + package='yolox_ros_cpp', + plugin='yolox_ros_cpp::YoloXNode', + name='yolox_ros_cpp', + parameters=[{ + 'model_path': LaunchConfiguration('model_path'), + 'p6': LaunchConfiguration('p6'), + 'class_labels_path': LaunchConfiguration('class_labels_path'), + 'num_classes': LaunchConfiguration('num_classes'), + 'is_nchw': LaunchConfiguration('is_nchw'), + 'model_type': 'tflite', + 'model_version': LaunchConfiguration('model_version'), + 'tflite/num_threads': LaunchConfiguration('tflite/num_threads'), + 'conf': LaunchConfiguration('conf'), + 'nms': LaunchConfiguration('nms'), + 'imshow_isshow': LaunchConfiguration('imshow_isshow'), + 'src_image_topic_name': LaunchConfiguration('src_image_topic_name'), + 'publish_image_topic_name': LaunchConfiguration('publish_image_topic_name'), + 'publish_boundingbox_topic_name': LaunchConfiguration('publish_boundingbox_topic_name'), + }], + ), + ], + output='screen', + ) return launch.LaunchDescription( - launch_args + - [ - container, - ] + launch_args + [container] ) diff --git a/youtube-publisher.repos b/youtube-publisher.repos deleted file mode 100644 index deb4c1d..0000000 --- a/youtube-publisher.repos +++ /dev/null @@ -1,5 +0,0 @@ -repositories: - YouTube-publisher-ROS2: - type: git - url: https://github.com/Ar-Ray-code/YouTube-publisher-ROS2.git - version: main