Skip to content
This repository has been archived by the owner on Jul 3, 2023. It is now read-only.

[pull] main from autowarefoundation:main #327

Merged
merged 8 commits into from
Mar 14, 2023
Prev Previous commit
Next Next commit
feat(lidar_centerpoint): add build only option for tensorrt engine (a…
…utowarefoundation#2677)

* feat(lidar_centerpoint): add build only option for tensorrt engine

Signed-off-by: yukke42 <yukke42@users.noreply.github.com>

* fix typo

Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com>

* style(pre-commit): autofix

* chore: add description

Signed-off-by: yukke42 <yukke42@users.noreply.github.com>

* chore: shutdown node

Signed-off-by: yukke42 <yukke42@users.noreply.github.com>

* feat: use tensorrt_commom

Signed-off-by: yukke42 <yukke42@users.noreply.github.com>

* fix: resolve the crash when shutting down the node

Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp>

* chore: fix typo

Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>

* style(pre-commit): autofix

---------

Signed-off-by: yukke42 <yukke42@users.noreply.github.com>
Signed-off-by: yukke42 <yusuke.muramatsu@tier4.jp>
Co-authored-by: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com>
Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
Co-authored-by: Kenzo Lobos Tsunekawa <kenzo.lobos@tier4.jp>
  • Loading branch information
4 people authored Mar 14, 2023
commit c1d28c9947207bd6f0a21ec12992e907603f1309
1 change: 1 addition & 0 deletions perception/lidar_centerpoint/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ We trained the models using <https://github.com/open-mmlab/mmdetection3d>.
| `nms_iou_target_class_names` | list[string] | - | target classes for IoU-based Non Maximum Suppression |
| `nms_iou_search_distance_2d` | double | - | If two objects are farther than the value, NMS isn't applied. |
| `nms_iou_threshold` | double | - | IoU threshold for the IoU-based Non Maximum Suppression |
| `build_only` | bool | `false` | shutdown the node after TensorRT engine file is built |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,6 @@ class CenterPointTRT
std::unique_ptr<PostProcessCUDA> post_proc_ptr_{nullptr};
cudaStream_t stream_{nullptr};

bool verbose_{false};
std::size_t class_size_{0};
CenterPointConfig config_;
std::size_t num_voxels_{0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,7 @@ class HeadTRT : public TensorRTWrapper
public:
using TensorRTWrapper::TensorRTWrapper;

HeadTRT(
const std::vector<std::size_t> & out_channel_sizes, const CenterPointConfig & config,
const bool verbose);
HeadTRT(const std::vector<std::size_t> & out_channel_sizes, const CenterPointConfig & config);

protected:
bool setProfile(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define LIDAR_CENTERPOINT__NETWORK__TENSORRT_WRAPPER_HPP_

#include <lidar_centerpoint/centerpoint_config.hpp>
#include <tensorrt_common/tensorrt_common.hpp>

#include <NvInfer.h>

Expand All @@ -25,53 +26,26 @@

namespace centerpoint
{
struct Deleter
{
template <typename T>
void operator()(T * obj) const
{
if (obj) {
delete obj;
}
}
};

template <typename T>
using unique_ptr = std::unique_ptr<T, Deleter>;

class Logger : public nvinfer1::ILogger
{
public:
explicit Logger(bool verbose) : verbose_(verbose) {}

void log(Severity severity, const char * msg) noexcept override
{
if (verbose_ || ((severity != Severity::kINFO) && (severity != Severity::kVERBOSE))) {
std::cout << msg << std::endl;
}
}

private:
bool verbose_{false};
};

class TensorRTWrapper
{
public:
explicit TensorRTWrapper(const CenterPointConfig & config, const bool verbose);
explicit TensorRTWrapper(const CenterPointConfig & config);

~TensorRTWrapper();

bool init(
const std::string & onnx_path, const std::string & engine_path, const std::string & precision);

unique_ptr<nvinfer1::IExecutionContext> context_ = nullptr;
tensorrt_common::TrtUniquePtr<nvinfer1::IExecutionContext> context_{nullptr};

protected:
virtual bool setProfile(
nvinfer1::IBuilder & builder, nvinfer1::INetworkDefinition & network,
nvinfer1::IBuilderConfig & config) = 0;

CenterPointConfig config_;
Logger logger_;
tensorrt_common::Logger logger_;

private:
bool parseONNX(
Expand All @@ -84,9 +58,9 @@ class TensorRTWrapper

bool createContext();

unique_ptr<nvinfer1::IRuntime> runtime_ = nullptr;
unique_ptr<nvinfer1::IHostMemory> plan_ = nullptr;
unique_ptr<nvinfer1::ICudaEngine> engine_ = nullptr;
tensorrt_common::TrtUniquePtr<nvinfer1::IRuntime> runtime_{nullptr};
tensorrt_common::TrtUniquePtr<nvinfer1::IHostMemory> plan_{nullptr};
tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine> engine_{nullptr};
};

} // namespace centerpoint
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<arg name="class_remapper_param_path" default="$(find-pkg-share lidar_centerpoint)/config/detection_class_remapper.param.yaml"/>
<arg name="score_threshold" default="0.35"/>
<arg name="has_twist" default="false"/>
<arg name="build_only" default="false" description="shutdown node after TensorRT engine file is built"/>

<node pkg="lidar_centerpoint" exec="lidar_centerpoint_node" name="lidar_centerpoint" output="screen">
<remap from="~/input/pointcloud" to="$(var input/pointcloud)"/>
Expand All @@ -21,6 +22,7 @@
<param name="encoder_engine_path" value="$(var model_path)/pts_voxel_encoder_$(var model_name).engine"/>
<param name="head_onnx_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).onnx"/>
<param name="head_engine_path" value="$(var model_path)/pts_backbone_neck_head_$(var model_name).engine"/>
<param name="build_only" value="$(var build_only)"/>
<param from="$(var model_param_path)"/>
<param from="$(var class_remapper_param_path)"/>
</node>
Expand Down
4 changes: 2 additions & 2 deletions perception/lidar_centerpoint/lib/centerpoint_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ CenterPointTRT::CenterPointTRT(
post_proc_ptr_ = std::make_unique<PostProcessCUDA>(config_);

// encoder
encoder_trt_ptr_ = std::make_unique<VoxelEncoderTRT>(config_, verbose_);
encoder_trt_ptr_ = std::make_unique<VoxelEncoderTRT>(config_);
encoder_trt_ptr_->init(
encoder_param.onnx_path(), encoder_param.engine_path(), encoder_param.trt_precision());
encoder_trt_ptr_->context_->setBindingDimensions(
Expand All @@ -47,7 +47,7 @@ CenterPointTRT::CenterPointTRT(
std::vector<std::size_t> out_channel_sizes = {
config_.class_size_, config_.head_out_offset_size_, config_.head_out_z_size_,
config_.head_out_dim_size_, config_.head_out_rot_size_, config_.head_out_vel_size_};
head_trt_ptr_ = std::make_unique<HeadTRT>(out_channel_sizes, config_, verbose_);
head_trt_ptr_ = std::make_unique<HeadTRT>(out_channel_sizes, config_);
head_trt_ptr_->init(head_param.onnx_path(), head_param.engine_path(), head_param.trt_precision());
head_trt_ptr_->context_->setBindingDimensions(
0, nvinfer1::Dims4(
Expand Down
5 changes: 2 additions & 3 deletions perception/lidar_centerpoint/lib/network/network_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,8 @@ bool VoxelEncoderTRT::setProfile(
}

HeadTRT::HeadTRT(
const std::vector<std::size_t> & out_channel_sizes, const CenterPointConfig & config,
const bool verbose)
: TensorRTWrapper(config, verbose), out_channel_sizes_(out_channel_sizes)
const std::vector<std::size_t> & out_channel_sizes, const CenterPointConfig & config)
: TensorRTWrapper(config), out_channel_sizes_(out_channel_sizes)
{
}

Expand Down
55 changes: 29 additions & 26 deletions perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,21 @@

namespace centerpoint
{
TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config, const bool verbose)
: config_(config), logger_(Logger(verbose))
TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config) : config_(config) {}

TensorRTWrapper::~TensorRTWrapper()
{
context_.reset();
runtime_.reset();
plan_.reset();
engine_.reset();
}

bool TensorRTWrapper::init(
const std::string & onnx_path, const std::string & engine_path, const std::string & precision)
{
runtime_ = unique_ptr<nvinfer1::IRuntime>(nvinfer1::createInferRuntime(logger_));
runtime_ =
tensorrt_common::TrtUniquePtr<nvinfer1::IRuntime>(nvinfer1::createInferRuntime(logger_));
if (!runtime_) {
std::cout << "Fail to create runtime" << std::endl;
return false;
Expand All @@ -55,7 +61,8 @@ bool TensorRTWrapper::createContext()
return false;
}

context_ = unique_ptr<nvinfer1::IExecutionContext>(engine_->createExecutionContext());
context_ =
tensorrt_common::TrtUniquePtr<nvinfer1::IExecutionContext>(engine_->createExecutionContext());
if (!context_) {
std::cout << "Fail to create context" << std::endl;
return false;
Expand All @@ -68,13 +75,15 @@ bool TensorRTWrapper::parseONNX(
const std::string & onnx_path, const std::string & engine_path, const std::string & precision,
const size_t workspace_size)
{
auto builder = unique_ptr<nvinfer1::IBuilder>(nvinfer1::createInferBuilder(logger_));
auto builder =
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilder>(nvinfer1::createInferBuilder(logger_));
if (!builder) {
std::cout << "Fail to create builder" << std::endl;
return false;
}

auto config = unique_ptr<nvinfer1::IBuilderConfig>(builder->createBuilderConfig());
auto config =
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilderConfig>(builder->createBuilderConfig());
if (!config) {
std::cout << "Fail to create config" << std::endl;
return false;
Expand All @@ -95,13 +104,15 @@ bool TensorRTWrapper::parseONNX(

const auto flag =
1U << static_cast<uint32_t>(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH);
auto network = unique_ptr<nvinfer1::INetworkDefinition>(builder->createNetworkV2(flag));
auto network =
tensorrt_common::TrtUniquePtr<nvinfer1::INetworkDefinition>(builder->createNetworkV2(flag));
if (!network) {
std::cout << "Fail to create network" << std::endl;
return false;
}

auto parser = unique_ptr<nvonnxparser::IParser>(nvonnxparser::createParser(*network, logger_));
auto parser = tensorrt_common::TrtUniquePtr<nvonnxparser::IParser>(
nvonnxparser::createParser(*network, logger_));
parser->parseFromFile(onnx_path.c_str(), static_cast<int>(nvinfer1::ILogger::Severity::kERROR));

if (!setProfile(*builder, *network, *config)) {
Expand All @@ -111,12 +122,13 @@ bool TensorRTWrapper::parseONNX(

std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..."
<< std::endl;
plan_ = unique_ptr<nvinfer1::IHostMemory>(builder->buildSerializedNetwork(*network, *config));
plan_ = tensorrt_common::TrtUniquePtr<nvinfer1::IHostMemory>(
builder->buildSerializedNetwork(*network, *config));
if (!plan_) {
std::cout << "Fail to create serialized network" << std::endl;
return false;
}
engine_ = unique_ptr<nvinfer1::ICudaEngine>(
engine_ = tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine>(
runtime_->deserializeCudaEngine(plan_->data(), plan_->size()));
if (!engine_) {
std::cout << "Fail to create engine" << std::endl;
Expand All @@ -136,22 +148,13 @@ bool TensorRTWrapper::saveEngine(const std::string & engine_path)

bool TensorRTWrapper::loadEngine(const std::string & engine_path)
{
std::ifstream file(engine_path, std::ios::in | std::ios::binary);
file.seekg(0, std::ifstream::end);
const size_t size = file.tellg();
file.seekg(0, std::ifstream::beg);

std::unique_ptr<char[]> buffer{new char[size]};
file.read(buffer.get(), size);
file.close();

if (!runtime_) {
std::cout << "Fail to load engine: Runtime isn't created" << std::endl;
return false;
}

std::cout << "Loading from " << engine_path << std::endl;
engine_ = unique_ptr<nvinfer1::ICudaEngine>(runtime_->deserializeCudaEngine(buffer.get(), size));
std::ifstream engine_file(engine_path);
std::stringstream engine_buffer;
engine_buffer << engine_file.rdbuf();
std::string engine_str = engine_buffer.str();
engine_ = tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine>(runtime_->deserializeCudaEngine(
reinterpret_cast<const void *>(engine_str.data()), engine_str.size()));
std::cout << "Loaded engine from " << engine_path << std::endl;
return true;
}

Expand Down
1 change: 1 addition & 0 deletions perception/lidar_centerpoint/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>python3-open3d</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>tensorrt_common</depend>
<depend>tf2_eigen</depend>
<depend>tf2_geometry_msgs</depend>
<depend>tier4_autoware_utils</depend>
Expand Down
5 changes: 5 additions & 0 deletions perception/lidar_centerpoint/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -121,6 +121,11 @@ LidarCenterPointNode::LidarCenterPointNode(const rclcpp::NodeOptions & node_opti
stop_watch_ptr_->tic("cyclic_time");
stop_watch_ptr_->tic("processing_time");
}

if (this->declare_parameter("build_only", false)) {
RCLCPP_INFO(this->get_logger(), "TensorRT engine is built and shutdown node.");
rclcpp::shutdown();
}
}

void LidarCenterPointNode::pointCloudCallback(
Expand Down