diff --git a/common/tvm_utility/include/tvm_utility/pipeline.hpp b/common/tvm_utility/include/tvm_utility/pipeline.hpp index dd7a104bcda14..600d12e1e3ec8 100644 --- a/common/tvm_utility/include/tvm_utility/pipeline.hpp +++ b/common/tvm_utility/include/tvm_utility/pipeline.hpp @@ -16,7 +16,6 @@ #define TVM_UTILITY__PIPELINE_HPP_ #include -#include #include #include @@ -30,8 +29,6 @@ #include #include -using autoware::common::types::char8_t; - namespace tvm_utility { @@ -190,7 +187,7 @@ using NetworkNode = std::pair>; typedef struct { // Network info - std::array modelzoo_version; + std::array modelzoo_version; std::string network_name; std::string network_backend; @@ -315,7 +312,7 @@ class InferenceEngineTVM : public InferenceEngine * @param[in] version_from Earliest supported model version. * @return The version status. */ - Version version_check(const std::array & version_from) const + Version version_check(const std::array & version_from) const { auto x{config_.modelzoo_version[0]}; auto y{config_.modelzoo_version[1]}; @@ -339,7 +336,7 @@ class InferenceEngineTVM : public InferenceEngine tvm::runtime::PackedFunc execute; tvm::runtime::PackedFunc get_output; // Latest supported model version. - const std::array version_up_to{2, 1, 0}; + const std::array version_up_to{2, 1, 0}; }; } // namespace pipeline diff --git a/common/tvm_utility/package.xml b/common/tvm_utility/package.xml index ea2a6c8940f73..e648a3bd47b59 100644 --- a/common/tvm_utility/package.xml +++ b/common/tvm_utility/package.xml @@ -29,7 +29,6 @@ autoware_cmake ament_index_cpp - autoware_auto_common libopenblas-dev libopencv-dev tvm_vendor diff --git a/common/tvm_utility/test/yolo_v2_tiny/main.cpp b/common/tvm_utility/test/yolo_v2_tiny/main.cpp index 4ed77f0f97d83..11acf571456b8 100644 --- a/common/tvm_utility/test/yolo_v2_tiny/main.cpp +++ b/common/tvm_utility/test/yolo_v2_tiny/main.cpp @@ -120,7 +120,8 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessorstrides == nullptr); assert(input[0].getArray()->dtype.bits == sizeof(float) * 8); - // Get a pointer to the output data - float * data_ptr = reinterpret_cast( - reinterpret_cast(input[0].getArray()->data) + input[0].getArray()->byte_offset); + // Copy the inference data to CPU memory + std::vector infer( + network_output_width * network_output_height * network_output_depth, 0); + TVMArrayCopyToBytes( + input[0].getArray(), infer.data(), + network_output_width * network_output_height * network_output_depth * network_datatype_bytes); // Utility function to return data from y given index - auto get_output_data = [this, data_ptr, n_classes, n_anchors, n_coords]( + auto get_output_data = [this, infer, n_classes, n_anchors, n_coords]( auto row_i, auto col_j, auto anchor_k, auto offset) { auto box_index = (row_i * network_output_height + col_j) * network_output_depth; auto index = box_index + anchor_k * (n_classes + n_coords + 1); - return data_ptr[index + offset]; + return infer[index + offset]; }; // Vector used to check if the result is accurate, @@ -228,6 +232,7 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor labels{}; std::vector> anchors{}; };