From db37c877712a583da96c4fa3e38977673b8e0709 Mon Sep 17 00:00:00 2001 From: Xinyu Wang <93699235+angry-crab@users.noreply.github.com> Date: Fri, 23 Dec 2022 08:35:39 +0900 Subject: [PATCH] refactor(tvm_utility): redefine network node and inference config (#2467) * redefine network node and inference config Signed-off-by: Xinyu Wang * accomondate network node changes Signed-off-by: Xinyu Wang * ci(pre-commit): autofix * revert device type and id Signed-off-by: Xinyu Wang * cmake setting Signed-off-by: Xinyu Wang * data type and modelzoo version Signed-off-by: Xinyu Wang Signed-off-by: Xinyu Wang Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .../include/tvm_utility/pipeline.hpp | 28 ++++++++++------ common/tvm_utility/test/yolo_v2_tiny/main.cpp | 32 ++++++++++--------- common/tvm_utility/tvm_utility-extras.cmake | 15 +++++++-- .../lidar_apollo_segmentation_tvm.hpp | 4 +-- .../src/lidar_apollo_segmentation_tvm.cpp | 26 +++++++-------- 5 files changed, 63 insertions(+), 42 deletions(-) diff --git a/common/tvm_utility/include/tvm_utility/pipeline.hpp b/common/tvm_utility/include/tvm_utility/pipeline.hpp index 600d12e1e3ec8..c6ecd9ca15194 100644 --- a/common/tvm_utility/include/tvm_utility/pipeline.hpp +++ b/common/tvm_utility/include/tvm_utility/pipeline.hpp @@ -182,8 +182,21 @@ class Pipeline PostProcessorType post_processor_{}; }; -// Each node should be specified with a string name and a shape -using NetworkNode = std::pair>; +// NetworkNode +typedef struct +{ + // Node name + std::string node_name; + + // Network data type configurations + DLDataTypeCode tvm_dtype_code; + int32_t tvm_dtype_bits; + int32_t tvm_dtype_lanes; + + // Shape info + std::vector node_shape; +} NetworkNode; + typedef struct { // Network info @@ -196,11 +209,6 @@ typedef struct std::string network_graph_path; std::string network_params_path; - // Network data type configurations - DLDataTypeCode tvm_dtype_code; - int32_t tvm_dtype_bits; - int32_t tvm_dtype_lanes; - // Inference hardware configuration DLDeviceType tvm_device_type; int32_t tvm_device_id; @@ -278,8 +286,8 @@ class InferenceEngineTVM : public InferenceEngine for (auto & output_config : config.network_outputs) { output_.push_back(TVMArrayContainer( - output_config.second, config.tvm_dtype_code, config.tvm_dtype_bits, config.tvm_dtype_lanes, - config.tvm_device_type, config.tvm_device_id)); + output_config.node_shape, output_config.tvm_dtype_code, output_config.tvm_dtype_bits, + output_config.tvm_dtype_lanes, config.tvm_device_type, config.tvm_device_id)); } } @@ -290,7 +298,7 @@ class InferenceEngineTVM : public InferenceEngine if (input[index].getArray() == nullptr) { throw std::runtime_error("input variable is null"); } - set_input(config_.network_inputs[index].first.c_str(), input[index].getArray()); + set_input(config_.network_inputs[index].node_name.c_str(), input[index].getArray()); } // Execute the inference diff --git a/common/tvm_utility/test/yolo_v2_tiny/main.cpp b/common/tvm_utility/test/yolo_v2_tiny/main.cpp index 11acf571456b8..aac7900f423c2 100644 --- a/common/tvm_utility/test/yolo_v2_tiny/main.cpp +++ b/common/tvm_utility/test/yolo_v2_tiny/main.cpp @@ -45,18 +45,18 @@ class PreProcessorYoloV2Tiny : public tvm_utility::pipeline::PreProcessor shape_x{1, network_input_width, network_input_height, network_input_depth}; tvm_utility::pipeline::TVMArrayContainer x{ shape_x, - config.tvm_dtype_code, - config.tvm_dtype_bits, - config.tvm_dtype_lanes, + config.network_inputs[0].tvm_dtype_code, + config.network_inputs[0].tvm_dtype_bits, + config.network_inputs[0].tvm_dtype_lanes, config.tvm_device_type, config.tvm_device_id}; @@ -101,7 +101,8 @@ class PreProcessorYoloV2Tiny : public tvm_utility::pipeline::PreProcessor labels{}; std::vector> anchors{}; }; diff --git a/common/tvm_utility/tvm_utility-extras.cmake b/common/tvm_utility/tvm_utility-extras.cmake index 7affa4752b5e4..f346aa8fb4922 100644 --- a/common/tvm_utility/tvm_utility-extras.cmake +++ b/common/tvm_utility/tvm_utility-extras.cmake @@ -14,7 +14,7 @@ # Get user-provided variables set(DOWNLOAD_ARTIFACTS OFF CACHE BOOL "enable artifacts download") -set(MODELZOO_VERSION "2.1.0-20221102" CACHE STRING "targeted ModelZoo version") +set(MODELZOO_VERSION "3.0.0-20221221" CACHE STRING "targeted ModelZoo version") # # Download the selected neural network if it is not already present on disk. @@ -32,6 +32,7 @@ set(MODELZOO_VERSION "2.1.0-20221102" CACHE STRING "targeted ModelZoo version") function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY) set(DATA_PATH ${CMAKE_CURRENT_SOURCE_DIR}/data) set(EXTERNALPROJECT_NAME ${MODEL_NAME}_${MODEL_BACKEND}) + set(PREPROCESSING "") # Prioritize user-provided models. if(IS_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}") @@ -42,6 +43,13 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY) "${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp" COPYONLY ) + if(EXISTS "${DATA_PATH}/user/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") + configure_file( + "${DATA_PATH}/user/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp" + "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp" + COPYONLY + ) + endif() set(DOWNLOAD_DIR "") set(SOURCE_DIR "${DATA_PATH}/user/${MODEL_NAME}") set(INSTALL_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}") @@ -63,7 +71,9 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY) set(SOURCE_DIR "${DATA_PATH}/models/${MODEL_NAME}") set(INSTALL_DIRECTORY "${DATA_PATH}/models/${MODEL_NAME}") endif() - + if(EXISTS "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") + set(PREPROCESSING "${DATA_PATH}/models/${MODEL_NAME}/preprocessing_inference_engine_tvm_config.hpp") + endif() include(ExternalProject) externalproject_add(${EXTERNALPROJECT_NAME} DOWNLOAD_DIR ${DOWNLOAD_DIR} @@ -72,6 +82,7 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY) CONFIGURE_COMMAND "" BUILD_COMMAND "" BUILD_BYPRODUCTS "${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp" + BUILD_BYPRODUCTS ${PREPROCESSING} INSTALL_COMMAND "" ) install( diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp index abe1325eb1419..089381ab51c61 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp @@ -79,7 +79,7 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_LOCAL ApolloLidarSegmentationPreProcessor const int64_t input_channels; const int64_t input_width; const int64_t input_height; - const int64_t datatype_bytes; + const int64_t input_datatype_bytes; const std::shared_ptr feature_generator; TVMArrayContainer output; }; @@ -115,7 +115,7 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_LOCAL ApolloLidarSegmentationPostProcessor const int64_t output_channels; const int64_t output_width; const int64_t output_height; - const int64_t datatype_bytes; + const int64_t output_datatype_bytes; const float32_t objectness_thresh_; const float32_t score_threshold_; const float32_t height_thresh_; diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index 261e57cb894eb..49ecbae311b58 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -36,10 +36,10 @@ ApolloLidarSegmentationPreProcessor::ApolloLidarSegmentationPreProcessor( const tvm_utility::pipeline::InferenceEngineTVMConfig & config, int32_t range, bool8_t use_intensity_feature, bool8_t use_constant_feature, float32_t min_height, float32_t max_height) -: input_channels(config.network_inputs[0].second[1]), - input_width(config.network_inputs[0].second[2]), - input_height(config.network_inputs[0].second[3]), - datatype_bytes(config.tvm_dtype_bits / 8), +: input_channels(config.network_inputs[0].node_shape[1]), + input_width(config.network_inputs[0].node_shape[2]), + input_height(config.network_inputs[0].node_shape[3]), + input_datatype_bytes(config.network_inputs[0].tvm_dtype_bits / 8), feature_generator(std::make_shared( input_width, input_height, range, use_intensity_feature, use_constant_feature, min_height, max_height)) @@ -48,9 +48,9 @@ ApolloLidarSegmentationPreProcessor::ApolloLidarSegmentationPreProcessor( std::vector shape_x{1, input_channels, input_width, input_height}; TVMArrayContainer x{ shape_x, - config.tvm_dtype_code, - config.tvm_dtype_bits, - config.tvm_dtype_lanes, + config.network_inputs[0].tvm_dtype_code, + config.network_inputs[0].tvm_dtype_bits, + config.network_inputs[0].tvm_dtype_lanes, config.tvm_device_type, config.tvm_device_id}; output = x; @@ -68,7 +68,7 @@ TVMArrayContainerVector ApolloLidarSegmentationPreProcessor::schedule( TVMArrayCopyFromBytes( output.getArray(), feature_map_ptr->map_data.data(), - input_channels * input_height * input_width * datatype_bytes); + input_channels * input_height * input_width * input_datatype_bytes); return {output}; } @@ -78,10 +78,10 @@ ApolloLidarSegmentationPostProcessor::ApolloLidarSegmentationPostProcessor( const pcl::PointCloud::ConstPtr & pc_ptr, int32_t range, float32_t objectness_thresh, float32_t score_threshold, float32_t height_thresh, int32_t min_pts_num) -: output_channels(config.network_outputs[0].second[1]), - output_width(config.network_outputs[0].second[2]), - output_height(config.network_outputs[0].second[3]), - datatype_bytes(config.tvm_dtype_bits / 8), +: output_channels(config.network_outputs[0].node_shape[1]), + output_width(config.network_outputs[0].node_shape[2]), + output_height(config.network_outputs[0].node_shape[3]), + output_datatype_bytes(config.network_outputs[0].tvm_dtype_bits / 8), objectness_thresh_(objectness_thresh), score_threshold_(score_threshold), height_thresh_(height_thresh), @@ -100,7 +100,7 @@ std::shared_ptr ApolloLidarSegmentationPostProcessor std::vector feature(output_channels * output_width * output_height, 0); TVMArrayCopyToBytes( input[0].getArray(), feature.data(), - output_channels * output_width * output_height * datatype_bytes); + output_channels * output_width * output_height * output_datatype_bytes); cluster2d_->cluster( feature.data(), pc_ptr_, valid_idx, objectness_thresh_, true /*use all grids for clustering*/); auto object_array = cluster2d_->getObjects(score_threshold_, height_thresh_, min_pts_num_);