tensorrt_wrapper.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154
  1. // Copyright 2021 TIER IV, Inc.
  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. #include "lidar_centerpoint/network/tensorrt_wrapper.hpp"
  15. #include <NvOnnxParser.h>
  16. #include <fstream>
  17. #include <memory>
  18. #include <string>
  19. namespace centerpoint
  20. {
  21. TensorRTWrapper::TensorRTWrapper(const CenterPointConfig & config, const bool verbose)
  22. : config_(config), logger_(Logger(verbose))
  23. {
  24. }
  25. bool TensorRTWrapper::init(
  26. const std::string & onnx_path, const std::string & engine_path, const std::string & precision)
  27. {
  28. runtime_ = unique_ptr<nvinfer1::IRuntime>(nvinfer1::createInferRuntime(logger_));
  29. if (!runtime_) {
  30. std::cout << "Fail to create runtime" << std::endl;
  31. return false;
  32. }
  33. bool success;
  34. std::ifstream engine_file(engine_path);
  35. if (engine_file.is_open()) {
  36. success = loadEngine(engine_path);
  37. } else {
  38. success = parseONNX(onnx_path, engine_path, precision);
  39. }
  40. success &= createContext();
  41. return success;
  42. }
  43. bool TensorRTWrapper::createContext()
  44. {
  45. if (!engine_) {
  46. std::cout << "Fail to create context: Engine isn't created" << std::endl;
  47. return false;
  48. }
  49. context_ = unique_ptr<nvinfer1::IExecutionContext>(engine_->createExecutionContext());
  50. if (!context_) {
  51. std::cout << "Fail to create context" << std::endl;
  52. return false;
  53. }
  54. return true;
  55. }
  56. bool TensorRTWrapper::parseONNX(
  57. const std::string & onnx_path, const std::string & engine_path, const std::string & precision,
  58. const size_t workspace_size)
  59. {
  60. auto builder = unique_ptr<nvinfer1::IBuilder>(nvinfer1::createInferBuilder(logger_));
  61. if (!builder) {
  62. std::cout << "Fail to create builder" << std::endl;
  63. return false;
  64. }
  65. auto config = unique_ptr<nvinfer1::IBuilderConfig>(builder->createBuilderConfig());
  66. if (!config) {
  67. std::cout << "Fail to create config" << std::endl;
  68. return false;
  69. }
  70. config->setMaxWorkspaceSize(workspace_size);
  71. if (precision == "fp16") {
  72. if (builder->platformHasFastFp16()) {
  73. std::cout << "use TensorRT FP16 Inference" << std::endl;
  74. config->setFlag(nvinfer1::BuilderFlag::kFP16);
  75. } else {
  76. std::cout << "TensorRT FP16 Inference isn't supported in this environment" << std::endl;
  77. }
  78. }
  79. const auto flag =
  80. 1U << static_cast<uint32_t>(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH);
  81. auto network = unique_ptr<nvinfer1::INetworkDefinition>(builder->createNetworkV2(flag));
  82. if (!network) {
  83. std::cout << "Fail to create network" << std::endl;
  84. return false;
  85. }
  86. auto parser = unique_ptr<nvonnxparser::IParser>(nvonnxparser::createParser(*network, logger_));
  87. parser->parseFromFile(onnx_path.c_str(), static_cast<int>(nvinfer1::ILogger::Severity::kERROR));
  88. if (!setProfile(*builder, *network, *config)) {
  89. std::cout << "Fail to set profile" << std::endl;
  90. return false;
  91. }
  92. std::cout << "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..."
  93. << std::endl;
  94. plan_ = unique_ptr<nvinfer1::IHostMemory>(builder->buildSerializedNetwork(*network, *config));
  95. if (!plan_) {
  96. std::cout << "Fail to create serialized network" << std::endl;
  97. return false;
  98. }
  99. engine_ = unique_ptr<nvinfer1::ICudaEngine>(
  100. runtime_->deserializeCudaEngine(plan_->data(), plan_->size()));
  101. if (!engine_) {
  102. std::cout << "Fail to create engine" << std::endl;
  103. return false;
  104. }
  105. return saveEngine(engine_path);
  106. }
  107. bool TensorRTWrapper::saveEngine(const std::string & engine_path)
  108. {
  109. std::cout << "Writing to " << engine_path << std::endl;
  110. std::ofstream file(engine_path, std::ios::out | std::ios::binary);
  111. file.write(reinterpret_cast<const char *>(plan_->data()), plan_->size());
  112. return true;
  113. }
  114. bool TensorRTWrapper::loadEngine(const std::string & engine_path)
  115. {
  116. std::ifstream file(engine_path, std::ios::in | std::ios::binary);
  117. file.seekg(0, std::ifstream::end);
  118. const size_t size = file.tellg();
  119. file.seekg(0, std::ifstream::beg);
  120. std::unique_ptr<char[]> buffer{new char[size]};
  121. file.read(buffer.get(), size);
  122. file.close();
  123. if (!runtime_) {
  124. std::cout << "Fail to load engine: Runtime isn't created" << std::endl;
  125. return false;
  126. }
  127. std::cout << "Loading from " << engine_path << std::endl;
  128. engine_ = unique_ptr<nvinfer1::ICudaEngine>(runtime_->deserializeCudaEngine(buffer.get(), size));
  129. return true;
  130. }
  131. } // namespace centerpoint