diff --git a/.gitignore b/.gitignore index 134ceb9..daa0324 100644 --- a/.gitignore +++ b/.gitignore @@ -7,6 +7,7 @@ YOLOX_outputs/ *.trt *.engine *.tflite +*.hef YOLOX/ YOLOX_outputs/ install/ diff --git a/weights/hailort/download.bash b/weights/hailort/download.bash new file mode 100644 index 0000000..9c948d7 --- /dev/null +++ b/weights/hailort/download.bash @@ -0,0 +1,3 @@ +#!/bin/bash +SCRIPT_DIR=$(cd $(dirname $0); pwd) +wget https://github.com/tier4/hailort-yoloXP/raw/main/hef/yolox-s-opt-relu6-960x960-T4.hef diff --git a/weights/onnx/download.bash b/weights/onnx/download.bash old mode 100755 new mode 100644 diff --git a/weights/openvino/install.bash b/weights/openvino/install.bash old mode 100755 new mode 100644 diff --git a/weights/tensorrt/convert.bash b/weights/tensorrt/convert.bash old mode 100755 new mode 100644 diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index c4a0ceb..92b68da 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -127,6 +127,16 @@ colcon build --cmake-args \ -DFLATBUFFERS_INCLUDE_DIR=${WORKSPACE}/tflite_build/flatbuffers/include ``` + +### HailoRT + +```bash +# build with hailort +source /opt/ros/humble/setup.bash +colcon build --cmake-args -DYOLOX_USE_HAILORT=ON +``` + +
## Run @@ -187,6 +197,12 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py # is_nchw:=false ``` +### HailoRT + +```bash +ros2 launch yolox_ros_cpp yolox_hailort.launch.py +``` + ### Parameter
@@ -276,3 +292,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py Reference from YOLOX demo code. - https://github.com/Megvii-BaseDetection/YOLOX/blob/5183a6716404bae497deb142d2c340a45ffdb175/demo/OpenVINO/cpp/yolox_openvino.cpp - https://github.com/Megvii-BaseDetection/YOLOX/tree/5183a6716404bae497deb142d2c340a45ffdb175/demo/TensorRT/cpp + +HailoRT +- https://github.com/tier4/hailort-yoloXP +- https://github.com/hailo-ai/hailort \ No newline at end of file diff --git a/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh b/yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh old mode 100755 new mode 100644 diff --git a/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh b/yolox_ros_cpp/docker/openvino/ros_entrypoint.sh old mode 100755 new mode 100644 diff --git a/yolox_ros_cpp/docker/tensorrt/ros_entrypoint.sh b/yolox_ros_cpp/docker/tensorrt/ros_entrypoint.sh old mode 100755 new mode 100644 diff --git a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt index 9070482..87f7bce 100644 --- a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt +++ b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt @@ -18,6 +18,7 @@ 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(YOLOX_USE_HAILORT "Use Hailort" OFF) option(JETSON "Use Jetson" OFF) if(JETSON) @@ -25,7 +26,7 @@ if(JETSON) 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) +if(NOT YOLOX_USE_OPENVINO AND NOT YOLOX_USE_TENSORRT AND NOT YOLOX_USE_ONNXRUNTIME AND NOT YOLOX_USE_TFLITE AND NOT YOLOX_USE_HAILORT) message(FATAL_ERROR "YOLOX_USE_OPENVINO, YOLOX_USE_TENSORRT, YOLOX_USE_ONNXRUNTIME, YOLOX_USE_TFLITE must be ON at least one") return() endif() @@ -34,6 +35,7 @@ set(ENABLE_OPENVINO OFF) set(ENABLE_TENSORRT OFF) set(ENABLE_ONNXRUNTIME OFF) set(ENABLE_TFLITE OFF) +set(ENABLE_HAILORT OFF) if(YOLOX_USE_OPENVINO) find_package(OpenVINO REQUIRED) @@ -75,6 +77,13 @@ if(YOLOX_USE_ONNXRUNTIME) set(TARGET_SRC src/yolox_onnxruntime.cpp) endif() +# hailort +if(YOLOX_USE_HAILORT) + find_package(HailoRT EXACT REQUIRED) + set(ENABLE_HAILORT ON) + set(TARGET_SRC src/yolox_hailort.cpp) +endif() + configure_file( "${PROJECT_SOURCE_DIR}/include/yolox_cpp/config.h.in" "${PROJECT_SOURCE_DIR}/include/yolox_cpp/config.h" @@ -100,6 +109,10 @@ if (YOLOX_USE_ONNXRUNTIME) target_link_libraries(yolox_cpp onnxruntime) endif() +if (YOLOX_USE_HAILORT) + target_link_libraries(yolox_cpp HailoRT::libhailort ${OpenCV_LIBS}) + ament_export_dependencies(HailoRT) +endif() if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/config.h.in b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/config.h.in index 72f4411..288a8c8 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/config.h.in +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/config.h.in @@ -5,5 +5,6 @@ #cmakedefine ENABLE_TENSORRT #cmakedefine ENABLE_ONNXRUNTIME #cmakedefine ENABLE_TFLITE +#cmakedefine ENABLE_HAILORT #endif // _YOLOX_CPP_CONFIG_H_ diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/hailort_common.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/hailort_common.hpp new file mode 100644 index 0000000..aa90be6 --- /dev/null +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/hailort_common.hpp @@ -0,0 +1,167 @@ +// Copyright 2023 Tier IV, Inc. +// +// 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. + +#ifndef _HAILORT_COMMON +#define _HAILORT_COMMON + +#include +#include +#include +#include +#include + +using namespace hailort; + +#define SAMPLING_PERIOD (HAILO_SAMPLING_PERIOD_332US) +#define AVERAGE_FACTOR (HAILO_AVERAGE_FACTOR_16) +#define DVM_OPTION (HAILO_DVM_OPTIONS_AUTO) // For current measurement over EVB - pass DVM explicitly (see hailo_dvm_options_t) +#define MEASUREMENT_BUFFER_INDEX (HAILO_MEASUREMENT_BUFFER_INDEX_0) + +constexpr size_t FRAMES_COUNT = 1; +constexpr bool QUANTIZED = true; +constexpr hailo_format_type_t FORMAT_TYPE = HAILO_FORMAT_TYPE_AUTO; +constexpr size_t MAX_LAYER_EDGES = 16; + +extern void writeAll(InputVStream &input, hailo_status &status, unsigned char *preprocessed); +extern void readAll(OutputVStream &output, hailo_status &status, std::vector &data); + +namespace hailortCommon +{ + template + float dequantInt(T qv, const float qp_scale, const float qp_zp) { + return ((float)qv - qp_zp) * qp_scale; + } + + void writeAll(InputVStream &input, hailo_status &status, unsigned char *preprocessed) + { + for (size_t i = 0; i < FRAMES_COUNT; i++) { + status = input.write(MemoryView(preprocessed, input.get_frame_size())); + if (HAILO_SUCCESS != status) { + return; + } + } + + // Flushing is not mandatory here + status = input.flush(); + if (HAILO_SUCCESS != status) { + std::cerr << "Failed flushing input vstream" << std::endl; + return; + } + + status = HAILO_SUCCESS; + return; + } + + void readAll(OutputVStream &output, hailo_status &status, std::vector &data) + { + for (size_t i = 0; i < FRAMES_COUNT; i++) { + status = output.read(MemoryView(data.data(), data.size())); + if (HAILO_SUCCESS != status) { + return; + } + } + status = HAILO_SUCCESS; + return; + } + + class HrtCommon + { + public: + HrtCommon() = default; + ~HrtCommon() = default; + + float dequant(void *qv, const float qp_scale, const float qp_zp, hailo_format_type_t format) + { + float dqv=0.0; + if (format == HAILO_FORMAT_TYPE_UINT16) { + dqv = dequantInt(*(uint16_t *)qv, qp_scale, qp_zp); + } else if (format == HAILO_FORMAT_TYPE_UINT8) { + dqv = dequantInt(*(uint8_t *)qv, qp_scale, qp_zp); + } else if (format == HAILO_FORMAT_TYPE_FLOAT32) { + dqv = *(float *)qv; + } else { + std::cout << "Warn : Unsupport Format" << std::endl; + } + return dqv; + } + + Expected> + configureNetworkGroup(VDevice &vdevice, std::string &hef_file) + { + auto hef = Hef::create(hef_file); + if (!hef) { + return make_unexpected(hef.status()); + } + + auto configure_params = vdevice.create_configure_params(hef.value()); + if (!configure_params) { + return make_unexpected(configure_params.status()); + } + + auto network_groups = vdevice.configure(hef.value(), configure_params.value()); + if (!network_groups) { + return make_unexpected(network_groups.status()); + } + + if (1 != network_groups->size()) { + std::cerr << "Invalid amount of network groups" << std::endl; + return make_unexpected(HAILO_INTERNAL_FAILURE); + } + return std::move(network_groups->at(0)); + } + + hailo_status infer(std::vector &input_streams, std::vector &output_streams, unsigned char *data, std::vector> &results) + { + hailo_status status = HAILO_SUCCESS; // Success oriented + hailo_status input_status[MAX_LAYER_EDGES] = {HAILO_UNINITIALIZED}; + hailo_status output_status[MAX_LAYER_EDGES] = {HAILO_UNINITIALIZED}; + std::unique_ptr input_threads[MAX_LAYER_EDGES]; + std::unique_ptr output_threads[MAX_LAYER_EDGES]; + size_t input_thread_index = 0; + size_t output_thread_index = 0; + // Create read threads + + for (output_thread_index = 0 ; output_thread_index < output_streams.size(); output_thread_index++) { + output_threads[output_thread_index] = std::make_unique(readAll, + std::ref(output_streams[output_thread_index]), std::ref(output_status[output_thread_index]), std::ref(results[output_thread_index])); + } + + // Create write threads + for (input_thread_index = 0 ; input_thread_index < input_streams.size(); input_thread_index++) { + input_threads[input_thread_index] = std::make_unique(writeAll, + std::ref(input_streams[input_thread_index]), std::ref(input_status[input_thread_index]), data); + } + + // Join write threads + for (size_t i = 0; i < input_thread_index; i++) { + input_threads[i]->join(); + if (HAILO_SUCCESS != input_status[i]) { + status = input_status[i]; + } + } + + // Join read threads + for (size_t i = 0; i < output_thread_index; i++) { + output_threads[i]->join(); + if (HAILO_SUCCESS != output_status[i]) { + status = output_status[i]; + } + } + + return status; + } + }; +} + +#endif // _HAILORT_COMMON \ No newline at end of file diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp index faad7cc..b9ad134 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp @@ -19,5 +19,9 @@ #include "yolox_tflite.hpp" #endif +#ifdef ENABLE_HAILORT + #include "yolox_hailort.hpp" +#endif + #endif diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_hailort.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_hailort.hpp new file mode 100644 index 0000000..641dd4b --- /dev/null +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_hailort.hpp @@ -0,0 +1,76 @@ +// Copyright 2024 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. + +// Copyright 2023 Tier IV, Inc. +// +// 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. + +#ifndef _YOLOX_CPP_YOLOX_HAILORT_HPP +#define _YOLOX_CPP_YOLOX_HAILORT_HPP + +#include +#include +#include +#include +#include +#include +#include + +#include "coco_names.hpp" +#include "hailort_common.hpp" +#include "core.hpp" + +namespace yolox_cpp +{ + using namespace hailort; + class YoloXHailoRT: public AbcYoloX + { + public: + YoloXHailoRT(std::string path_to_model, float nms_th, float conf_th, int num_classes); + std::vector inference(const cv::Mat &src) override; + + protected: + std::string hef_path_; + float nms_thresh_; + float thresh_; + int num_classes_; + + int output_index_; + std::vector> f_results_; + std::vector> results_; + std::vector m_output_strides; + std::unique_ptr vdevice_; + + std::vector input_streams_; + std::vector output_streams_; + + std::shared_ptr hrtCommon; + Expected>> physical_devices; + Expected, std::vector>> vstreams; + + hailo_vstream_info_t input_info_; + }; +} + +#endif // _YOLOX_CPP_YOLOX_HAILORT_HPP \ No newline at end of file diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_hailort.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_hailort.cpp new file mode 100644 index 0000000..ac79720 --- /dev/null +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_hailort.cpp @@ -0,0 +1,123 @@ +// Copyright 2024 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. + +// Copyright 2023 Tier IV, Inc. +// +// 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. + +#include "yolox_cpp/yolox_hailort.hpp" + +namespace yolox_cpp +{ + using namespace hailort; + YoloXHailoRT::YoloXHailoRT(std::string path_to_model, float nms_th=0.45, float conf_th=0.3, int num_classes=80) : + AbcYoloX(nms_th, conf_th, "0.1", 8, false), hef_path_(path_to_model), + nms_thresh_(nms_th), thresh_(conf_th), num_classes_(num_classes) + { + m_output_strides = {8, 16, 32}; + + hrtCommon = std::make_shared(); + Expected> vdevice = VDevice::create(); + if (!vdevice) std::cerr << "Failed create vdevice, status = " << vdevice.status() << std::endl; + vdevice_ = std::move(vdevice.value()); + + auto network_group = hrtCommon->configureNetworkGroup(*vdevice_, hef_path_); + if (!network_group) { + std::cerr << "Failed to configure network group " << hef_path_ << std::endl; + return; + } + + Expected, std::vector>> temp_vstreams = VStreamsBuilder::create_vstreams(*network_group.value(), QUANTIZED, FORMAT_TYPE); + if (!temp_vstreams) { + std::cerr << "Failed creating vstreams " << temp_vstreams.status() << std::endl; + return; + } + input_streams_ = std::move(temp_vstreams->first); + output_streams_ = std::move(temp_vstreams->second); + + if (input_streams_.size() > MAX_LAYER_EDGES || output_streams_.size() > MAX_LAYER_EDGES) { + std::cerr << "Trying to infer network with too many input/output virtual streams, Maximum amount is " << + MAX_LAYER_EDGES << " (either change HEF or change the definition of MAX_LAYER_EDGES)"<< std::endl; + return; + } + + for (output_index_ = 0 ; output_index_ < (int)output_streams_.size(); output_index_++) { + auto size = output_streams_[output_index_].get_frame_size(); + auto info = output_streams_[output_index_].get_info(); + std::vector data(size); + results_.emplace_back(data); + std::vector f_data(size*4); + f_results_.emplace_back(f_data); + assert(info.format.type == HAILO_FORMAT_TYPE_UINT8); + } + + input_info_ = input_streams_[0].get_info(); + input_w_ = input_info_.shape.width; + input_h_ = input_info_.shape.height; + } + + std::vector YoloXHailoRT::inference(const cv::Mat &src) + { + std::vector object_array; + cv::Mat input = this->static_resize(src); + + hrtCommon->infer(input_streams_, output_streams_, input.data, results_); + std::vector> prev(results_.begin(), results_.end()); + + for (int output_index = 0 ; output_index < (int)output_streams_.size(); output_index++) { + auto info = output_streams_[output_index].get_info(); + auto size = output_streams_[output_index].get_frame_size(); + + std::vector data(size); + std::vector proposals; + std::vector picked; + std::vector grid_strides; + + hailo_quant_info_t quant_info = info.quant_info; + + for (int i = 0; i < (int)size; i++) { + int xy = i % info.shape.features; + int c = i / info.shape.features; + int index = xy * (4+1+num_classes_) + c; + f_results_[output_index][index] = hrtCommon->dequant(&prev[output_index][i], quant_info.qp_scale, quant_info.qp_zp, info.format.type); + } + + auto input_info = input_streams_[0].get_info(); + const float scale = std::min(input_info.shape.width / (float)src.size().width, input_info.shape.height / (float)src.size().height); + + this->generate_grids_and_stride(input_info.shape.width, input_info.shape.height, m_output_strides, grid_strides); + this->generate_yolox_proposals(grid_strides, f_results_[output_index].data(), thresh_, proposals); + if (proposals.size() == 0) + continue; + + this->qsort_descent_inplace(proposals, 0, proposals.size() - 1); + this->nms_sorted_bboxes(proposals, picked, nms_thresh_); + object_array.resize(static_cast(picked.size())); + this->decode_outputs(f_results_[output_index].data(), grid_strides, object_array, thresh_, scale, src.size().width, src.size().height); + } + + return object_array; + } +} + diff --git a/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_hailort.launch.py b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_hailort.launch.py new file mode 100644 index 0000000..c5ebed0 --- /dev/null +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_hailort.launch.py @@ -0,0 +1,115 @@ +# Copyright 2024 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 +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='./src/YOLOX-ROS/weights/hailort/yolox-s-opt-relu6-960x960-T4.hef', + description='yolox model path.' + ), + DeclareLaunchArgument( + 'class_labels_path', + default_value='', + description='if use custom model, set class name labels. ' + ), + DeclareLaunchArgument( + 'num_classes', + default_value='8', # TODO: support 80 classes + description='num classes.' + ), + 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'), + 'class_labels_path': LaunchConfiguration('class_labels_path'), + 'num_classes': LaunchConfiguration('num_classes'), + 'model_type': 'hailort', + '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/src/yolox_ros_cpp.cpp b/yolox_ros_cpp/yolox_ros_cpp/src/yolox_ros_cpp.cpp index d69edf9..def07b9 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/src/yolox_ros_cpp.cpp +++ b/yolox_ros_cpp/yolox_ros_cpp/src/yolox_ros_cpp.cpp @@ -87,6 +87,17 @@ namespace yolox_ros_cpp #else RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with tflite"); rclcpp::shutdown(); +#endif + } + else if (this->params_.model_type == "hailort") + { +#ifdef ENABLE_HAILORT + RCLCPP_INFO(this->get_logger(), "Model Type is hailort"); + this->yolox_ = std::make_unique( + this->params_.model_path, this->params_.nms, this->params_.conf, this->params_.num_classes); +#else + RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with hailort"); + rclcpp::shutdown(); #endif } RCLCPP_INFO(this->get_logger(), "model loaded"); diff --git a/yolox_ros_py/package.xml.old b/yolox_ros_py/package.xml.old old mode 100755 new mode 100644 diff --git a/yolox_ros_py/setup.cfg b/yolox_ros_py/setup.cfg old mode 100755 new mode 100644 diff --git a/yolox_ros_py/setup.py.old b/yolox_ros_py/setup.py.old old mode 100755 new mode 100644