From b8f978458957f7f968f074e91a53038c016bb279 Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 20:19:57 +0900 Subject: [PATCH 1/8] add for tflite --- yolox_ros_cpp/yolox_cpp/CMakeLists.txt | 53 ++++-- .../yolox_cpp/include/yolox_cpp/config.h.in | 1 + .../yolox_cpp/include/yolox_cpp/core.hpp | 33 +++- .../yolox_cpp/include/yolox_cpp/yolox.hpp | 4 + .../include/yolox_cpp/yolox_tflite.hpp | 53 ++++++ yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp | 158 ++++++++++++++++++ .../include/yolox_ros_cpp/yolox_ros_cpp.hpp | 2 + .../launch/yolox_tflite.launch.py | 121 ++++++++++++++ .../yolox_ros_cpp/src/yolox_ros_cpp.cpp | 26 ++- 9 files changed, 432 insertions(+), 19 deletions(-) create mode 100644 yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp create mode 100644 yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp create mode 100644 yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py diff --git a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt index 96cf7a7..63bd72f 100644 --- a/yolox_ros_cpp/yolox_cpp/CMakeLists.txt +++ b/yolox_ros_cpp/yolox_cpp/CMakeLists.txt @@ -21,10 +21,16 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS ON) option(YOLOX_USE_OPENVINO "Use OpenVINO" ON) option(YOLOX_USE_TENSORRT "Use TensorRT" ON) option(YOLOX_USE_ONNXRUNTIME "Use ONNXRuntime" ON) +option(YOLOX_USE_TFLITE "Use tflite" OFF) +set(TFLITE_LIB_PATH "" CACHE PATH "Path to libtensorflow-lite.so") +set(TFLITE_INCLUDE_DIR "" CACHE PATH "Header directory of tflite") +set(ABSEIL_CPP_ICLUDE_DIR "" CACHE PATH "Header directory of abseil-cpp") +set(FLATBUFFERS_INCLUDE_DIR "" CACHE PATH "Header directory of flatbuffers") set(ENABLE_OPENVINO OFF) set(ENABLE_TENSORRT OFF) set(ENABLE_ONNXRUNTIME OFF) +set(ENABLE_TFLITE OFF) # find dependencies find_package(ament_cmake REQUIRED) @@ -46,22 +52,27 @@ if(YOLOX_USE_TENSORRT) find_library(NVONNXPARSER NAMES nvonnxparser) find_library(NVONNXPARSERRUNTIME NAMES nvonnxparser_runtime) if(NOT CUDA_FOUND) - message(WARNING " CUDA ${CUDA_FOUND}") + message(WARNING " CUDA not found") endif() if(NOT NVINFER) - message(WARNING " NVINFER ${NVINFER}") + message(WARNING " NVINFER not found") endif() if(NOT NVINFERPLUGIN) - message(WARNING " NVINFERPLUGIN ${NVINFERPLUGIN}") + message(WARNING " NVINFERPLUGIN not found") endif() if(NOT NVPARSERS) - message(WARNING " NVPARSERS ${NVPARSERS}") + message(WARNING " NVPARSERS not found") endif() if(NOT NVONNXPARSER) - message(WARNING " NVONNXPARSER ${NVONNXPARSER}") + message(WARNING " NVONNXPARSER not found") endif() # message(WARNING " NVONNXPARSERRUNTIME ${NVONNXPARSERRUNTIME}") #not use if( CUDA_FOUND AND NVINFER AND NVINFERPLUGIN AND NVPARSERS AND NVONNXPARSER ) + message(STATUS " CUDA ${CUDA_FOUND}") + message(STATUS " NVINFER ${NVINFER}") + message(STATUS " NVINFERPLUGIN ${NVINFERPLUGIN}") + message(STATUS " NVPARSERS ${NVPARSERS}") + message(STATUS " NVONNXPARSER ${NVONNXPARSER}") set(ENABLE_TENSORRT ON) set(SRC ${SRC} src/yolox_tensorrt.cpp) endif() @@ -69,20 +80,32 @@ endif() if(YOLOX_USE_ONNXRUNTIME) find_library(ONNXRUNTIME NAMES onnxruntime) if(NOT ONNXRUNTIME) - message(WARNING " ONNXRUNTIME ${ONNXRUNTIME}") - endif() - if(ONNXRUNTIME) + message(WARNING " ONNXRUNTIME not found") + else() + message(STATUS " ONNXRUNTIME ${ONNXRUNTIME}") set(ENABLE_ONNXRUNTIME ON) set(SRC ${SRC} src/yolox_onnxruntime.cpp) endif() endif() +if(YOLOX_USE_TFLITE) + if(NOT ${TFLITE_LIB_PATH}) + set(ENABLE_TFLITE ON) + set(SRC ${SRC} src/yolox_tflite.cpp) + set(INCLUDES ${INCLUDES} ${TFLITE_INCLUDE_DIR}) + set(INCLUDES ${INCLUDES} ${ABSEIL_CPP_ICLUDE_DIR}) + set(INCLUDES ${INCLUDES} ${FLATBUFFERS_INCLUDE_DIR}) + else() + message(WARNING "TFLITE_LIB_PATH is not set") + endif() +endif() message(STATUS " ENABLE_OPENVINO: ${ENABLE_OPENVINO}") message(STATUS " ENABLE_TENSORRT: ${ENABLE_TENSORRT}") message(STATUS " ENABLE_ONNXRUNTIME: ${ENABLE_ONNXRUNTIME}") +message(STATUS " ENABLE_TFLITE: ${ENABLE_TFLITE}") -if(NOT ENABLE_OPENVINO AND NOT ENABLE_TENSORRT AND NOT ENABLE_ONNXRUNTIME) - message(WARNING "skip building yolox_cpp, no OpenVINO, TensorRT and ONNXRuntime found") +if(NOT ENABLE_OPENVINO AND NOT ENABLE_TENSORRT AND NOT ENABLE_ONNXRUNTIME AND NOT ENABLE_TFLITE) + message(WARNING "skip building yolox_cpp, no OpenVINO, TensorRT, ONNXRuntime and tflite found") return() endif() @@ -91,6 +114,8 @@ configure_file( "${PROJECT_SOURCE_DIR}/include/yolox_cpp/config.h" ) +set(INCLUDES ${INCLUDES} $) +set(INCLUDES ${INCLUDES} $) add_library(yolox_cpp SHARED ${SRC} @@ -102,8 +127,7 @@ target_compile_definitions(yolox_cpp target_compile_options(yolox_cpp PUBLIC -Wall) target_include_directories(yolox_cpp PUBLIC - $ - $ + ${INCLUDES} ) ament_target_dependencies(yolox_cpp @@ -132,6 +156,11 @@ if(ENABLE_ONNXRUNTIME) onnxruntime ) endif() +if(ENABLE_TFLITE) + target_link_libraries(yolox_cpp + ${TFLITE_LIB_PATH} + ) +endif() 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 ae5276e..72f4411 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 @@ -4,5 +4,6 @@ #cmakedefine ENABLE_OPENVINO #cmakedefine ENABLE_TENSORRT #cmakedefine ENABLE_ONNXRUNTIME +#cmakedefine ENABLE_TFLITE #endif // _YOLOX_CPP_CONFIG_H_ diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp index 501c0ef..6b936b4 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp @@ -61,11 +61,12 @@ namespace yolox_cpp{ return out; } + // for NCHW void blobFromImage(const cv::Mat& img, float *blob_data) { - int channels = 3; - int img_h = img.rows; - int img_w = img.cols; + size_t channels = 3; + size_t img_h = img.rows; + size_t img_w = img.cols; if(this->model_version_=="0.1.0"){ for (size_t c = 0; c < channels; ++c) { @@ -92,6 +93,32 @@ namespace yolox_cpp{ } } + // for NHWC + void blobFromImage_nhwc(const cv::Mat& img, float *blob_data) + { + size_t channels = 3; + size_t img_h = img.rows; + size_t img_w = img.cols; + if(this->model_version_=="0.1.0"){ + for (size_t i = 0; i < img_h * img_w; ++i) + { + for (size_t c = 0; c < channels; ++c) + { + blob_data[i * channels + c] = + ((float)img.data[i * channels + c] / 255.0 - this->mean_[c]) / this->std_[c]; + } + } + }else{ + for (size_t i = 0; i < img_h * img_w; ++i) + { + for (size_t c = 0; c < channels; ++c) + { + blob_data[i * channels + c] = (float)img.data[i * channels + c]; // 0.1.1rc0 or later + } + } + } + } + void generate_grids_and_stride(const int target_w, const int target_h, const std::vector& strides, std::vector& grid_strides) { for (auto stride : strides) 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 d9865e2..faad7cc 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp @@ -15,5 +15,9 @@ #include "yolox_onnxruntime.hpp" #endif +#ifdef ENABLE_TFLITE + #include "yolox_tflite.hpp" +#endif + #endif diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp new file mode 100644 index 0000000..326b630 --- /dev/null +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp @@ -0,0 +1,53 @@ +#ifndef _YOLOX_CPP_YOLOX_TFLITE_HPP +#define _YOLOX_CPP_YOLOX_TFLITE_HPP + +#include +#include +#include +#include +#include +#include +#include + +#include "tensorflow/lite/interpreter.h" +#include "tensorflow/lite/kernels/register.h" +#include "tensorflow/lite/kernels/internal/tensor_ctypes.h" +#include "tensorflow/lite/model.h" +#include "tensorflow/lite/optional_debug_tools.h" +#include "tensorflow/lite/delegates/xnnpack/xnnpack_delegate.h" +// #include "tensorflow/lite/delegates/nnapi/nnapi_delegate.h" +// #include "tensorflow/lite/delegates/gpu/delegate.h" + +#include "core.hpp" +#include "coco_names.hpp" + +namespace yolox_cpp{ + #define TFLITE_MINIMAL_CHECK(x) \ + if (!(x)) { \ + fprintf(stderr, "Error at %s:%d\n", __FILE__, __LINE__); \ + exit(1); \ + } + + class YoloXTflite: public AbcYoloX{ + public: + YoloXTflite(file_name_t path_to_model, int num_threads, + float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", + int num_classes=80, bool is_nchw=true); + ~YoloXTflite(); + std::vector inference(const cv::Mat& frame) override; + + private: + int doInference(float* input, float* output); + + int input_size_; + int output_size_; + bool is_nchw_; + std::unique_ptr model_; + std::unique_ptr resolver_; + std::unique_ptr interpreter_; + TfLiteDelegate* delegate_; + + }; +} // namespace yolox_cpp + +#endif \ No newline at end of file diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp new file mode 100644 index 0000000..5df4cc6 --- /dev/null +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp @@ -0,0 +1,158 @@ +#include "yolox_cpp/yolox_tflite.hpp" + +namespace yolox_cpp{ + + YoloXTflite::YoloXTflite(file_name_t path_to_model, int num_threads, + float nms_th, float conf_th, std::string model_version, + int num_classes, bool is_nchw) + :AbcYoloX(nms_th, conf_th, model_version, num_classes), is_nchw_(is_nchw) + { + TfLiteStatus status; + this->model_ = tflite::FlatBufferModel::BuildFromFile(path_to_model.c_str()); + TFLITE_MINIMAL_CHECK(model_); + + this->resolver_ = std::make_unique(); + this->interpreter_ = std::make_unique(); + + tflite::InterpreterBuilder builder(*model_, *this->resolver_); + builder(&this->interpreter_); + TFLITE_MINIMAL_CHECK(this->interpreter_ != nullptr); + + TFLITE_MINIMAL_CHECK(this->interpreter_->AllocateTensors() == kTfLiteOk); + // tflite::PrintInterpreterState(this->interpreter_.get()); + + status = this->interpreter_->SetNumThreads(num_threads); + if(status != TfLiteStatus::kTfLiteOk){ + std::cerr << "Failed to SetNumThreads." << std::endl; + exit(1); + } + + // XNNPACK Delegate + auto xnnpack_options = TfLiteXNNPackDelegateOptionsDefault(); + xnnpack_options.num_threads = num_threads; + this->delegate_ = TfLiteXNNPackDelegateCreate(&xnnpack_options); + status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); + if(status != TfLiteStatus::kTfLiteOk){ + std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; + exit(1); + } + + // // GPU Delegate + // auto gpu_options = TfLiteGpuDelegateOptionsV2Default(); + // gpu_options.inference_preference = TFLITE_GPU_INFERENCE_PREFERENCE_SUSTAINED_SPEED; + // gpu_options.inference_priority1 = TFLITE_GPU_INFERENCE_PRIORITY_MIN_LATENCY; + // this->delegate_ = TfLiteGpuDelegateV2Create(&gpu_options); + // status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); + // if(status != TfLiteStatus::kTfLiteOk){ + // std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; + // exit(1); + // } + + // // NNAPI Delegate + // tflite::StatefulNnApiDelegate::Options nnapi_options; + // nnapi_options.execution_preference = tflite::StatefulNnApiDelegate::Options::kSustainedSpeed; + // nnapi_options.allow_fp16 = true; + // nnapi_options.disallow_nnapi_cpu = true; + // this->delegate_ = new tflite::StatefulNnApiDelegate(nnapi_options); + // status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); + // if(status != TfLiteStatus::kTfLiteOk){ + // std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; + // exit(1); + // } + + if(this->interpreter_->AllocateTensors() != TfLiteStatus::kTfLiteOk){ + std::cerr << "Failed to allocate tensors." << std::endl; + exit(1); + } + + { + std::cout << "input:" << std::endl; + TfLiteTensor* tensor = this->interpreter_->input_tensor(0); + std::cout << " name: " << tensor->name << std::endl; + if(this->is_nchw_ == true) + { + // NCHW + this->input_h_ = tensor->dims->data[2]; + this->input_w_ = tensor->dims->data[3]; + } + else + { + // NHWC + this->input_h_ = tensor->dims->data[1]; + this->input_w_ = tensor->dims->data[2]; + } + + std::cout << " shape:" << std::endl; + if(tensor->type == kTfLiteUInt8){ + this->input_size_ = sizeof(uint8_t); + }else{ + this->input_size_ = sizeof(float); + } + for (size_t i = 0; i < tensor->dims->size; i++) + { + this->input_size_ *= tensor->dims->data[i]; + std::cout << " - " << tensor->dims->data[i] << std::endl; + } + std::cout << " input_h: " << this->input_h_ << std::endl; + std::cout << " input_w: " << this->input_w_ << std::endl; + std::cout << " tensor_type: " << tensor->type << std::endl; + } + + { + std::cout << "output:" << std::endl; + TfLiteTensor* tensor = this->interpreter_->output_tensor(0); + std::cout << " name: " << tensor->name << std::endl; + std::cout << " shape:" << std::endl; + if(tensor->type == kTfLiteUInt8){ + this->output_size_ = sizeof(uint8_t); + }else{ + this->output_size_ = sizeof(float); + } + for (size_t i = 0; i < tensor->dims->size; i++) + { + this->output_size_ *= tensor->dims->data[i]; + std::cout << " - " << tensor->dims->data[i] << std::endl; + } + std::cout << " tensor_type: " << tensor->type << std::endl; + } + + // Prepare GridAndStrides + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + + } + YoloXTflite::~YoloXTflite(){ + // TfLiteXNNPackDelegateDelete(this->delegate_); + } + std::vector YoloXTflite::inference(const cv::Mat& frame) + { + // preprocess + cv::Mat pr_img = static_resize(frame); + + float* input_blob = this->interpreter_->typed_input_tensor(0); + if(this->is_nchw_ == true) + { + blobFromImage(pr_img, input_blob); + } + else + { + blobFromImage_nhwc(pr_img, input_blob); + } + + // inference + TfLiteStatus ret = this->interpreter_->Invoke(); + if(ret != TfLiteStatus::kTfLiteOk){ + std::cerr << "Failed to invoke." << std::endl; + return std::vector(); + } + + // postprocess + std::vector objects; + float scale = std::min(this->input_w_ / (frame.cols * 1.0), this->input_h_ / (frame.rows * 1.0)); + float* output_blob = this->interpreter_->typed_output_tensor(0); + decode_outputs(output_blob, this->grid_strides_, objects, this->bbox_conf_thresh_, scale, frame.cols, frame.rows); + + return objects; + } + +} // namespace yolox_cpp + diff --git a/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp b/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp index 21f7756..63e9e20 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp +++ b/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp @@ -37,9 +37,11 @@ namespace yolox_ros_cpp{ bool onnxruntime_use_parallel_; int onnxruntime_intra_op_num_threads_; int onnxruntime_inter_op_num_threads_; + int tflite_num_threads_; float conf_th_; float nms_th_; int num_classes_; + bool is_nchw_; std::vector class_names_; std::string class_labels_path_; 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 new file mode 100644 index 0000000..df50319 --- /dev/null +++ b/yolox_ros_cpp/yolox_ros_cpp/launch/yolox_tflite.launch.py @@ -0,0 +1,121 @@ +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/tflite/model.tflite", + description="yolox model path." + ), + DeclareLaunchArgument( + "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. " + ), + DeclareLaunchArgument( + "num_classes", + default_value="1", + description="num classes." + ), + DeclareLaunchArgument( + "model_version", + default_value="0.1.1rc0", + description="yolox model version." + ), + DeclareLaunchArgument( + "tflite/num_threads", + default_value="1", + description="tflite num_threads." + ), + 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"), + "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, + ] + ) 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 d842378..31d034d 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 @@ -65,6 +65,17 @@ namespace yolox_ros_cpp{ RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with ONNXRuntime"); rclcpp::shutdown(); #endif + }else if(this->model_type_ == "tflite"){ + #ifdef ENABLE_TFLITE + RCLCPP_INFO(this->get_logger(), "Model Type is tflite"); + this->yolox_ = std::make_unique(this->model_path_, this->tflite_num_threads_, + this->nms_th_, this->conf_th_, this->model_version_, + this->num_classes_, this->is_nchw_ + ); + #else + RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with tflite"); + rclcpp::shutdown(); + #endif } RCLCPP_INFO(this->get_logger(), "model loaded"); @@ -83,9 +94,10 @@ namespace yolox_ros_cpp{ void YoloXNode::initializeParameter() { this->declare_parameter("imshow_isshow", true); - this->declare_parameter("model_path", "src/YOLOX-ROS/weights/openvino/yolox_tiny.xml"); + this->declare_parameter("model_path", "./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite"); + this->declare_parameter("num_classes", 1); + this->declare_parameter("is_nchw", true); this->declare_parameter("class_labels_path", ""); - this->declare_parameter("num_classes", 80); this->declare_parameter("conf", 0.3f); this->declare_parameter("nms", 0.45f); this->declare_parameter("tensorrt/device", 0); @@ -95,7 +107,8 @@ namespace yolox_ros_cpp{ this->declare_parameter("onnxruntime/use_parallel", false); this->declare_parameter("onnxruntime/inter_op_num_threads", 1); this->declare_parameter("onnxruntime/intra_op_num_threads", 1); - this->declare_parameter("model_type", "openvino"); + this->declare_parameter("tflite/num_threads", 1); + this->declare_parameter("model_type", "tflite"); this->declare_parameter("model_version", "0.1.1rc0"); this->declare_parameter("src_image_topic_name", "image_raw"); this->declare_parameter("publish_image_topic_name", "yolox/image_raw"); @@ -105,6 +118,7 @@ namespace yolox_ros_cpp{ this->get_parameter("model_path", this->model_path_); this->get_parameter("class_labels_path", this->class_labels_path_); this->get_parameter("num_classes", this->num_classes_); + this->get_parameter("is_nchw", this->is_nchw_); this->get_parameter("conf", this->conf_th_); this->get_parameter("nms", this->nms_th_); this->get_parameter("tensorrt/device", this->tensorrt_device_); @@ -113,7 +127,7 @@ namespace yolox_ros_cpp{ this->get_parameter("onnxruntime/device_id", this->onnxruntime_device_id_); this->get_parameter("onnxruntime/use_parallel", this->onnxruntime_use_parallel_); this->get_parameter("onnxruntime/inter_op_num_threads", this->onnxruntime_inter_op_num_threads_); - this->get_parameter("onnxruntime/intra_op_num_threads", this->onnxruntime_intra_op_num_threads_); + this->get_parameter("tflite/num_threads", this->tflite_num_threads_); this->get_parameter("model_type", this->model_type_); this->get_parameter("model_version", this->model_version_); this->get_parameter("src_image_topic_name", this->src_image_topic_name_); @@ -124,6 +138,7 @@ namespace yolox_ros_cpp{ RCLCPP_INFO(this->get_logger(), "Set parameter model_path: '%s'", this->model_path_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter class_labels_path: '%s'", this->class_labels_path_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter num_classes: %i", this->num_classes_); + RCLCPP_INFO(this->get_logger(), "Set parameter is_nchw: %i", this->is_nchw_); RCLCPP_INFO(this->get_logger(), "Set parameter conf: %f", this->conf_th_); RCLCPP_INFO(this->get_logger(), "Set parameter nms: %f", this->nms_th_); RCLCPP_INFO(this->get_logger(), "Set parameter tensorrt/device: %i", this->tensorrt_device_); @@ -131,6 +146,9 @@ namespace yolox_ros_cpp{ RCLCPP_INFO(this->get_logger(), "Set parameter onnxruntime/use_cuda: %i", this->onnxruntime_use_cuda_); RCLCPP_INFO(this->get_logger(), "Set parameter onnxruntime/device_id: %i", this->onnxruntime_device_id_); RCLCPP_INFO(this->get_logger(), "Set parameter onnxruntime/use_parallel: %i", this->onnxruntime_use_parallel_); + RCLCPP_INFO(this->get_logger(), "Set parameter onnxruntime/inter_op_num_threads: %i", this->onnxruntime_inter_op_num_threads_); + RCLCPP_INFO(this->get_logger(), "Set parameter onnxruntime/intra_op_num_threads: %i", this->onnxruntime_intra_op_num_threads_); + RCLCPP_INFO(this->get_logger(), "Set parameter tflite/num_threads: %i", this->tflite_num_threads_); RCLCPP_INFO(this->get_logger(), "Set parameter model_type: '%s'", this->model_type_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter model_version: '%s'", this->model_version_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter src_image_topic_name: '%s'", this->src_image_topic_name_.c_str()); From 4c1411ee3b49bba98ecbc79be458250357e3c292 Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 20:48:29 +0900 Subject: [PATCH 2/8] update README.md --- yolox_ros_cpp/README.md | 92 ++++++++++++++++++++++++++++++++++++----- 1 file changed, 82 insertions(+), 10 deletions(-) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 3a5974a..216d8df 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -8,11 +8,14 @@ - OpenVINO 2021.* - TensorRT 8.x * - ONNXRuntime * +- Tensorflow Lite * -※ Either one of OpenVINO or TensorRT or ONNXRuntime is required. +※ Either one of OpenVINO or TensorRT or ONNXRuntime or Tensorflow Lite is required. ※ ONNXRuntime support CPU or CUDA execute provider. +※ Tensorflow Lite support XNNPACK Delegate only. + ※ Model convert script is not supported OpenVINO 2022.* ※ YOLOX is not required. @@ -144,6 +147,15 @@ source /opt/ros/foxy/setup.bash ./src/YOLOX-ROS/weights/onnx/download.bash yolox_nano ``` +#### Tensorflow Lite +```bash +cd ~/ros2_ws + +# Download tflite Person Detection model +# https://github.com/Kazuhito00/Person-Detection-using-RaspberryPi-CPU/ +./src/YOLOX-ROS/weights/tflite/download_model.bash +``` + #### PINTO_model_zoo - Support PINTO_model_zoo model - Download model using the following script. @@ -167,6 +179,46 @@ colcon build --symlink-install source ./install/setup.bash ``` + +#### build yolox_ros_cpp with tflite + +##### build tflite +https://www.tensorflow.org/lite/guide/build_cmake + +Below is an example build script. +Please change `${workspace}` as appropriate for your environment. +```bash +cd ${workspace} +git clone https://github.com/tensorflow/tensorflow.git tensorflow_src +mkdir tflite_build +cd tflite_build + +cmake ../tensorflow_src/tensorflow/lite \ + -DBUILD_SHARED_LIBS=ON \ + -DTFLITE_ENABLE_INSTALL=OFF \ + -DTFLITE_ENABLE_XNNPACK=ON \ + -DTFLITE_ENABLE_RUY=OFF \ + -DCMAKE_BUILD_TYPE=Release + +make -j"$(nproc)" +sudo make install +``` + +##### build ros package with tflite + +This is build script when tflite built as above. + +```bash +# build with tflite +colcon build --symlink-install \ + --cmake-args \ + -DYOLOX_USE_TFLITE=ON \ + -DTFLITE_LIB_PATH=${workspace}/tflite_build/libtensorflow-lite.so \ + -DTFLITE_INCLUDE_DIR=${workspace}/tensorflow/ \ + -DABSEIL_CPP_ICLUDE_DIR=${workspace}/tflite_build/abseil-cpp \ + -DFLATBUFFERS_INCLUDE_DIR=${workspace}/tflite_build/flatbuffers/include +``` + ### Run #### OpenVINO @@ -217,6 +269,12 @@ ros2 launch yolox_ros_cpp yolox_tensorrt_jetson.launch.py ros2 launch yolox_ros_cpp yolox_onnxruntime.launch.py ``` +#### Tensorflow Lite +```bash +# run Person Detection Model +ros2 launch yolox_ros_cpp yolox_tflite.launch.py +``` + ### Parameter #### OpenVINO example - `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/openvino/yolox_nano.xml @@ -229,9 +287,9 @@ ros2 launch yolox_ros_cpp yolox_onnxruntime.launch.py - `conf`: 0.3 - `nms`: 0.45 - `imshow_isshow`: true -- `src_image_topic_name`: image_raw -- `publish_image_topic_name`: yolox/image_raw -- `publish_boundingbox_topic_name`: yolox/bounding_boxes +- `src_image_topic_name`: /image_raw +- `publish_image_topic_name`: /yolox/image_raw +- `publish_boundingbox_topic_name`: /yolox/bounding_boxes #### TensorRT example. @@ -243,9 +301,9 @@ ros2 launch yolox_ros_cpp yolox_onnxruntime.launch.py - `conf`: 0.3 - `nms`: 0.45 - `imshow_isshow`: true -- `src_image_topic_name`: image_raw -- `publish_image_topic_name`: yolox/image_raw -- `publish_boundingbox_topic_name`: yolox/bounding_boxes +- `src_image_topic_name`: /image_raw +- `publish_image_topic_name`: /yolox/image_raw +- `publish_boundingbox_topic_name`: /yolox/bounding_boxes #### ONNXRuntime example. @@ -263,9 +321,23 @@ ros2 launch yolox_ros_cpp yolox_onnxruntime.launch.py - `conf`: 0.3 - `nms`: 0.45 - `imshow_isshow`: true -- `src_image_topic_name`: image_raw -- `publish_image_topic_name`: yolox/image_raw -- `publish_boundingbox_topic_name`: yolox/bounding_boxes +- `src_image_topic_name`: /image_raw +- `publish_image_topic_name`: /yolox/image_raw +- `publish_boundingbox_topic_name`: /yolox/bounding_boxes + +#### Tensorflow Lite example. +- `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite +- `is_nchw`: true +- `class_labels_path`: "" +- `num_classes`: 80 +- `model_version`: 0.1.1rc0 +- `tflite/num_threads`: 1 +- `conf`: 0.3 +- `nms`: 0.45 +- `imshow_isshow`: true +- `src_image_topic_name`: /image_raw +- `publish_image_topic_name`: /yolox/image_raw +- `publish_boundingbox_topic_name`: /yolox/bounding_boxes ### Reference From 4462b67ff245a28107bf43f9622d75798d0e53ad Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 21:19:37 +0900 Subject: [PATCH 3/8] Update README.md --- yolox_ros_cpp/README.md | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 216d8df..5cec3f3 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -214,7 +214,7 @@ colcon build --symlink-install \ --cmake-args \ -DYOLOX_USE_TFLITE=ON \ -DTFLITE_LIB_PATH=${workspace}/tflite_build/libtensorflow-lite.so \ - -DTFLITE_INCLUDE_DIR=${workspace}/tensorflow/ \ + -DTFLITE_INCLUDE_DIR=${workspace}/tensorflow_src \ -DABSEIL_CPP_ICLUDE_DIR=${workspace}/tflite_build/abseil-cpp \ -DFLATBUFFERS_INCLUDE_DIR=${workspace}/tflite_build/flatbuffers/include ``` @@ -271,6 +271,9 @@ ros2 launch yolox_ros_cpp yolox_onnxruntime.launch.py #### Tensorflow Lite ```bash +# add libtensorflow-lite.so directory path to `LD_LIBRARY_PATH` +export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:${workspace}/tflite_build + # run Person Detection Model ros2 launch yolox_ros_cpp yolox_tflite.launch.py ``` From a4a2ed50d7a53ce979652ec8588125c79e7c34fd Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 21:45:16 +0900 Subject: [PATCH 4/8] bug fix --- yolox_ros_cpp/README.md | 1 - yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp | 60 ++++++++++++-------- 2 files changed, 36 insertions(+), 25 deletions(-) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 5cec3f3..b432379 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -201,7 +201,6 @@ cmake ../tensorflow_src/tensorflow/lite \ -DCMAKE_BUILD_TYPE=Release make -j"$(nproc)" -sudo make install ``` ##### build ros package with tflite diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp index 5df4cc6..2bc12ec 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp @@ -1,11 +1,12 @@ #include "yolox_cpp/yolox_tflite.hpp" -namespace yolox_cpp{ +namespace yolox_cpp +{ YoloXTflite::YoloXTflite(file_name_t path_to_model, int num_threads, float nms_th, float conf_th, std::string model_version, int num_classes, bool is_nchw) - :AbcYoloX(nms_th, conf_th, model_version, num_classes), is_nchw_(is_nchw) + : AbcYoloX(nms_th, conf_th, model_version, num_classes), is_nchw_(is_nchw) { TfLiteStatus status; this->model_ = tflite::FlatBufferModel::BuildFromFile(path_to_model.c_str()); @@ -22,7 +23,8 @@ namespace yolox_cpp{ // tflite::PrintInterpreterState(this->interpreter_.get()); status = this->interpreter_->SetNumThreads(num_threads); - if(status != TfLiteStatus::kTfLiteOk){ + if (status != TfLiteStatus::kTfLiteOk) + { std::cerr << "Failed to SetNumThreads." << std::endl; exit(1); } @@ -32,7 +34,8 @@ namespace yolox_cpp{ xnnpack_options.num_threads = num_threads; this->delegate_ = TfLiteXNNPackDelegateCreate(&xnnpack_options); status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); - if(status != TfLiteStatus::kTfLiteOk){ + if (status != TfLiteStatus::kTfLiteOk) + { std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; exit(1); } @@ -43,7 +46,8 @@ namespace yolox_cpp{ // gpu_options.inference_priority1 = TFLITE_GPU_INFERENCE_PRIORITY_MIN_LATENCY; // this->delegate_ = TfLiteGpuDelegateV2Create(&gpu_options); // status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); - // if(status != TfLiteStatus::kTfLiteOk){ + // if (status != TfLiteStatus::kTfLiteOk) + // { // std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; // exit(1); // } @@ -55,21 +59,23 @@ namespace yolox_cpp{ // nnapi_options.disallow_nnapi_cpu = true; // this->delegate_ = new tflite::StatefulNnApiDelegate(nnapi_options); // status = this->interpreter_->ModifyGraphWithDelegate(this->delegate_); - // if(status != TfLiteStatus::kTfLiteOk){ + // if (status != TfLiteStatus::kTfLiteOk) + // { // std::cerr << "Failed to ModifyGraphWithDelegate." << std::endl; // exit(1); // } - if(this->interpreter_->AllocateTensors() != TfLiteStatus::kTfLiteOk){ + if (this->interpreter_->AllocateTensors() != TfLiteStatus::kTfLiteOk) + { std::cerr << "Failed to allocate tensors." << std::endl; exit(1); } { + TfLiteTensor *tensor = this->interpreter_->input_tensor(0); std::cout << "input:" << std::endl; - TfLiteTensor* tensor = this->interpreter_->input_tensor(0); std::cout << " name: " << tensor->name << std::endl; - if(this->is_nchw_ == true) + if (this->is_nchw_ == true) { // NCHW this->input_h_ = tensor->dims->data[2]; @@ -83,9 +89,12 @@ namespace yolox_cpp{ } std::cout << " shape:" << std::endl; - if(tensor->type == kTfLiteUInt8){ + if (tensor->type == kTfLiteUInt8) + { this->input_size_ = sizeof(uint8_t); - }else{ + } + else + { this->input_size_ = sizeof(float); } for (size_t i = 0; i < tensor->dims->size; i++) @@ -99,13 +108,16 @@ namespace yolox_cpp{ } { + TfLiteTensor *tensor = this->interpreter_->output_tensor(0); std::cout << "output:" << std::endl; - TfLiteTensor* tensor = this->interpreter_->output_tensor(0); std::cout << " name: " << tensor->name << std::endl; std::cout << " shape:" << std::endl; - if(tensor->type == kTfLiteUInt8){ + if (tensor->type == kTfLiteUInt8) + { this->output_size_ = sizeof(uint8_t); - }else{ + } + else + { this->output_size_ = sizeof(float); } for (size_t i = 0; i < tensor->dims->size; i++) @@ -118,18 +130,18 @@ namespace yolox_cpp{ // Prepare GridAndStrides generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); - } - YoloXTflite::~YoloXTflite(){ - // TfLiteXNNPackDelegateDelete(this->delegate_); + YoloXTflite::~YoloXTflite() + { + TfLiteXNNPackDelegateDelete(this->delegate_); } - std::vector YoloXTflite::inference(const cv::Mat& frame) + std::vector YoloXTflite::inference(const cv::Mat &frame) { // preprocess cv::Mat pr_img = static_resize(frame); - - float* input_blob = this->interpreter_->typed_input_tensor(0); - if(this->is_nchw_ == true) + + float *input_blob = this->interpreter_->typed_input_tensor(0); + if (this->is_nchw_ == true) { blobFromImage(pr_img, input_blob); } @@ -140,7 +152,8 @@ namespace yolox_cpp{ // inference TfLiteStatus ret = this->interpreter_->Invoke(); - if(ret != TfLiteStatus::kTfLiteOk){ + if (ret != TfLiteStatus::kTfLiteOk) + { std::cerr << "Failed to invoke." << std::endl; return std::vector(); } @@ -148,11 +161,10 @@ namespace yolox_cpp{ // postprocess std::vector objects; float scale = std::min(this->input_w_ / (frame.cols * 1.0), this->input_h_ / (frame.rows * 1.0)); - float* output_blob = this->interpreter_->typed_output_tensor(0); + float *output_blob = this->interpreter_->typed_output_tensor(0); decode_outputs(output_blob, this->grid_strides_, objects, this->bbox_conf_thresh_, scale, frame.cols, frame.rows); return objects; } } // namespace yolox_cpp - From 1c8a775d1bd4761e5be6761431e2910c36585c79 Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 22:18:19 +0900 Subject: [PATCH 5/8] add parameter p6 --- yolox_ros_cpp/README.md | 4 ++ .../yolox_cpp/include/yolox_cpp/core.hpp | 6 +- .../include/yolox_cpp/yolox_onnxruntime.hpp | 2 +- .../include/yolox_cpp/yolox_openvino.hpp | 2 +- .../include/yolox_cpp/yolox_tensorrt.hpp | 2 +- .../include/yolox_cpp/yolox_tflite.hpp | 2 +- .../yolox_cpp/src/yolox_onnxruntime.cpp | 19 +++-- .../yolox_cpp/src/yolox_openvino.cpp | 13 +++- .../yolox_cpp/src/yolox_tensorrt.cpp | 13 +++- yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp | 13 +++- .../include/yolox_ros_cpp/yolox_ros_cpp.hpp | 1 + .../launch/yolox_onnxruntime.launch.py | 6 ++ .../launch/yolox_openvino.launch.py | 6 ++ .../launch/yolox_openvino_ncs2.launch.py | 6 ++ .../launch/yolox_tensorrt.launch.py | 6 ++ .../launch/yolox_tensorrt_jetson.launch.py | 6 ++ .../launch/yolox_tflite.launch.py | 6 ++ .../yolox_ros_cpp/src/yolox_ros_cpp.cpp | 72 +++++++------------ 18 files changed, 119 insertions(+), 66 deletions(-) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index b432379..1ddbc98 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -280,6 +280,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py ### Parameter #### OpenVINO example - `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/openvino/yolox_nano.xml +- `p6`: false - `class_labels_path`: "" - if not set, use coco_names. - See [here](https://github.com/fateshelled/YOLOX-ROS/blob/dev_cpp/yolox_ros_cpp/yolox_ros_cpp/labels/coco_names.txt) for label format. @@ -296,6 +297,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py #### TensorRT example. - `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tensorrt/yolox_nano.trt +- `p6`: false - `class_labels_path`: "" - `num_classes`: 80 - `model_version`: 0.1.1rc0 @@ -310,6 +312,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py #### ONNXRuntime example. - `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/onnx/yolox_nano.onnx +- `p6`: false - `class_labels_path`: "" - `num_classes`: 80 - `model_version`: 0.1.1rc0 @@ -329,6 +332,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py #### Tensorflow Lite example. - `model_path`: ./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite +- `p6`: false - `is_nchw`: true - `class_labels_path`: "" - `num_classes`: 80 diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp index 6b936b4..3034033 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp @@ -30,9 +30,9 @@ namespace yolox_cpp{ AbcYoloX(){} AbcYoloX(float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", - int num_classes=80) + int num_classes=80, bool p6=false) :nms_thresh_(nms_th), bbox_conf_thresh_(conf_th), - model_version_(model_version), num_classes_(num_classes) + model_version_(model_version), num_classes_(num_classes), p6_(p6) { } virtual std::vector inference(const cv::Mat& frame) = 0; @@ -42,10 +42,12 @@ namespace yolox_cpp{ float nms_thresh_; float bbox_conf_thresh_; int num_classes_; + bool p6_; std::string model_version_; const std::vector mean_ = {0.485, 0.456, 0.406}; const std::vector std_ = {0.229, 0.224, 0.225}; const std::vector strides_ = {8, 16, 32}; + const std::vector strides_p6_ = {8, 16, 32, 64}; std::vector grid_strides_; cv::Mat static_resize(const cv::Mat& img) diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_onnxruntime.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_onnxruntime.hpp index f34d209..75e6fd0 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_onnxruntime.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_onnxruntime.hpp @@ -20,7 +20,7 @@ namespace yolox_cpp{ int intra_op_num_threads, int inter_op_num_threads=1, bool use_cuda=true, int device_id=0, bool use_parallel=false, float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", - int num_classes=80); + int num_classes=80, bool p6=false); std::vector inference(const cv::Mat& frame) override; private: diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_openvino.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_openvino.hpp index e217852..74c7b93 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_openvino.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_openvino.hpp @@ -17,7 +17,7 @@ namespace yolox_cpp{ public: YoloXOpenVINO(file_name_t path_to_model, std::string device_name, float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", - int num_classes=80); + int num_classes=80, bool p6=false); std::vector inference(const cv::Mat& frame) override; private: diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tensorrt.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tensorrt.hpp index 4c45108..03962a4 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tensorrt.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tensorrt.hpp @@ -35,7 +35,7 @@ namespace yolox_cpp{ public: YoloXTensorRT(file_name_t path_to_engine, int device=0, float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", - int num_classes=80); + int num_classes=80, bool p6=false); std::vector inference(const cv::Mat& frame) override; private: diff --git a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp index 326b630..ff216be 100644 --- a/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp +++ b/yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_tflite.hpp @@ -32,7 +32,7 @@ namespace yolox_cpp{ public: YoloXTflite(file_name_t path_to_model, int num_threads, float nms_th=0.45, float conf_th=0.3, std::string model_version="0.1.1rc0", - int num_classes=80, bool is_nchw=true); + int num_classes=80, bool p6=false, bool is_nchw=true); ~YoloXTflite(); std::vector inference(const cv::Mat& frame) override; diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_onnxruntime.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_onnxruntime.cpp index 058e9b2..3545584 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_onnxruntime.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_onnxruntime.cpp @@ -6,8 +6,8 @@ namespace yolox_cpp{ int intra_op_num_threads, int inter_op_num_threads, bool use_cuda, int device_id, bool use_parallel, float nms_th, float conf_th, std::string model_version, - int num_classes) - :AbcYoloX(nms_th, conf_th, model_version, num_classes), + int num_classes, bool p6) + :AbcYoloX(nms_th, conf_th, model_version, num_classes, p6), intra_op_num_threads_(intra_op_num_threads), inter_op_num_threads_(inter_op_num_threads), use_cuda_(use_cuda), device_id_(device_id), use_parallel_(use_parallel) { @@ -48,7 +48,8 @@ namespace yolox_cpp{ // Allocate input memory buffer std::cout << "input:" << std::endl; - this->input_name_ = this->session_.GetInputName(0, ort_alloc); + this->input_name_ = std::string(this->session_.GetInputNameAllocated(0, ort_alloc).get()); + // this->input_name_ = this->session_.GetInputName(0, ort_alloc); std::cout << " name: " << this->input_name_ << std::endl; auto input_info = this->session_.GetInputTypeInfo(0); auto input_shape_info = input_info.GetTensorTypeAndShapeInfo(); @@ -77,7 +78,8 @@ namespace yolox_cpp{ // Allocate output memory buffer std::cout << "outputs" << std::endl; - this->output_name_ = this->session_.GetOutputName(0, ort_alloc); + this->output_name_ = std::string(this->session_.GetOutputNameAllocated(0, ort_alloc).get()); + // this->output_name_ = this->session_.GetOutputName(0, ort_alloc); std::cout << " name: " << this->output_name_ << std::endl; auto output_info = this->session_.GetOutputTypeInfo(0); @@ -104,7 +106,14 @@ namespace yolox_cpp{ this->output_buffer_.emplace_back(std::move(output_buffer)); // Prepare GridAndStrides - generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + if(this->p6_) + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_p6_, this->grid_strides_); + } + else + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + } } std::vector YoloXONNXRuntime::inference(const cv::Mat& frame) diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_openvino.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_openvino.cpp index 3043a8d..a6ef7b4 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_openvino.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_openvino.cpp @@ -5,8 +5,8 @@ namespace yolox_cpp{ YoloXOpenVINO::YoloXOpenVINO(file_name_t path_to_model, std::string device_name, float nms_th, float conf_th, std::string model_version, - int num_classes) - :AbcYoloX(nms_th, conf_th, model_version, num_classes), + int num_classes, bool p6) + :AbcYoloX(nms_th, conf_th, model_version, num_classes, p6), device_name_(device_name) { // Step 1. Initialize inference engine core @@ -61,7 +61,14 @@ namespace yolox_cpp{ infer_request_ = executable_network_.CreateInferRequest(); // Prepare GridAndStrides - generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + if(this->p6_) + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_p6_, this->grid_strides_); + } + else + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + } } std::vector YoloXOpenVINO::inference(const cv::Mat& frame) diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp index 6a66f7b..f7da8d5 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp @@ -4,8 +4,8 @@ namespace yolox_cpp{ YoloXTensorRT::YoloXTensorRT(file_name_t path_to_engine, int device, float nms_th, float conf_th, std::string model_version, - int num_classes) - :AbcYoloX(nms_th, conf_th, model_version, num_classes), + int num_classes, bool p6) + :AbcYoloX(nms_th, conf_th, model_version, num_classes, p6), DEVICE_(device) { cudaSetDevice(this->DEVICE_); @@ -56,7 +56,14 @@ namespace yolox_cpp{ assert(this->engine_->getBindingDataType(this->outputIndex_) == nvinfer1::DataType::kFLOAT); // Prepare GridAndStrides - generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + if(this->p6_) + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_p6_, this->grid_strides_); + } + else + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + } } std::vector YoloXTensorRT::inference(const cv::Mat& frame) diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp index 2bc12ec..83a8e99 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_tflite.cpp @@ -5,8 +5,8 @@ namespace yolox_cpp YoloXTflite::YoloXTflite(file_name_t path_to_model, int num_threads, float nms_th, float conf_th, std::string model_version, - int num_classes, bool is_nchw) - : AbcYoloX(nms_th, conf_th, model_version, num_classes), is_nchw_(is_nchw) + int num_classes, bool p6, bool is_nchw) + : AbcYoloX(nms_th, conf_th, model_version, num_classes, p6), is_nchw_(is_nchw) { TfLiteStatus status; this->model_ = tflite::FlatBufferModel::BuildFromFile(path_to_model.c_str()); @@ -129,7 +129,14 @@ namespace yolox_cpp } // Prepare GridAndStrides - generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + if(this->p6_) + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_p6_, this->grid_strides_); + } + else + { + generate_grids_and_stride(this->input_w_, this->input_h_, this->strides_, this->grid_strides_); + } } YoloXTflite::~YoloXTflite() { diff --git a/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp b/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp index 63e9e20..a8f233f 100644 --- a/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp +++ b/yolox_ros_cpp/yolox_ros_cpp/include/yolox_ros_cpp/yolox_ros_cpp.hpp @@ -42,6 +42,7 @@ namespace yolox_ros_cpp{ float nms_th_; int num_classes_; bool is_nchw_; + bool p6_; std::vector class_names_; std::string class_labels_path_; 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 552c3cf..217c6dc 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 @@ -19,6 +19,11 @@ def generate_launch_description(): default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/onnx/yolox_nano.onnx", description="yolox model path." ), + DeclareLaunchArgument( + "p6", + default_value="false", + description="with p6." + ), DeclareLaunchArgument( "class_labels_path", default_value="''", @@ -110,6 +115,7 @@ def generate_launch_description(): 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", 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 46fb322..af017ca 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 @@ -19,6 +19,11 @@ def generate_launch_description(): default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/openvino/yolox_nano.xml", description="yolox model path." ), + DeclareLaunchArgument( + "p6", + default_value="false", + description="with p6." + ), DeclareLaunchArgument( "class_labels_path", default_value="''", @@ -90,6 +95,7 @@ def generate_launch_description(): 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", 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 index ae67f4c..9b423ad 100644 --- 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 @@ -19,6 +19,11 @@ def generate_launch_description(): 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="''", @@ -85,6 +90,7 @@ def generate_launch_description(): 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", 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 374a118..ac08f95 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 @@ -20,6 +20,11 @@ def generate_launch_description(): 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="''", @@ -92,6 +97,7 @@ def generate_launch_description(): 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", 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 index 792dac3..4d9193f 100644 --- 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 @@ -20,6 +20,11 @@ def generate_launch_description(): 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="''", @@ -87,6 +92,7 @@ def generate_launch_description(): 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", 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 df50319..e58efe7 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 @@ -19,6 +19,11 @@ def generate_launch_description(): default_value="./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite", description="yolox model path." ), + DeclareLaunchArgument( + "p6", + default_value="false", + description="with p6." + ), DeclareLaunchArgument( "is_nchw", default_value="true", @@ -95,6 +100,7 @@ def generate_launch_description(): 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"), 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 31d034d..6d55fc6 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 @@ -35,7 +35,7 @@ namespace yolox_ros_cpp{ RCLCPP_INFO(this->get_logger(), "Model Type is TensorRT"); this->yolox_ = std::make_unique(this->model_path_, this->tensorrt_device_, this->nms_th_, this->conf_th_, this->model_version_, - this->num_classes_); + this->num_classes_, this->p6_); #else RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with TensorRT"); rclcpp::shutdown(); @@ -45,7 +45,7 @@ namespace yolox_ros_cpp{ RCLCPP_INFO(this->get_logger(), "Model Type is OpenVINO"); this->yolox_ = std::make_unique(this->model_path_, this->openvino_device_, this->nms_th_, this->conf_th_, this->model_version_, - this->num_classes_); + this->num_classes_, this->p6_); #else RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with OpenVINO"); rclcpp::shutdown(); @@ -59,8 +59,7 @@ namespace yolox_ros_cpp{ this->onnxruntime_use_cuda_, this->onnxruntime_device_id_, this->onnxruntime_use_parallel_, this->nms_th_, this->conf_th_, this->model_version_, - this->num_classes_ - ); + this->num_classes_, this->p6_); #else RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with ONNXRuntime"); rclcpp::shutdown(); @@ -70,8 +69,7 @@ namespace yolox_ros_cpp{ RCLCPP_INFO(this->get_logger(), "Model Type is tflite"); this->yolox_ = std::make_unique(this->model_path_, this->tflite_num_threads_, this->nms_th_, this->conf_th_, this->model_version_, - this->num_classes_, this->is_nchw_ - ); + this->num_classes_, this->p6_, this->is_nchw_); #else RCLCPP_ERROR(this->get_logger(), "yolox_cpp is not built with tflite"); rclcpp::shutdown(); @@ -93,52 +91,34 @@ namespace yolox_ros_cpp{ void YoloXNode::initializeParameter() { - this->declare_parameter("imshow_isshow", true); - this->declare_parameter("model_path", "./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite"); - this->declare_parameter("num_classes", 1); - this->declare_parameter("is_nchw", true); - this->declare_parameter("class_labels_path", ""); - this->declare_parameter("conf", 0.3f); - this->declare_parameter("nms", 0.45f); - this->declare_parameter("tensorrt/device", 0); - this->declare_parameter("openvino/device", "CPU"); - this->declare_parameter("onnxruntime/use_cuda", true); - this->declare_parameter("onnxruntime/device_id", 0); - this->declare_parameter("onnxruntime/use_parallel", false); - this->declare_parameter("onnxruntime/inter_op_num_threads", 1); - this->declare_parameter("onnxruntime/intra_op_num_threads", 1); - this->declare_parameter("tflite/num_threads", 1); - this->declare_parameter("model_type", "tflite"); - this->declare_parameter("model_version", "0.1.1rc0"); - this->declare_parameter("src_image_topic_name", "image_raw"); - this->declare_parameter("publish_image_topic_name", "yolox/image_raw"); - this->declare_parameter("publish_boundingbox_topic_name", "yolox/bounding_boxes"); - - this->get_parameter("imshow_isshow", this->imshow_); - this->get_parameter("model_path", this->model_path_); - this->get_parameter("class_labels_path", this->class_labels_path_); - this->get_parameter("num_classes", this->num_classes_); - this->get_parameter("is_nchw", this->is_nchw_); - this->get_parameter("conf", this->conf_th_); - this->get_parameter("nms", this->nms_th_); - this->get_parameter("tensorrt/device", this->tensorrt_device_); - this->get_parameter("openvino/device", this->openvino_device_); - this->get_parameter("onnxruntime/use_cuda", this->onnxruntime_use_cuda_); - this->get_parameter("onnxruntime/device_id", this->onnxruntime_device_id_); - this->get_parameter("onnxruntime/use_parallel", this->onnxruntime_use_parallel_); - this->get_parameter("onnxruntime/inter_op_num_threads", this->onnxruntime_inter_op_num_threads_); - this->get_parameter("tflite/num_threads", this->tflite_num_threads_); - this->get_parameter("model_type", this->model_type_); - this->get_parameter("model_version", this->model_version_); - this->get_parameter("src_image_topic_name", this->src_image_topic_name_); - this->get_parameter("publish_image_topic_name", this->publish_image_topic_name_); - this->get_parameter("publish_boundingbox_topic_name", this->publish_boundingbox_topic_name_); + this->imshow_ = this->declare_parameter("imshow_isshow", true); + this->model_path_ = this->declare_parameter("model_path", "./install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model.tflite"); + this->num_classes_ = this->declare_parameter("num_classes", 1); + this->is_nchw_ = this->declare_parameter("is_nchw", true); + this->p6_ = this->declare_parameter("p6", false); + this->class_labels_path_ = this->declare_parameter("class_labels_path", ""); + this->conf_th_ = this->declare_parameter("conf", 0.3f); + this->nms_th_ = this->declare_parameter("nms", 0.45f); + this->tensorrt_device_ = this->declare_parameter("tensorrt/device", 0); + this->openvino_device_ = this->declare_parameter("openvino/device", "CPU"); + this->onnxruntime_use_cuda_ = this->declare_parameter("onnxruntime/use_cuda", true); + this->onnxruntime_device_id_ = this->declare_parameter("onnxruntime/device_id", 0); + this->onnxruntime_use_parallel_ = this->declare_parameter("onnxruntime/use_parallel", false); + this->onnxruntime_inter_op_num_threads_ = this->declare_parameter("onnxruntime/inter_op_num_threads", 1); + this->onnxruntime_intra_op_num_threads_ = this->declare_parameter("onnxruntime/intra_op_num_threads", 1); + this->tflite_num_threads_ = this->declare_parameter("tflite/num_threads", 1); + this->model_type_ = this->declare_parameter("model_type", "tflite"); + this->model_version_ = this->declare_parameter("model_version", "0.1.1rc0"); + this->src_image_topic_name_ = this->declare_parameter("src_image_topic_name", "image_raw"); + this->publish_image_topic_name_ = this->declare_parameter("publish_image_topic_name", "yolox/image_raw"); + this->publish_boundingbox_topic_name_ = this->declare_parameter("publish_boundingbox_topic_name", "yolox/bounding_boxes"); RCLCPP_INFO(this->get_logger(), "Set parameter imshow_isshow: %i", this->imshow_); RCLCPP_INFO(this->get_logger(), "Set parameter model_path: '%s'", this->model_path_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter class_labels_path: '%s'", this->class_labels_path_.c_str()); RCLCPP_INFO(this->get_logger(), "Set parameter num_classes: %i", this->num_classes_); RCLCPP_INFO(this->get_logger(), "Set parameter is_nchw: %i", this->is_nchw_); + RCLCPP_INFO(this->get_logger(), "Set parameter p6: %i", this->p6_); RCLCPP_INFO(this->get_logger(), "Set parameter conf: %f", this->conf_th_); RCLCPP_INFO(this->get_logger(), "Set parameter nms: %f", this->nms_th_); RCLCPP_INFO(this->get_logger(), "Set parameter tensorrt/device: %i", this->tensorrt_device_); From c9274836982f3f334243336e3358f2d26f66a347 Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 23:27:53 +0900 Subject: [PATCH 6/8] Update README.md --- yolox_ros_cpp/README.md | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 1ddbc98..31a5d62 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -16,6 +16,8 @@ ※ Tensorflow Lite support XNNPACK Delegate only. +※ Tensorflow Lite support float model and does not support integer model. + ※ Model convert script is not supported OpenVINO 2022.* ※ YOLOX is not required. @@ -164,9 +166,12 @@ cd ~/ros2_ws - ONNX model copy to weight dir - `cp resouces_new/saved_model_yolox_nano_480x640/yolox_nano_480x640.onnx ./src/YOLOX-ROS/weights/onnx/` + - Convert to TensorRT engine - `./src/YOLOX-ROS/weights/tensorrt/convert.bash yolox_nano_480x640` +- tflite model copy to weight dir + - `cp resouces_new/saved_model_yolox_nano_480x640/model_float32.tflite ./src/YOLOX-ROS/weights/tflite/` ### build packages ```bash @@ -275,6 +280,13 @@ export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:${workspace}/tflite_build # run Person Detection Model ros2 launch yolox_ros_cpp yolox_tflite.launch.py + +# run PINTO_model_zoo model +ros2 launch yolox_ros_cpp yolox_tflite.launch.py \ + model_path:=install/yolox_ros_cpp/share/yolox_ros_cpp/weights/tflite/model_float32.tflite \ + model_version:=0.1.0 \ + num_classes:=80 \ + is_nchw:=false ``` ### Parameter @@ -335,7 +347,7 @@ ros2 launch yolox_ros_cpp yolox_tflite.launch.py - `p6`: false - `is_nchw`: true - `class_labels_path`: "" -- `num_classes`: 80 +- `num_classes`: 1 - `model_version`: 0.1.1rc0 - `tflite/num_threads`: 1 - `conf`: 0.3 From 3d4cd2d160b0c56d83c1854f1f35bf7eb4c596ce Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 23:31:48 +0900 Subject: [PATCH 7/8] Update README.md --- yolox_ros_cpp/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/yolox_ros_cpp/README.md b/yolox_ros_cpp/README.md index 31a5d62..c1ea2a7 100644 --- a/yolox_ros_cpp/README.md +++ b/yolox_ros_cpp/README.md @@ -215,6 +215,7 @@ This is build script when tflite built as above. ```bash # build with tflite colcon build --symlink-install \ + --packages-up-to yolox_ros_cpp \ --cmake-args \ -DYOLOX_USE_TFLITE=ON \ -DTFLITE_LIB_PATH=${workspace}/tflite_build/libtensorflow-lite.so \ From 0a7e86acb49660cb90d922adcdce7928acb06dc9 Mon Sep 17 00:00:00 2001 From: fateshelled <53618876+fateshelled@users.noreply.github.com> Date: Thu, 29 Dec 2022 23:39:58 +0900 Subject: [PATCH 8/8] fix tensorrt --- yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp b/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp index f7da8d5..7b86c8c 100644 --- a/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp +++ b/yolox_ros_cpp/yolox_cpp/src/yolox_tensorrt.cpp @@ -103,7 +103,7 @@ namespace yolox_cpp{ // DMA input batch data to device, infer on the batch asynchronously, and DMA output back to host CHECK(cudaMemcpyAsync(buffers[this->inputIndex_], input, 3 * this->input_h_ * this->input_w_ * sizeof(float), cudaMemcpyHostToDevice, stream)); - context_->enqueue(1, buffers, stream, nullptr); + context_->enqueueV2(buffers, stream, nullptr); CHECK(cudaMemcpyAsync(output, buffers[this->outputIndex_], this->output_size_ * sizeof(float), cudaMemcpyDeviceToHost, stream)); cudaStreamSynchronize(stream);