Skip to content

Commit 208ecf2

Browse files
authored
build(lidar_centerpoint_tvm): remove artifacts download (#5367)
Signed-off-by: Alexey Panferov <lexavtanke@gmail.com>
1 parent 08b905a commit 208ecf2

10 files changed

+192
-13
lines changed
Original file line numberDiff line numberDiff line change
@@ -1 +0,0 @@
1-
data/
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,60 @@
1+
// Copyright 2021 Arm Limited and Contributors.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "tvm_utility/pipeline.hpp"
16+
17+
#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
18+
#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
19+
20+
namespace model_zoo
21+
{
22+
namespace perception
23+
{
24+
namespace lidar_obstacle_detection
25+
{
26+
namespace centerpoint_backbone
27+
{
28+
namespace onnx_centerpoint_backbone
29+
{
30+
31+
static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
32+
{3, 0, 0}, // modelzoo_version
33+
34+
"centerpoint_backbone", // network_name
35+
"llvm", // network_backend
36+
37+
"./deploy_lib.so", // network_module_path
38+
"./deploy_graph.json", // network_graph_path
39+
"./deploy_param.params", // network_params_path
40+
41+
kDLCPU, // tvm_device_type
42+
0, // tvm_device_id
43+
44+
{{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}}, // network_inputs
45+
46+
{{"heatmap", kDLFloat, 32, 1, {1, 3, 560, 560}},
47+
{"reg", kDLFloat, 32, 1, {1, 2, 560, 560}},
48+
{"height", kDLFloat, 32, 1, {1, 1, 560, 560}},
49+
{"dim", kDLFloat, 32, 1, {1, 3, 560, 560}},
50+
{"rot", kDLFloat, 32, 1, {1, 2, 560, 560}},
51+
{"vel", kDLFloat, 32, 1, {1, 2, 560, 560}}} // network_outputs
52+
};
53+
54+
} // namespace onnx_centerpoint_backbone
55+
} // namespace centerpoint_backbone
56+
} // namespace lidar_obstacle_detection
57+
} // namespace perception
58+
} // namespace model_zoo
59+
// NOLINTNEXTLINE
60+
#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__INFERENCE_ENGINE_TVM_CONFIG_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
1+
// Copyright 2021 Arm Limited and Contributors.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "tvm_utility/pipeline.hpp"
16+
17+
#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
18+
#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
19+
20+
namespace model_zoo
21+
{
22+
namespace perception
23+
{
24+
namespace lidar_obstacle_detection
25+
{
26+
namespace centerpoint_backbone
27+
{
28+
namespace onnx_centerpoint_backbone
29+
{
30+
namespace preprocessing
31+
{
32+
33+
static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
34+
{3, 0, 0}, // modelzoo_version
35+
36+
"centerpoint_backbone", // network_name
37+
"llvm", // network_backend
38+
39+
"./preprocess.so", // network_module_path
40+
"./", // network_graph_path
41+
"./", // network_params_path
42+
43+
kDLCPU, // tvm_device_type
44+
0, // tvm_device_id
45+
46+
{{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}},
47+
{"coords", kDLInt, 32, 1, {40000, 3}}}, // network_inputs
48+
49+
{{"spatial_features", kDLFloat, 32, 1, {1, 32, 560, 560}}} // network_outputs
50+
};
51+
52+
} // namespace preprocessing
53+
} // namespace onnx_centerpoint_backbone
54+
} // namespace centerpoint_backbone
55+
} // namespace lidar_obstacle_detection
56+
} // namespace perception
57+
} // namespace model_zoo
58+
// NOLINTNEXTLINE
59+
#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_BACKBONE__PREPROCESSING_INFERENCE_ENGINE_TVM_CONFIG_HPP_
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
// Copyright 2021 Arm Limited and Contributors.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "tvm_utility/pipeline.hpp"
16+
17+
#ifndef PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
18+
#define PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_ // NOLINT
19+
20+
namespace model_zoo
21+
{
22+
namespace perception
23+
{
24+
namespace lidar_obstacle_detection
25+
{
26+
namespace centerpoint_encoder
27+
{
28+
namespace onnx_centerpoint_encoder
29+
{
30+
31+
static const tvm_utility::pipeline::InferenceEngineTVMConfig config{
32+
{3, 0, 0}, // modelzoo_version
33+
34+
"centerpoint_encoder", // network_name
35+
"llvm", // network_backend
36+
37+
"./deploy_lib.so", // network_module_path
38+
"./deploy_graph.json", // network_graph_path
39+
"./deploy_param.params", // network_params_path
40+
41+
kDLCPU, // tvm_device_type
42+
0, // tvm_device_id
43+
44+
{{"input_features", kDLFloat, 32, 1, {40000, 32, 9}}}, // network_inputs
45+
46+
{{"pillar_features", kDLFloat, 32, 1, {40000, 1, 32}}} // network_outputs
47+
};
48+
49+
} // namespace onnx_centerpoint_encoder
50+
} // namespace centerpoint_encoder
51+
} // namespace lidar_obstacle_detection
52+
} // namespace perception
53+
} // namespace model_zoo
54+
// NOLINTNEXTLINE
55+
#endif // PERCEPTION__LIDAR_CENTERPOINT_TVM__DATA__MODELS__CENTERPOINT_ENCODER__INFERENCE_ENGINE_TVM_CONFIG_HPP_

perception/lidar_centerpoint_tvm/include/lidar_centerpoint_tvm/centerpoint_tvm.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class LIDAR_CENTERPOINT_TVM_LOCAL TVMScatterIE : public tvm_utility::pipeline::I
6060
public:
6161
explicit TVMScatterIE(
6262
tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name,
63-
const std::string & function_name);
63+
const std::string & data_path, const std::string & function_name);
6464
TVMArrayContainerVector schedule(const TVMArrayContainerVector & input);
6565
void set_coords(TVMArrayContainer coords) { coords_ = coords; }
6666

@@ -132,7 +132,8 @@ class LIDAR_CENTERPOINT_TVM_PUBLIC CenterPointTVM
132132
/// \param[in] dense_param The densification parameter used to constructing vg_ptr.
133133
/// \param[in] config The CenterPoint model configuration.
134134
explicit CenterPointTVM(
135-
const DensificationParam & densification_param, const CenterPointConfig & config);
135+
const DensificationParam & densification_param, const CenterPointConfig & config,
136+
const std::string & data_path);
136137

137138
~CenterPointTVM();
138139

perception/lidar_centerpoint_tvm/launch/lidar_centerpoint_tvm.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -10,6 +10,7 @@
1010
<arg name="score_threshold" default="0.35"/>
1111
<arg name="yaw_norm_threshold" default="0.0"/>
1212
<arg name="has_twist" default="false"/>
13+
<arg name="data_path" default="$(env HOME)/autoware_data"/>
1314

1415
<node pkg="lidar_centerpoint_tvm" exec="lidar_centerpoint_tvm_node" name="lidar_centerpoint_tvm" output="screen">
1516
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
@@ -20,5 +21,6 @@
2021
<param name="densification_num_past_frames" value="1"/>
2122
<param name="has_twist" value="$(var has_twist)"/>
2223
<param from="$(var model_param_path)"/>
24+
<param name="data_path" value="$(var data_path)"/>
2325
</node>
2426
</launch>

perception/lidar_centerpoint_tvm/launch/single_inference_lidar_centerpoint_tvm.launch.xml

+2
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@
1212
<arg name="has_twist" default="false"/>
1313
<arg name="pcd_path" default="test.pcd"/>
1414
<arg name="detections_path" default="test.ply"/>
15+
<arg name="data_path" default="$(env HOME)/autoware_data"/>
1516

1617
<node pkg="lidar_centerpoint_tvm" exec="single_inference_lidar_centerpoint_tvm_node" name="lidar_centerpoint_tvm" output="screen">
1718
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
@@ -22,6 +23,7 @@
2223

2324
<param name="pcd_path" value="$(var pcd_path)"/>
2425
<param name="detections_path" value="$(var detections_path)"/>
26+
<param name="data_path" value="$(var data_path)"/>
2527
</node>
2628

2729
<node pkg="lidar_centerpoint_tvm" exec="lidar_centerpoint_visualizer.py" name="lidar_centerpoint_visualizer" output="screen">

perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp

+7-7
Original file line numberDiff line numberDiff line change
@@ -43,11 +43,10 @@ namespace lidar_centerpoint_tvm
4343

4444
TVMScatterIE::TVMScatterIE(
4545
tvm_utility::pipeline::InferenceEngineTVMConfig config, const std::string & pkg_name,
46-
const std::string & function_name)
46+
const std::string & data_path, const std::string & function_name)
4747
: config_(config)
4848
{
49-
std::string network_prefix =
50-
ament_index_cpp::get_package_share_directory(pkg_name) + "/models/" + config.network_name + "/";
49+
std::string network_prefix = data_path + "/" + pkg_name + "/models/" + config.network_name + "/";
5150
std::string network_module_path = network_prefix + config.network_module_path;
5251

5352
std::ifstream module(network_module_path);
@@ -159,14 +158,15 @@ std::vector<Box3D> BackboneNeckHeadPostProcessor::schedule(const TVMArrayContain
159158
}
160159

161160
CenterPointTVM::CenterPointTVM(
162-
const DensificationParam & densification_param, const CenterPointConfig & config)
161+
const DensificationParam & densification_param, const CenterPointConfig & config,
162+
const std::string & data_path)
163163
: config_ve(config_en),
164164
config_bnh(config_bk),
165165
VE_PreP(std::make_shared<VE_PrePT>(config_en, config)),
166-
VE_IE(std::make_shared<IET>(config_en, "lidar_centerpoint_tvm")),
167-
BNH_IE(std::make_shared<IET>(config_bk, "lidar_centerpoint_tvm")),
166+
VE_IE(std::make_shared<IET>(config_en, "lidar_centerpoint_tvm", data_path)),
167+
BNH_IE(std::make_shared<IET>(config_bk, "lidar_centerpoint_tvm", data_path)),
168168
BNH_PostP(std::make_shared<BNH_PostPT>(config_bk, config)),
169-
scatter_ie(std::make_shared<TSE>(config_scatter, "lidar_centerpoint_tvm", "scatter")),
169+
scatter_ie(std::make_shared<TSE>(config_scatter, "lidar_centerpoint_tvm", data_path, "scatter")),
170170
TSP_pipeline(std::make_shared<TSP>(VE_PreP, VE_IE, scatter_ie, BNH_IE, BNH_PostP)),
171171
config_(config)
172172
{

perception/lidar_centerpoint_tvm/src/node.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -65,6 +65,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod
6565
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("downsample_factor"));
6666
const std::size_t encoder_in_feature_size =
6767
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("encoder_in_feature_size"));
68+
const auto data_path = this->declare_parameter<std::string>("data_path");
6869

6970
DensificationParam densification_param(
7071
densification_world_frame_id, densification_num_past_frames);
@@ -83,7 +84,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod
8384
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
8485
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
8586
yaw_norm_threshold);
86-
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config);
87+
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config, data_path);
8788

8889
pointcloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
8990
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),

perception/lidar_centerpoint_tvm/src/single_inference_node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
7070
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("encoder_in_feature_size"));
7171
const auto pcd_path = this->declare_parameter<std::string>("pcd_path");
7272
const auto detections_path = this->declare_parameter<std::string>("detections_path");
73-
73+
const auto data_path = this->declare_parameter<std::string>("data_path");
7474
DensificationParam densification_param(
7575
densification_world_frame_id, densification_num_past_frames);
7676

@@ -88,7 +88,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
8888
class_names_.size(), point_feature_size, max_voxel_size, point_cloud_range, voxel_size,
8989
downsample_factor, encoder_in_feature_size, score_threshold, circle_nms_dist_threshold,
9090
yaw_norm_threshold);
91-
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config);
91+
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config, data_path);
9292

9393
detect(pcd_path, detections_path);
9494
exit(0);

0 commit comments

Comments
 (0)