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

add hailort support #47

Open
wants to merge 1 commit into
base: humble
Choose a base branch
from
Open
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
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@ YOLOX_outputs/
*.trt
*.engine
*.tflite
*.hef
YOLOX/
YOLOX_outputs/
install/
Expand Down
3 changes: 3 additions & 0 deletions weights/hailort/download.bash
Original file line number Diff line number Diff line change
@@ -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
Empty file modified weights/onnx/download.bash
100755 → 100644
Empty file.
Empty file modified weights/openvino/install.bash
100755 → 100644
Empty file.
Empty file modified weights/tensorrt/convert.bash
100755 → 100644
Empty file.
20 changes: 20 additions & 0 deletions yolox_ros_cpp/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
```


<br>

## Run
Expand Down Expand Up @@ -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

<details>
Expand Down Expand Up @@ -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
Empty file modified yolox_ros_cpp/docker/onnxruntime/ros_entrypoint.sh
100755 → 100644
Empty file.
Empty file modified yolox_ros_cpp/docker/openvino/ros_entrypoint.sh
100755 → 100644
Empty file.
Empty file modified yolox_ros_cpp/docker/tensorrt/ros_entrypoint.sh
100755 → 100644
Empty file.
15 changes: 14 additions & 1 deletion yolox_ros_cpp/yolox_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,15 @@ 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)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -I/usr/include/aarch64-linux-gnu/ -L/usr/lib/aarch64-linux-gnu/")
set(YOLOX_USE_TENSORRT ON)
endif()

if(NOT YOLOX_USE_OPENVINO AND NOT YOLOX_USE_TENSORRT AND NOT YOLOX_USE_ONNXRUNTIME AND NOT YOLOX_USE_TFLITE)
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()
Expand All @@ -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)
Expand Down Expand Up @@ -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"
Expand All @@ -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)
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 @@ -5,5 +5,6 @@
#cmakedefine ENABLE_TENSORRT
#cmakedefine ENABLE_ONNXRUNTIME
#cmakedefine ENABLE_TFLITE
#cmakedefine ENABLE_HAILORT

#endif // _YOLOX_CPP_CONFIG_H_
167 changes: 167 additions & 0 deletions yolox_ros_cpp/yolox_cpp/include/yolox_cpp/hailort_common.hpp
Original file line number Diff line number Diff line change
@@ -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 <algorithm>
#include <iostream>
#include <hailo/hailort.hpp>
#include <sstream>
#include <thread>

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<uint8_t> &data);

namespace hailortCommon
{
template <typename T>
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<uint8_t> &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<std::shared_ptr<ConfiguredNetworkGroup>>
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<InputVStream> &input_streams, std::vector<OutputVStream> &output_streams, unsigned char *data, std::vector<std::vector<uint8_t>> &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<std::thread> input_threads[MAX_LAYER_EDGES];
std::unique_ptr<std::thread> 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<std::thread>(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<std::thread>(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
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 @@ -19,5 +19,9 @@
#include "yolox_tflite.hpp"
#endif

#ifdef ENABLE_HAILORT
#include "yolox_hailort.hpp"
#endif


#endif
76 changes: 76 additions & 0 deletions yolox_ros_cpp/yolox_cpp/include/yolox_cpp/yolox_hailort.hpp
Original file line number Diff line number Diff line change
@@ -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 <algorithm>
#include <cassert>
#include <filesystem>
#include <iostream>
#include <omp.h>
#include <opencv2/opencv.hpp>
#include <sstream>

#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<Object> inference(const cv::Mat &src) override;

protected:
std::string hef_path_;
float nms_thresh_;
float thresh_;
int num_classes_;

int output_index_;
std::vector<std::vector<float>> f_results_;
std::vector<std::vector<uint8_t>> results_;
std::vector<int> m_output_strides;
std::unique_ptr<VDevice> vdevice_;

std::vector<InputVStream> input_streams_;
std::vector<OutputVStream> output_streams_;

std::shared_ptr<hailortCommon::HrtCommon> hrtCommon;
Expected<std::vector<std::reference_wrapper<Device>>> physical_devices;
Expected<std::pair<std::vector<InputVStream>, std::vector<OutputVStream>>> vstreams;

hailo_vstream_info_t input_info_;
};
}

#endif // _YOLOX_CPP_YOLOX_HAILORT_HPP
Loading