From 5ee7539688dd3232cf482fe1942eab0cf182a8d1 Mon Sep 17 00:00:00 2001 From: Daisuke Nishimatsu <42202095+wep21@users.noreply.github.com> Date: Wed, 10 Aug 2022 20:46:52 +0900 Subject: [PATCH] fix: update trt api (#1472) * fix: update trt api Signed-off-by: Daisuke Nishimatsu * compatible build with tensorrt 8.2 Signed-off-by: Daisuke Nishimatsu * revert changes for caffe parser Signed-off-by: Daisuke Nishimatsu --- .../lidar_apollo_instance_segmentation/CMakeLists.txt | 5 +++++ .../lidar_apollo_instance_segmentation/src/detector.cpp | 6 ++++-- .../lidar_centerpoint/lib/network/tensorrt_wrapper.cpp | 4 ++++ perception/tensorrt_yolo/lib/src/trt_yolo.cpp | 4 ++++ perception/traffic_light_classifier/utils/trt_common.cpp | 8 +++++--- perception/traffic_light_classifier/utils/trt_common.hpp | 1 - .../traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp | 4 ++++ 7 files changed, 26 insertions(+), 6 deletions(-) diff --git a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt index 8fff790a64790..53b0d6ba6a352 100644 --- a/perception/lidar_apollo_instance_segmentation/CMakeLists.txt +++ b/perception/lidar_apollo_instance_segmentation/CMakeLists.txt @@ -134,6 +134,11 @@ if(TRT_AVAIL AND CUDA_AVAIL AND CUDNN_AVAIL) ${PCL_LIBRARIES} ) + target_compile_options(tensorrt_apollo_cnn_lib + PUBLIC + -Wno-deprecated-declarations + ) + ament_auto_add_library(lidar_apollo_instance_segmentation SHARED src/node.cpp src/detector.cpp diff --git a/perception/lidar_apollo_instance_segmentation/src/detector.cpp b/perception/lidar_apollo_instance_segmentation/src/detector.cpp index 77eee2c551846..6f486c9fb8ce1 100644 --- a/perception/lidar_apollo_instance_segmentation/src/detector.cpp +++ b/perception/lidar_apollo_instance_segmentation/src/detector.cpp @@ -60,9 +60,11 @@ LidarApolloInstanceSegmentation::LidarApolloInstanceSegmentation(rclcpp::Node * RCLCPP_ERROR(node_->get_logger(), "can not find output named %s", output_node.c_str()); } network->markOutput(*output); - const int batch_size = 1; - builder->setMaxBatchSize(batch_size); +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, 1 << 30); +#else config->setMaxWorkspaceSize(1 << 30); +#endif nvinfer1::IHostMemory * plan = builder->buildSerializedNetwork(*network, *config); assert(plan != nullptr); std::ofstream outfile(engine_file, std::ofstream::binary); diff --git a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp index 81e48a98adbf0..a175079ab0348 100644 --- a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp @@ -79,7 +79,11 @@ bool TensorRTWrapper::parseONNX( std::cout << "Fail to create config" << std::endl; return false; } +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); +#else config->setMaxWorkspaceSize(workspace_size); +#endif if (precision == "fp16") { if (builder->platformHasFastFp16()) { std::cout << "use TensorRT FP16 Inference" << std::endl; diff --git a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp index 748680266ca9c..65fb298aff388 100644 --- a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp +++ b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp @@ -161,7 +161,11 @@ Net::Net( if (fp16 || int8) { config->setFlag(nvinfer1::BuilderFlag::kFP16); } +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); +#else config->setMaxWorkspaceSize(workspace_size); +#endif // Parse ONNX FCN std::cout << "Building " << precision << " core model..." << std::endl; diff --git a/perception/traffic_light_classifier/utils/trt_common.cpp b/perception/traffic_light_classifier/utils/trt_common.cpp index cae9f0cd1682a..4aae3e0ece5e1 100644 --- a/perception/traffic_light_classifier/utils/trt_common.cpp +++ b/perception/traffic_light_classifier/utils/trt_common.cpp @@ -42,8 +42,7 @@ TrtCommon::TrtCommon(std::string model_path, std::string precision) precision_(precision), input_name_("input_0"), output_name_("output_0"), - is_initialized_(false), - max_batch_size_(1) + is_initialized_(false) { runtime_ = UniquePtr(nvinfer1::createInferRuntime(logger_)); } @@ -106,8 +105,11 @@ bool TrtCommon::buildEngineFromOnnx(std::string onnx_file_path, std::string outp return false; } - builder->setMaxBatchSize(max_batch_size_); +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, 16 << 20); +#else config->setMaxWorkspaceSize(16 << 20); +#endif if (precision_ == "fp16") { config->setFlag(nvinfer1::BuilderFlag::kFP16); diff --git a/perception/traffic_light_classifier/utils/trt_common.hpp b/perception/traffic_light_classifier/utils/trt_common.hpp index 7c172b6719678..9577dfd2262a6 100644 --- a/perception/traffic_light_classifier/utils/trt_common.hpp +++ b/perception/traffic_light_classifier/utils/trt_common.hpp @@ -136,7 +136,6 @@ class TrtCommon std::string input_name_; std::string output_name_; bool is_initialized_; - size_t max_batch_size_; }; } // namespace Tn diff --git a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp index ba9f94b014513..d810eb5275058 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp +++ b/perception/traffic_light_ssd_fine_detector/lib/src/trt_ssd.cpp @@ -92,7 +92,11 @@ Net::Net( if (fp16 || int8) { config->setFlag(nvinfer1::BuilderFlag::kFP16); } +#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 + config->setMemoryPoolLimit(nvinfer1::MemoryPoolType::kWORKSPACE, workspace_size); +#else config->setMaxWorkspaceSize(workspace_size); +#endif // Parse ONNX FCN std::cout << "Building " << precision << " core model..." << std::endl;