Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

support tflite C++ #31

Merged
merged 8 commits into from
Dec 30, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
111 changes: 101 additions & 10 deletions yolox_ros_cpp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,11 +8,16 @@
- 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.

※ Tensorflow Lite support float model and does not support integer model.

※ Model convert script is not supported OpenVINO 2022.*

※ YOLOX is not required.
Expand Down Expand Up @@ -144,6 +149,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.
Expand All @@ -152,9 +166,12 @@ source /opt/ros/foxy/setup.bash

- 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
Expand All @@ -167,6 +184,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)"
```

##### build ros package with tflite

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 \
-DTFLITE_INCLUDE_DIR=${workspace}/tensorflow_src \
-DABSEIL_CPP_ICLUDE_DIR=${workspace}/tflite_build/abseil-cpp \
-DFLATBUFFERS_INCLUDE_DIR=${workspace}/tflite_build/flatbuffers/include
```

### Run

#### OpenVINO
Expand Down Expand Up @@ -217,9 +274,26 @@ ros2 launch yolox_ros_cpp yolox_tensorrt_jetson.launch.py
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

# 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
#### 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.
Expand All @@ -229,27 +303,29 @@ 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.
- `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
- `tensorrt/device`: 0
- `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.
- `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
Expand All @@ -263,9 +339,24 @@ 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
- `p6`: false
- `is_nchw`: true
- `class_labels_path`: ""
- `num_classes`: 1
- `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
Expand Down
53 changes: 41 additions & 12 deletions yolox_ros_cpp/yolox_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -46,43 +52,60 @@ 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()
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()

Expand All @@ -91,6 +114,8 @@ configure_file(
"${PROJECT_SOURCE_DIR}/include/yolox_cpp/config.h"
)

set(INCLUDES ${INCLUDES} $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>)
set(INCLUDES ${INCLUDES} $<INSTALL_INTERFACE:include>)

add_library(yolox_cpp SHARED
${SRC}
Expand All @@ -102,8 +127,7 @@ target_compile_definitions(yolox_cpp
target_compile_options(yolox_cpp PUBLIC -Wall)

target_include_directories(yolox_cpp PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>
${INCLUDES}
)

ament_target_dependencies(yolox_cpp
Expand Down Expand Up @@ -132,6 +156,11 @@ if(ENABLE_ONNXRUNTIME)
onnxruntime
)
endif()
if(ENABLE_TFLITE)
target_link_libraries(yolox_cpp
${TFLITE_LIB_PATH}
)
endif()



Expand Down
1 change: 1 addition & 0 deletions yolox_ros_cpp/yolox_cpp/include/yolox_cpp/config.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -4,5 +4,6 @@
#cmakedefine ENABLE_OPENVINO
#cmakedefine ENABLE_TENSORRT
#cmakedefine ENABLE_ONNXRUNTIME
#cmakedefine ENABLE_TFLITE

#endif // _YOLOX_CPP_CONFIG_H_
39 changes: 34 additions & 5 deletions yolox_ros_cpp/yolox_cpp/include/yolox_cpp/core.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<Object> inference(const cv::Mat& frame) = 0;
Expand All @@ -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<float> mean_ = {0.485, 0.456, 0.406};
const std::vector<float> std_ = {0.229, 0.224, 0.225};
const std::vector<int> strides_ = {8, 16, 32};
const std::vector<int> strides_p6_ = {8, 16, 32, 64};
std::vector<GridAndStride> grid_strides_;

cv::Mat static_resize(const cv::Mat& img)
Expand All @@ -61,11 +63,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)
{
Expand All @@ -92,6 +95,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<int>& strides, std::vector<GridAndStride>& grid_strides)
{
for (auto stride : strides)
Expand Down
4 changes: 4 additions & 0 deletions yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,5 +15,9 @@
#include "yolox_onnxruntime.hpp"
#endif

#ifdef ENABLE_TFLITE
#include "yolox_tflite.hpp"
#endif


#endif
Loading