diff --git a/perception/lidar_centerpoint_tvm/.gitignore b/perception/lidar_centerpoint_tvm/.gitignore
index 8fce603003c1e..e69de29bb2d1d 100644
--- a/perception/lidar_centerpoint_tvm/.gitignore
+++ b/perception/lidar_centerpoint_tvm/.gitignore
@@ -1 +0,0 @@
-data/
diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp
new file mode 100644
index 0000000000000..8201dd25c1039
--- /dev/null
+++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/inference_engine_tvm_config.hpp
@@ -0,0 +1,60 @@
+// Copyright 2021 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.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "tvm_utility/pipeline.hpp"
+
+#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+
+namespace model_zoo
+{
+namespace perception
+{
+namespace lidar_obstacle_detection
+{
+namespace centerpoint_backbone
+{
+namespace onnx_centerpoint_backbone
+{
+
+static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
+ {3, 0, 0}, // modelzoo_version
+
+ "centerpoint_backbone", // network_name
+ "llvm", // network_backend
+
+ "./deploy_lib.so", // network_module_path
+ "./deploy_graph.json", // network_graph_path
+ "./deploy_param.params", // network_params_path
+
+ kDLCPU, // tvm_device_type
+ 0, // tvm_device_id
+
+ {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}}, // network_inputs
+
+ {{"heatmap", kDLFloat, 32, 1, {1, 3, 560, 560}},
+ {"reg", kDLFloat, 32, 1, {1, 2, 560, 560}},
+ {"height", kDLFloat, 32, 1, {1, 1, 560, 560}},
+ {"dim", kDLFloat, 32, 1, {1, 3, 560, 560}},
+ {"rot", kDLFloat, 32, 1, {1, 2, 560, 560}},
+ {"vel", kDLFloat, 32, 1, {1, 2, 560, 560}}} // network_outputs
+};
+
+} // namespace onnx_centerpoint_backbone
+} // namespace centerpoint_backbone
+} // namespace lidar_obstacle_detection
+} // namespace perception
+} // namespace model_zoo
+// NOLINTNEXTLINE
+#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_
diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp
new file mode 100644
index 0000000000000..2f6943e90bc83
--- /dev/null
+++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_backbone/preprocessing_inference_engine_tvm_config.hpp
@@ -0,0 +1,59 @@
+// Copyright 2021 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.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "tvm_utility/pipeline.hpp"
+
+#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+
+namespace model_zoo
+{
+namespace perception
+{
+namespace lidar_obstacle_detection
+{
+namespace centerpoint_backbone
+{
+namespace onnx_centerpoint_backbone
+{
+namespace preprocessing
+{
+
+static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
+ {3, 0, 0}, // modelzoo_version
+
+ "centerpoint_backbone", // network_name
+ "llvm", // network_backend
+
+ "./preprocess.so", // network_module_path
+ "./", // network_graph_path
+ "./", // network_params_path
+
+ kDLCPU, // tvm_device_type
+ 0, // tvm_device_id
+
+ {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}},
+ {"coords", kDLInt, 32, 1, {40000, 3}}}, // network_inputs
+
+ {{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}} // network_outputs
+};
+
+} // namespace preprocessing
+} // namespace onnx_centerpoint_backbone
+} // namespace centerpoint_backbone
+} // namespace lidar_obstacle_detection
+} // namespace perception
+} // namespace model_zoo
+// NOLINTNEXTLINE
+#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_
diff --git a/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp
new file mode 100644
index 0000000000000..521036b49a533
--- /dev/null
+++ b/perception/lidar_centerpoint_tvm/data/models/centerpoint_encoder/inference_engine_tvm_config.hpp
@@ -0,0 +1,55 @@
+// Copyright 2021 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.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "tvm_utility/pipeline.hpp"
+
+#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
+
+namespace model_zoo
+{
+namespace perception
+{
+namespace lidar_obstacle_detection
+{
+namespace centerpoint_encoder
+{
+namespace onnx_centerpoint_encoder
+{
+
+static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
+ {3, 0, 0}, // modelzoo_version
+
+ "centerpoint_encoder", // network_name
+ "llvm", // network_backend
+
+ "./deploy_lib.so", // network_module_path
+ "./deploy_graph.json", // network_graph_path
+ "./deploy_param.params", // network_params_path
+
+ kDLCPU, // tvm_device_type
+ 0, // tvm_device_id
+
+ {{"input_features", kDLFloat, 32, 1, {40000, 32, 9}}}, // network_inputs
+
+ {{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}} // network_outputs
+};
+
+} // namespace onnx_centerpoint_encoder
+} // namespace centerpoint_encoder
+} // namespace lidar_obstacle_detection
+} // namespace perception
+} // namespace model_zoo
+// NOLINTNEXTLINE
+#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_
diff --git a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp
index 168a249714bb4..865ca7d4253bf 100644
--- a/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp
+++ b/perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp
@@ -60,7 +60,7 @@ class LIDAR_CENTERPOINT_TVM_LOCAL TVMScatterIE : public tvm_utility::pipeline::I
public:
explicit TVMScatterIE(
tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name,
- const std::string & function_name);
+ const std::string & data_path, const std::string & function_name);
TVMArrayContainerVector schedule(const TVMArrayContainerVector & input);
void set_coords(TVMArrayContainer coords) { coords_ = coords; }
@@ -132,7 +132,8 @@ class LIDAR_CENTERPOINT_TVM_PUBLIC CenterPointTVM
/// \param[in] dense_param The densification parameter used to constructing vg_ptr.
/// \param[in] config The CenterPoint model configuration.
explicit CenterPointTVM(
- const DensificationParam & densification_param, const CenterPointConfig & config);
+ const DensificationParam & densification_param, const CenterPointConfig & config,
+ const std::string & data_path);
~CenterPointTVM();
diff --git a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml
index e838f01e347ce..2bd6e3aa15c21 100644
--- a/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml
+++ b/perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml
@@ -10,6 +10,7 @@
+
@@ -20,5 +21,6 @@
+
diff --git a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml
index e62808804ca07..c2e0801fbd11c 100644
--- a/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml
+++ b/perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml
@@ -12,6 +12,7 @@
+
@@ -22,6 +23,7 @@
+
diff --git a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp
index 7b31bdf3c8fd3..2e0f9ad28bfb6 100644
--- a/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp
+++ b/perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp
@@ -43,11 +43,10 @@ namespace lidar_centerpoint_tvm
TVMScatterIE::TVMScatterIE(
tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name,
- const std::string & function_name)
+ const std::string & data_path, const std::string & function_name)
: config_(config)
{
- std::string network_prefix =
- ament_index_cpp::get_package_share_directory(pkg_name) + "/models/" + config.network_name + "/";
+ std::string network_prefix = data_path + "/" + pkg_name + "/models/" + config.network_name + "/";
std::string network_module_path = network_prefix + config.network_module_path;
std::ifstream module(network_module_path);
@@ -159,14 +158,15 @@ std::vector BackboneNeckHeadPostProcessor::schedule(const TVMArrayContain
}
CenterPointTVM::CenterPointTVM(
- const DensificationParam & densification_param, const CenterPointConfig & config)
+ const DensificationParam & densification_param, const CenterPointConfig & config,
+ const std::string & data_path)
: config_ve(config_en),
config_bnh(config_bk),
VE_PreP(std::make_shared(config_en, config)),
- VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm")),
- BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm")),
+ VE_IE(std::make_shared(config_en, "lidar_centerpoint_tvm", data_path)),
+ BNH_IE(std::make_shared(config_bk, "lidar_centerpoint_tvm", data_path)),
BNH_PostP(std::make_shared(config_bk, config)),
- scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", "scatter")),
+ scatter_ie(std::make_shared(config_scatter, "lidar_centerpoint_tvm", data_path, "scatter")),
TSP_pipeline(std::make_shared(VE_PreP, VE_IE, scatter_ie, BNH_IE, BNH_PostP)),
config_(config)
{
diff --git a/perception/lidar_centerpoint_tvm/src/node.cpp b/perception/lidar_centerpoint_tvm/src/node.cpp
index e63cb7e19ba8e..0054211a15f9f 100644
--- a/perception/lidar_centerpoint_tvm/src/node.cpp
+++ b/perception/lidar_centerpoint_tvm/src/node.cpp
@@ -65,6 +65,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod
static_cast(this->declare_parameter("downsample_factor"));
const std::size_t encoder_in_feature_size =
static_cast(this->declare_parameter("encoder_in_feature_size"));
+ const auto data_path = this->declare_parameter("data_path");
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
@@ -83,7 +84,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_threshold);
- detector_ptr_ = std::make_unique(densification_param, config);
+ detector_ptr_ = std::make_unique(densification_param, config, data_path);
pointcloud_sub_ = this->create_subscription(
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),
diff --git a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp
index 8b810c5a7d759..a08850a7572f2 100644
--- a/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp
+++ b/perception/lidar_centerpoint_tvm/src/single_inference_node.cpp
@@ -70,7 +70,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
static_cast(this->declare_parameter("encoder_in_feature_size"));
const auto pcd_path = this->declare_parameter("pcd_path");
const auto detections_path = this->declare_parameter("detections_path");
-
+ const auto data_path = this->declare_parameter("data_path");
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
@@ -88,7 +88,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
yaw_norm_threshold);
- detector_ptr_ = std::make_unique(densification_param, config);
+ detector_ptr_ = std::make_unique(densification_param, config, data_path);
detect(pcd_path, detections_path);
exit(0);