Skip to content

Commit

Permalink
fix(lidar_apollo_segmentation_tvm, tvm_utility): fixed output dim and…
Browse files Browse the repository at this point in the history
… pipeline (#2185)

Signed-off-by: Xinyu Wang <xinyu.wang@tier4.jp>
  • Loading branch information
angry-crab authored Nov 15, 2022
1 parent e8fcf6c commit 7e37a6c
Show file tree
Hide file tree
Showing 6 changed files with 33 additions and 37 deletions.
2 changes: 1 addition & 1 deletion common/tvm_utility/include/tvm_utility/pipeline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -282,7 +282,7 @@ 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,
kDLCPU, 0));
config.tvm_device_type, config.tvm_device_id));
}
}

Expand Down
43 changes: 22 additions & 21 deletions common/tvm_utility/tvm_utility-extras.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -42,11 +42,9 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY)
"${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp"
COPYONLY
)
install(
DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}"
DESTINATION "share/${PROJECT_NAME}/models/"
USE_SOURCE_PERMISSIONS
)
set(DOWNLOAD_DIR "")
set(SOURCE_DIR "${DATA_PATH}/user/${MODEL_NAME}")
set(INSTALL_DIRECTORY "${DATA_PATH}/user/${MODEL_NAME}")
else()
set(ARCHIVE_NAME "${MODEL_NAME}-${CMAKE_SYSTEM_PROCESSOR}-${MODEL_BACKEND}-${MODELZOO_VERSION}.tar.gz")

Expand All @@ -61,24 +59,27 @@ function(get_neural_network MODEL_NAME MODEL_BACKEND DEPENDENCY)
set(${DEPENDENCY} "" PARENT_SCOPE)
return()
endif()

include(ExternalProject)
externalproject_add(${EXTERNALPROJECT_NAME}
DOWNLOAD_DIR "${DATA_PATH}/downloads"
SOURCE_DIR "${DATA_PATH}/models/${MODEL_NAME}"
URL ${URL}
CONFIGURE_COMMAND ""
BUILD_COMMAND ""
BUILD_BYPRODUCTS "${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp"
INSTALL_COMMAND ""
)
install(
DIRECTORY "${DATA_PATH}/models/${MODEL_NAME}"
DESTINATION "share/${PROJECT_NAME}/models/"
USE_SOURCE_PERMISSIONS
)
set(DOWNLOAD_DIR "${DATA_PATH}/downloads")
set(SOURCE_DIR "${DATA_PATH}/models/${MODEL_NAME}")
set(INSTALL_DIRECTORY "${DATA_PATH}/models/${MODEL_NAME}")
endif()

include(ExternalProject)
externalproject_add(${EXTERNALPROJECT_NAME}
DOWNLOAD_DIR ${DOWNLOAD_DIR}
SOURCE_DIR ${SOURCE_DIR}
URL ${URL}
CONFIGURE_COMMAND ""
BUILD_COMMAND ""
BUILD_BYPRODUCTS "${DATA_PATH}/models/${MODEL_NAME}/inference_engine_tvm_config.hpp"
INSTALL_COMMAND ""
)
install(
DIRECTORY ${INSTALL_DIRECTORY}
DESTINATION "share/${PROJECT_NAME}/models/"
USE_SOURCE_PERMISSIONS
)

set(${DEPENDENCY} ${EXTERNALPROJECT_NAME} PARENT_SCOPE)

endfunction()
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,6 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_LOCAL ApolloLidarSegmentationPostProcessor
const float32_t score_threshold_;
const float32_t height_thresh_;
const int32_t min_pts_num_;
const std::shared_ptr<float32_t> inferred_data;
const pcl::PointCloud<pcl::PointXYZI>::ConstPtr pc_ptr_;
const std::shared_ptr<Cluster2D> cluster2d_;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,9 +86,6 @@ ApolloLidarSegmentationPostProcessor::ApolloLidarSegmentationPostProcessor(
score_threshold_(score_threshold),
height_thresh_(height_thresh),
min_pts_num_(min_pts_num),
inferred_data(std::shared_ptr<float32_t>(
new float32_t[output_channels * output_width * output_height],
std::default_delete<float32_t[]>())),
pc_ptr_(pc_ptr),
cluster2d_(std::make_shared<Cluster2D>(output_width, output_height, range))
{
Expand All @@ -100,9 +97,12 @@ std::shared_ptr<DetectedObjectsWithFeature> ApolloLidarSegmentationPostProcessor
pcl::PointIndices valid_idx;
valid_idx.indices.resize(pc_ptr_->size());
std::iota(valid_idx.indices.begin(), valid_idx.indices.end(), 0);
std::vector<float32_t> feature(output_channels * output_width * output_height, 0);
TVMArrayCopyToBytes(
input[0].getArray(), feature.data(),
output_channels * output_width * output_height * datatype_bytes);
cluster2d_->cluster(
static_cast<float32_t *>(input[0].getArray()->data), pc_ptr_, valid_idx, objectness_thresh_,
true /*use all grids for clustering*/);
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_);

return object_array;
Expand Down
8 changes: 2 additions & 6 deletions perception/lidar_apollo_segmentation_tvm/test/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,15 +85,11 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo
EXPECT_EQ(expect_throw, has_thrown);
}

// Test configuration matching the default-provided network.
TEST(lidar_apollo_segmentation_tvm, sanity) { test_segmentation(true, false, false); }

// Test that configuring ApolloLidarSegmentation with too few channels results in an error.
TEST(lidar_apollo_segmentation_tvm, runtime_error) { test_segmentation(false, false, true); }

// Other test configurations to increase code coverage.
TEST(lidar_apollo_segmentation_tvm, others)
{
test_segmentation(false, true, false);
test_segmentation(true, true, false);
test_segmentation(false, false, false);
test_segmentation(true, false, false);
}
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
/**:
ros__parameters:
# The range of the 2D grid with respect to the origin.
range: 70
range: 90
# The detection confidence score threshold for filtering out the candidate
# clusters in the post-processing step.
score_threshold: 0.8
score_threshold: 0.1
# Enable input channel intensity feature.
use_intensity_feature: true
use_intensity_feature: false
# Enable input channel constant feature.
use_constant_feature: false
# Vertical translation of the pointcloud before inference.
Expand Down

0 comments on commit 7e37a6c

Please sign in to comment.