Skip to content

Commit

Permalink
fix(tvm_utility): copy test result to CPU (autowarefoundation#2414)
Browse files Browse the repository at this point in the history
Also remove dependency to autoware_auto_common.

Issue-Id: SCM-5401
Signed-off-by: Ambroise Vincent <ambroise.vincent@arm.com>
Change-Id: I83b859742df2f2ff7df1d0bd2d287bfe0aa04c3d

Signed-off-by: Ambroise Vincent <ambroise.vincent@arm.com>
Co-authored-by: Xinyu Wang <93699235+angry-crab@users.noreply.github.com>
  • Loading branch information
ambroise-arm and angry-crab committed Dec 6, 2022
1 parent eb99468 commit a1d3c80
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 13 deletions.
9 changes: 3 additions & 6 deletions common/tvm_utility/include/tvm_utility/pipeline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,6 @@
#define TVM_UTILITY__PIPELINE_HPP_

#include <ament_index_cpp/get_package_share_directory.hpp>
#include <common/types.hpp>

#include <tvm_vendor/dlpack/dlpack.h>
#include <tvm_vendor/tvm/runtime/c_runtime_api.h>
Expand All @@ -30,8 +29,6 @@
#include <utility>
#include <vector>

using autoware::common::types::char8_t;

namespace tvm_utility
{

Expand Down Expand Up @@ -190,7 +187,7 @@ using NetworkNode = std::pair<std::string, std::vector<int64_t>>;
typedef struct
{
// Network info
std::array<char8_t, 3> modelzoo_version;
std::array<char, 3> modelzoo_version;
std::string network_name;
std::string network_backend;

Expand Down Expand Up @@ -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<char8_t, 3> & version_from) const
Version version_check(const std::array<char, 3> & version_from) const
{
auto x{config_.modelzoo_version[0]};
auto y{config_.modelzoo_version[1]};
Expand All @@ -339,7 +336,7 @@ class InferenceEngineTVM : public InferenceEngine
tvm::runtime::PackedFunc execute;
tvm::runtime::PackedFunc get_output;
// Latest supported model version.
const std::array<char8_t, 3> version_up_to{2, 1, 0};
const std::array<char, 3> version_up_to{2, 1, 0};
};

} // namespace pipeline
Expand Down
1 change: 0 additions & 1 deletion common/tvm_utility/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,6 @@
<build_depend>autoware_cmake</build_depend>

<depend>ament_index_cpp</depend>
<depend>autoware_auto_common</depend>
<depend>libopenblas-dev</depend>
<depend>libopencv-dev</depend>
<depend>tvm_vendor</depend>
Expand Down
17 changes: 11 additions & 6 deletions common/tvm_utility/test/yolo_v2_tiny/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,8 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor<std:
explicit PostProcessorYoloV2Tiny(tvm_utility::pipeline::InferenceEngineTVMConfig config)
: network_output_width(config.network_outputs[0].second[1]),
network_output_height(config.network_outputs[0].second[2]),
network_output_depth(config.network_outputs[0].second[3])
network_output_depth(config.network_outputs[0].second[3]),
network_datatype_bytes(config.tvm_dtype_bits / 8)
{
// Parse human readable names for the classes
std::ifstream label_file{LABEL_FILENAME};
Expand Down Expand Up @@ -164,16 +165,19 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor<std:
assert(input[0].getArray()->strides == nullptr);
assert(input[0].getArray()->dtype.bits == sizeof(float) * 8);

// Get a pointer to the output data
float * data_ptr = reinterpret_cast<float *>(
reinterpret_cast<uint8_t *>(input[0].getArray()->data) + input[0].getArray()->byte_offset);
// Copy the inference data to CPU memory
std::vector<float> 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,
Expand Down Expand Up @@ -228,6 +232,7 @@ class PostProcessorYoloV2Tiny : public tvm_utility::pipeline::PostProcessor<std:
int64_t network_output_width;
int64_t network_output_height;
int64_t network_output_depth;
int64_t network_datatype_bytes;
std::vector<std::string> labels{};
std::vector<std::pair<float, float>> anchors{};
};
Expand Down

0 comments on commit a1d3c80

Please sign in to comment.