Skip to content

Commit

Permalink
Merge branch 'main' into refactor/start_planner_post_process
Browse files Browse the repository at this point in the history
Signed-off-by: kyoichi-sugahara <[email protected]>
  • Loading branch information
kyoichi-sugahara committed Nov 10, 2023
2 parents 5fc69ae + 208ecf2 commit aad49e9
Show file tree
Hide file tree
Showing 10 changed files with 192 additions and 13 deletions.
1 change: 0 additions & 1 deletion perception/lidar_centerpoint_tvm/.gitignore
Original file line number Diff line number Diff line change
@@ -1 +0,0 @@
data/
Original file line number Diff line number Diff line change
@@ -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_
Original file line number Diff line number Diff line change
@@ -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_
Original file line number Diff line number Diff line change
@@ -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_
Original file line number Diff line number Diff line change
Expand Up @@ -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; }

Expand Down Expand Up @@ -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();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,7 @@
<arg name="score_threshold" default="0.35"/>
<arg name="yaw_norm_threshold" default="0.0"/>
<arg name="has_twist" default="false"/>
<arg name="data_path" default="$(env HOME)/autoware_data"/>

<node pkg="lidar_centerpoint_tvm" exec="lidar_centerpoint_tvm_node" name="lidar_centerpoint_tvm" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
Expand All @@ -20,5 +21,6 @@
<param name="densification_num_past_frames" value="1"/>
<param name="has_twist" value="$(var has_twist)"/>
<param from="$(var model_param_path)"/>
<param name="data_path" value="$(var data_path)"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
<arg name="has_twist" default="false"/>
<arg name="pcd_path" default="test.pcd"/>
<arg name="detections_path" default="test.ply"/>
<arg name="data_path" default="$(env HOME)/autoware_data"/>

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

<param name="pcd_path" value="$(var pcd_path)"/>
<param name="detections_path" value="$(var detections_path)"/>
<param name="data_path" value="$(var data_path)"/>
</node>

<node pkg="lidar_centerpoint_tvm" exec="lidar_centerpoint_visualizer.py" name="lidar_centerpoint_visualizer" output="screen">
Expand Down
14 changes: 7 additions & 7 deletions perception/lidar_centerpoint_tvm/lib/centerpoint_tvm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -159,14 +158,15 @@ std::vector<Box3D> 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<VE_PrePT>(config_en, config)),
VE_IE(std::make_shared<IET>(config_en, "lidar_centerpoint_tvm")),
BNH_IE(std::make_shared<IET>(config_bk, "lidar_centerpoint_tvm")),
VE_IE(std::make_shared<IET>(config_en, "lidar_centerpoint_tvm", data_path)),
BNH_IE(std::make_shared<IET>(config_bk, "lidar_centerpoint_tvm", data_path)),
BNH_PostP(std::make_shared<BNH_PostPT>(config_bk, config)),
scatter_ie(std::make_shared<TSE>(config_scatter, "lidar_centerpoint_tvm", "scatter")),
scatter_ie(std::make_shared<TSE>(config_scatter, "lidar_centerpoint_tvm", data_path, "scatter")),
TSP_pipeline(std::make_shared<TSP>(VE_PreP, VE_IE, scatter_ie, BNH_IE, BNH_PostP)),
config_(config)
{
Expand Down
3 changes: 2 additions & 1 deletion perception/lidar_centerpoint_tvm/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ LidarCenterPointTVMNode::LidarCenterPointTVMNode(const rclcpp::NodeOptions & nod
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("downsample_factor"));
const std::size_t encoder_in_feature_size =
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("encoder_in_feature_size"));
const auto data_path = this->declare_parameter<std::string>("data_path");

DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);
Expand All @@ -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<CenterPointTVM>(densification_param, config);
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config, data_path);

pointcloud_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"~/input/pointcloud", rclcpp::SensorDataQoS{}.keep_last(1),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ SingleInferenceLidarCenterPointNode::SingleInferenceLidarCenterPointNode(
static_cast<std::size_t>(this->declare_parameter<std::int64_t>("encoder_in_feature_size"));
const auto pcd_path = this->declare_parameter<std::string>("pcd_path");
const auto detections_path = this->declare_parameter<std::string>("detections_path");

const auto data_path = this->declare_parameter<std::string>("data_path");
DensificationParam densification_param(
densification_world_frame_id, densification_num_past_frames);

Expand All @@ -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<CenterPointTVM>(densification_param, config);
detector_ptr_ = std::make_unique<CenterPointTVM>(densification_param, config, data_path);

detect(pcd_path, detections_path);
exit(0);
Expand Down

0 comments on commit aad49e9

Please sign in to comment.