Skip to content

Commit

Permalink
feat(ModelZoo): model descriptors versioning (autowarefoundation#2158)
Browse files Browse the repository at this point in the history
Introduce a version field to the interface.

Make use of it in the lidar_apollo_segmentation_tvm packages and the
yolo_v2 example of tvm_utility.

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

Signed-off-by: Ambroise Vincent <ambroise.vincent@arm.com>
Co-authored-by: Xinyu Wang <93699235+angry-crab@users.noreply.github.com>
Signed-off-by: yoshiri <yoshiyoshidetteiu@gmail.com>
  • Loading branch information
2 people authored and YoshiRi committed Jan 11, 2023
1 parent 1a536e1 commit 9721aff
Show file tree
Hide file tree
Showing 9 changed files with 93 additions and 4 deletions.
8 changes: 8 additions & 0 deletions common/tvm_utility/design/tvm-utility-design.md
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,14 @@ int main() {
}
```

#### Version checking

The `InferenceEngineTVM::version_check` function can be used to check the version of the neural network in use against the range of earliest to latest supported versions.

The `InferenceEngineTVM` class holds the latest supported version, which needs to be updated when the targeted version changes; after having tested the effect of the version change on the packages dependent on this one.

The earliest supported version depends on each package making use of the inference, and so should be defined (and maintained) in those packages.

#### Models

Dependent packages are expected to use the `get_neural_network` cmake function from this package in order to get the compiled TVM models.
Expand Down
44 changes: 42 additions & 2 deletions common/tvm_utility/include/tvm_utility/pipeline.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,11 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef TVM_UTILITY__PIPELINE_HPP_
#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 @@ -26,11 +30,21 @@
#include <utility>
#include <vector>

#ifndef TVM_UTILITY__PIPELINE_HPP_
#define TVM_UTILITY__PIPELINE_HPP_
using autoware::common::types::char8_t;

namespace tvm_utility
{

/**
* @brief Possible version status for a neural network.
*/
enum class Version {
OK,
Unknown,
Untested,
Unsupported,
};

namespace pipeline
{

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

Expand Down Expand Up @@ -294,12 +309,37 @@ class InferenceEngineTVM : public InferenceEngine
return output_;
}

/**
* @brief Get version information from the config structure and check if there is a mismatch
* between the supported version(s) and the actual version.
* @param[in] version_from Earliest supported model version.
* @return The version status.
*/
Version version_check(const std::array<char8_t, 3> & version_from) const
{
auto x{config_.modelzoo_version[0]};
auto y{config_.modelzoo_version[1]};
Version ret{Version::OK};

if (x == 0) {
ret = Version::Unknown;
} else if (x > version_up_to[0] || (x == version_up_to[0] && y > version_up_to[1])) {
ret = Version::Untested;
} else if (x < version_from[0] || (x == version_from[0] && y < version_from[1])) {
ret = Version::Unsupported;
}

return ret;
}

private:
InferenceEngineTVMConfig config_;
TVMArrayContainerVector output_;
tvm::runtime::PackedFunc set_input;
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};
};

} // namespace pipeline
Expand Down
1 change: 1 addition & 0 deletions common/tvm_utility/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
<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
5 changes: 4 additions & 1 deletion common/tvm_utility/test/yolo_v2_tiny/main.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
// Copyright 2021 Arm Limited and Contributors.
// Copyright 2021-2022 Arm Limited and Contributors.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
Expand Down Expand Up @@ -245,6 +245,9 @@ TEST(PipelineExamples, SimplePipeline)

tvm_utility::pipeline::Pipeline<PrePT, IET, PostPT> pipeline(PreP, IE, PostP);

auto version_status = IE.version_check({2, 0, 0});
EXPECT_NE(version_status, tvm_utility::Version::Unsupported);

// Push data input the pipeline and get the output
auto output = pipeline.schedule(IMAGE_FILENAME);

Expand Down
2 changes: 1 addition & 1 deletion common/tvm_utility/tvm_utility-extras.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@

# Get user-provided variables
set(DOWNLOAD_ARTIFACTS OFF CACHE BOOL "enable artifacts download")
set(MODELZOO_VERSION "1.3.0-20220902" CACHE STRING "targeted ModelZoo version")
set(MODELZOO_VERSION "2.1.0-20221102" CACHE STRING "targeted ModelZoo version")

#
# Download the selected neural network if it is not already present on disk.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -158,6 +158,14 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation
std::shared_ptr<const DetectedObjectsWithFeature> detectDynamicObjects(
const sensor_msgs::msg::PointCloud2 & input);

/// \brief Get the name of the neural network used.
/// \return The name.
const std::string & network_name() const;

/// \brief Check the model's version against supported versions.
/// \return The version status.
tvm_utility::Version version_check() const;

private:
const int32_t range_;
const float32_t score_threshold_;
Expand All @@ -166,6 +174,8 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation
const int32_t min_pts_num_;
const float32_t height_thresh_;
const pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud_ptr_;
// Earliest supported model version.
const std::array<char8_t, 3> model_version_from{2, 0, 0};

// Pipeline
using PrePT = ApolloLidarSegmentationPreProcessor;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <tvm_utility/pipeline.hpp>

#include <memory>
#include <string>
#include <vector>

using autoware::common::types::bool8_t;
Expand Down Expand Up @@ -192,6 +193,13 @@ std::shared_ptr<const DetectedObjectsWithFeature> ApolloLidarSegmentation::detec

return output;
}

const std::string & ApolloLidarSegmentation::network_name() const { return config.network_name; }

tvm_utility::Version ApolloLidarSegmentation::version_check() const
{
return IE->version_check(model_version_from);
}
} // namespace lidar_apollo_segmentation_tvm
} // namespace perception
} // namespace autoware
3 changes: 3 additions & 0 deletions perception/lidar_apollo_segmentation_tvm/test/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ void test_segmentation(bool use_intensity_feature, bool use_constant_feature, bo
range, score_threshold, use_intensity_feature, use_constant_feature, z_offset, min_height,
max_height, objectness_thresh, min_pts_num, height_thresh);

auto version_status = segmentation.version_check();
EXPECT_NE(version_status, tvm_utility::Version::Unsupported);

std::random_device rd;
std::mt19937 gen(42);
std::uniform_real_distribution<float32_t> dis(-50.0, 50.0);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include <common/types.hpp>
#include <lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp>
#include <lidar_apollo_segmentation_tvm_nodes/lidar_apollo_segmentation_tvm_node.hpp>
#include <rclcpp/logging.hpp>
#include <rclcpp_components/register_node_macro.hpp>

#include <memory>
Expand Down Expand Up @@ -50,6 +51,21 @@ ApolloLidarSegmentationNode::ApolloLidarSegmentationNode(const rclcpp::NodeOptio
declare_parameter("min_pts_num", rclcpp::ParameterValue{3}).get<int32_t>(),
declare_parameter("height_thresh", rclcpp::ParameterValue{0.5}).get<float32_t>())}
{
// Log unexpected versions of the neural network.
auto version_status = m_detector_ptr->version_check();
if (version_status != tvm_utility::Version::OK) {
auto network_name = m_detector_ptr->network_name();
if (version_status == tvm_utility::Version::Unknown) {
RCLCPP_INFO(
get_logger(), "The '%s' network doesn't provide a version number.", network_name.c_str());
} else if (version_status == tvm_utility::Version::Untested) {
RCLCPP_WARN(
get_logger(), "The version of the '%s' network is untested.", network_name.c_str());
} else if (version_status == tvm_utility::Version::Unsupported) {
RCLCPP_ERROR(
get_logger(), "The version of the '%s' network is unsupported.", network_name.c_str());
}
}
}

void ApolloLidarSegmentationNode::pointCloudCallback(
Expand Down

0 comments on commit 9721aff

Please sign in to comment.