From 6835bc47da0f596079514454e220375f2b9030d5 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Mon, 29 Jan 2024 09:02:15 +0900 Subject: [PATCH] refactor: update TRT build log (#6117) * feat: add support of throttle logging Signed-off-by: ktro2828 * refactor: replace custom `Logger` to `tensorrt_common::Logger` Signed-off-by: ktro2828 * refactor: update to display standard output on screen Signed-off-by: ktro2828 * refactor: update log message while building engine from onnx Signed-off-by: ktro2828 * refactor: update logger in `lidar_centerpoint` Signed-off-by: ktro2828 * refactor: update log message Signed-off-by: ktro2828 * refactor: set default verbose=true for bulding engine from onnx Signed-off-by: ktro2828 * refactor: remove including unused `rclcpp.hpp` Signed-off-by: ktro2828 * refactor: update launcher to output logs on screen Signed-off-by: ktro2828 --------- Signed-off-by: ktro2828 Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com> --- .../include/tensorrt_common/logger.hpp | 63 ++++++++++++++++--- .../tensorrt_common/src/tensorrt_common.cpp | 4 ++ .../lib/network/network_trt.cpp | 7 +-- .../lib/network/tensorrt_wrapper.cpp | 40 ++++++------ .../tensorrt_yolo/lib/include/trt_yolo.hpp | 20 +----- perception/tensorrt_yolo/lib/src/trt_yolo.cpp | 35 ++++++----- perception/tensorrt_yolo/package.xml | 1 + .../traffic_light_classifier.launch.xml | 2 +- .../traffic_light_fine_detector.launch.xml | 2 +- ...traffic_light_ssd_fine_detector.launch.xml | 2 +- .../lib/include/trt_ssd.hpp | 21 ++----- .../lib/src/trt_ssd.cpp | 35 ++++++----- .../package.xml | 1 + 13 files changed, 133 insertions(+), 100 deletions(-) diff --git a/common/tensorrt_common/include/tensorrt_common/logger.hpp b/common/tensorrt_common/include/tensorrt_common/logger.hpp index 98fe18794998d..73190d13b9de3 100644 --- a/common/tensorrt_common/include/tensorrt_common/logger.hpp +++ b/common/tensorrt_common/include/tensorrt_common/logger.hpp @@ -19,6 +19,7 @@ #include "NvInferRuntimeCommon.h" +#include #include #include #include @@ -26,6 +27,7 @@ #include #include #include +#include namespace tensorrt_common { @@ -200,7 +202,15 @@ class Logger : public nvinfer1::ILogger // NOLINT public: // Logger(Severity severity = Severity::kWARNING) // Logger(Severity severity = Severity::kVERBOSE) - explicit Logger(Severity severity = Severity::kINFO) : mReportableSeverity(severity) {} + explicit Logger(Severity severity = Severity::kINFO) + : mReportableSeverity(severity), mVerbose(true), mThrottleStopFlag(false) + { + } + + explicit Logger(const bool verbose, Severity severity = Severity::kINFO) + : mReportableSeverity(severity), mVerbose(verbose), mThrottleStopFlag(false) + { + } //! //! \enum TestResult @@ -234,7 +244,44 @@ class Logger : public nvinfer1::ILogger // NOLINT //! void log(Severity severity, const char * msg) noexcept override { - LogStreamConsumer(mReportableSeverity, severity) << "[TRT] " << std::string(msg) << std::endl; + if (mVerbose) { + LogStreamConsumer(mReportableSeverity, severity) << "[TRT] " << std::string(msg) << std::endl; + } + } + + /** + * @brief Logging with throttle. + * + * @example + * Logger logger(); + * auto log_thread = logger.log_throttle(nvinfer1::ILogger::Severity::kINFO, "SOME MSG", 1); + * // some operation + * logger.stop_throttle(log_thread); + * + * @param severity + * @param msg + * @param duration + * @return std::thread + * + */ + std::thread log_throttle(Severity severity, const char * msg, const int duration) noexcept + { + mThrottleStopFlag.store(false); + auto log_func = [this](Severity s, const char * m, const int d) { + while (!mThrottleStopFlag.load()) { + this->log(s, m); + std::this_thread::sleep_for(std::chrono::seconds(d)); + } + }; + + std::thread log_thread(log_func, severity, msg, duration); + return log_thread; + } + + void stop_throttle(std::thread & log_thread) noexcept + { + mThrottleStopFlag.store(true); + log_thread.join(); } //! @@ -430,6 +477,8 @@ class Logger : public nvinfer1::ILogger // NOLINT } Severity mReportableSeverity; + bool mVerbose; + std::atomic mThrottleStopFlag; }; namespace @@ -444,7 +493,7 @@ namespace //! inline LogStreamConsumer LOG_VERBOSE(const Logger & logger) { - return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE); + return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE) << "[TRT] "; } //! @@ -456,7 +505,7 @@ inline LogStreamConsumer LOG_VERBOSE(const Logger & logger) //! inline LogStreamConsumer LOG_INFO(const Logger & logger) { - return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO); + return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO) << "[TRT] "; } //! @@ -468,7 +517,7 @@ inline LogStreamConsumer LOG_INFO(const Logger & logger) //! inline LogStreamConsumer LOG_WARN(const Logger & logger) { - return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING); + return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING) << "[TRT] "; } //! @@ -480,7 +529,7 @@ inline LogStreamConsumer LOG_WARN(const Logger & logger) //! inline LogStreamConsumer LOG_ERROR(const Logger & logger) { - return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR); + return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR) << "[TRT] "; } //! @@ -494,7 +543,7 @@ inline LogStreamConsumer LOG_ERROR(const Logger & logger) //! inline LogStreamConsumer LOG_FATAL(const Logger & logger) { - return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR); + return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR) << "[TRT] "; } } // anonymous namespace diff --git a/common/tensorrt_common/src/tensorrt_common.cpp b/common/tensorrt_common/src/tensorrt_common.cpp index f1e4835d2ba2d..2b218cd3e49f2 100644 --- a/common/tensorrt_common/src/tensorrt_common.cpp +++ b/common/tensorrt_common/src/tensorrt_common.cpp @@ -186,7 +186,11 @@ void TrtCommon::setup() } else { std::cout << "Building... " << cache_engine_path << std::endl; logger_.log(nvinfer1::ILogger::Severity::kINFO, "Start build engine"); + auto log_thread = logger_.log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5); buildEngineFromOnnx(model_file_path_, cache_engine_path); + logger_.stop_throttle(log_thread); logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine"); } engine_path = cache_engine_path; diff --git a/perception/lidar_centerpoint/lib/network/network_trt.cpp b/perception/lidar_centerpoint/lib/network/network_trt.cpp index 2d841d22c2eb1..ad1a7ae90630c 100644 --- a/perception/lidar_centerpoint/lib/network/network_trt.cpp +++ b/perception/lidar_centerpoint/lib/network/network_trt.cpp @@ -14,8 +14,6 @@ #include "lidar_centerpoint/network/network_trt.hpp" -#include - namespace centerpoint { bool VoxelEncoderTRT::setProfile( @@ -65,9 +63,8 @@ bool HeadTRT::setProfile( if ( out_name == std::string("heatmap") && network.getOutput(ci)->getDimensions().d[1] != static_cast(out_channel_sizes_[ci])) { - RCLCPP_ERROR( - rclcpp::get_logger("lidar_centerpoint"), - "Expected and actual number of classes do not match"); + tensorrt_common::LOG_ERROR(logger_) + << "Expected and actual number of classes do not match" << std::endl; return false; } auto out_dims = nvinfer1::Dims4( diff --git a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp index 2255df99dbcf4..91fcce9a80f78 100644 --- a/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp +++ b/perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp @@ -14,8 +14,6 @@ #include "lidar_centerpoint/network/tensorrt_wrapper.hpp" -#include - #include #include @@ -42,7 +40,7 @@ bool TensorRTWrapper::init( runtime_ = tensorrt_common::TrtUniquePtr(nvinfer1::createInferRuntime(logger_)); if (!runtime_) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create runtime"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl; return false; } @@ -51,7 +49,11 @@ bool TensorRTWrapper::init( if (engine_file.is_open()) { success = loadEngine(engine_path); } else { + auto log_thread = logger_.log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5); success = parseONNX(onnx_path, engine_path, precision); + logger_.stop_throttle(log_thread); } success &= createContext(); @@ -61,15 +63,15 @@ bool TensorRTWrapper::init( bool TensorRTWrapper::createContext() { if (!engine_) { - RCLCPP_ERROR( - rclcpp::get_logger("lidar_centerpoint"), "Failed to create context: Engine was not created"); + tensorrt_common::LOG_ERROR(logger_) + << "Failed to create context: Engine was not created" << std::endl; return false; } context_ = tensorrt_common::TrtUniquePtr(engine_->createExecutionContext()); if (!context_) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create context"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl; return false; } @@ -83,14 +85,14 @@ bool TensorRTWrapper::parseONNX( auto builder = tensorrt_common::TrtUniquePtr(nvinfer1::createInferBuilder(logger_)); if (!builder) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create builder"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl; return false; } auto config = tensorrt_common::TrtUniquePtr(builder->createBuilderConfig()); if (!config) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create config"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl; return false; } #if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400 @@ -100,12 +102,11 @@ bool TensorRTWrapper::parseONNX( #endif if (precision == "fp16") { if (builder->platformHasFastFp16()) { - RCLCPP_INFO(rclcpp::get_logger("lidar_centerpoint"), "Using TensorRT FP16 Inference"); + tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl; config->setFlag(nvinfer1::BuilderFlag::kFP16); } else { - RCLCPP_INFO( - rclcpp::get_logger("lidar_centerpoint"), - "TensorRT FP16 Inference isn't supported in this environment"); + tensorrt_common::LOG_INFO(logger_) + << "TensorRT FP16 Inference isn't supported in this environment" << std::endl; } } @@ -114,7 +115,7 @@ bool TensorRTWrapper::parseONNX( auto network = tensorrt_common::TrtUniquePtr(builder->createNetworkV2(flag)); if (!network) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create network"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl; return false; } @@ -123,23 +124,20 @@ bool TensorRTWrapper::parseONNX( parser->parseFromFile(onnx_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); if (!setProfile(*builder, *network, *config)) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to set profile"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl; return false; } - RCLCPP_INFO_STREAM( - rclcpp::get_logger("lidar_centerpoint"), - "Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ..."); plan_ = tensorrt_common::TrtUniquePtr( builder->buildSerializedNetwork(*network, *config)); if (!plan_) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create serialized network"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create serialized network" << std::endl; return false; } engine_ = tensorrt_common::TrtUniquePtr( runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { - RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create engine"); + tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl; return false; } @@ -148,7 +146,7 @@ bool TensorRTWrapper::parseONNX( bool TensorRTWrapper::saveEngine(const std::string & engine_path) { - RCLCPP_INFO_STREAM(rclcpp::get_logger("lidar_centerpoint"), "Writing to " << engine_path); + tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl; std::ofstream file(engine_path, std::ios::out | std::ios::binary); file.write(reinterpret_cast(plan_->data()), plan_->size()); return true; @@ -162,7 +160,7 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path) std::string engine_str = engine_buffer.str(); engine_ = tensorrt_common::TrtUniquePtr(runtime_->deserializeCudaEngine( reinterpret_cast(engine_str.data()), engine_str.size())); - RCLCPP_INFO_STREAM(rclcpp::get_logger("lidar_centerpoint"), "Loaded engine from " << engine_path); + tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl; return true; } diff --git a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp index af8065ffed379..a64c94c008526 100644 --- a/perception/tensorrt_yolo/lib/include/trt_yolo.hpp +++ b/perception/tensorrt_yolo/lib/include/trt_yolo.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include #include @@ -67,22 +68,6 @@ struct Deleter template using unique_ptr = std::unique_ptr; -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}; -}; - struct Config { int num_anchors; @@ -105,7 +90,7 @@ class Net Net( const std::string & onnx_file_path, const std::string & precision, const int max_batch_size, const Config & yolo_config, const std::vector & calibration_images, - const std::string & calibration_table, bool verbose = false, + const std::string & calibration_table, bool verbose = true, size_t workspace_size = (1ULL << 30)); ~Net(); @@ -138,6 +123,7 @@ class Net cuda::unique_ptr out_scores_d_ = nullptr; cuda::unique_ptr out_boxes_d_ = nullptr; cuda::unique_ptr out_classes_d_ = nullptr; + tensorrt_common::Logger logger_; void load(const std::string & path); bool prepare(); diff --git a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp index 7f1d2dbbf4577..c8793aa4c8512 100644 --- a/perception/tensorrt_yolo/lib/src/trt_yolo.cpp +++ b/perception/tensorrt_yolo/lib/src/trt_yolo.cpp @@ -113,10 +113,9 @@ std::vector Net::preprocess( return result; } -Net::Net(const std::string & path, bool verbose) +Net::Net(const std::string & path, bool verbose) : logger_(verbose) { - Logger logger(verbose); - runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger)); + runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger_)); load(path); if (!prepare()) { std::cout << "Fail to prepare engine" << std::endl; @@ -136,9 +135,9 @@ Net::Net( const std::string & onnx_file_path, const std::string & precision, const int max_batch_size, const Config & yolo_config, const std::vector & calibration_images, const std::string & calibration_table, bool verbose, size_t workspace_size) +: logger_(verbose) { - Logger logger(verbose); - runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger)); + runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger_)); if (!runtime_) { std::cout << "Fail to create runtime" << std::endl; return; @@ -147,7 +146,7 @@ Net::Net( bool int8 = precision.compare("INT8") == 0; // Create builder - auto builder = unique_ptr(nvinfer1::createInferBuilder(logger)); + auto builder = unique_ptr(nvinfer1::createInferBuilder(logger_)); if (!builder) { std::cout << "Fail to create builder" << std::endl; return; @@ -168,20 +167,23 @@ Net::Net( #endif // Parse ONNX FCN - std::cout << "Building " << precision << " core model..." << std::endl; + tensorrt_common::LOG_INFO(logger_) << "Building " << precision << " core model..." << std::endl; const auto flag = 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); auto network = unique_ptr(builder->createNetworkV2(flag)); if (!network) { - std::cout << "Fail to create network" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create network" << std::endl; return; } - auto parser = unique_ptr(nvonnxparser::createParser(*network, logger)); + auto parser = unique_ptr(nvonnxparser::createParser(*network, logger_)); if (!parser) { - std::cout << "Fail to create parser" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create parser" << std::endl; return; } + auto log_thread = logger_.log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5); parser->parseFromFile( onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); std::vector scores, boxes, classes; @@ -250,28 +252,31 @@ Net::Net( calib = std::make_unique(stream, calibration_table); config->setInt8Calibrator(calib.get()); } else { - std::cout << "Fail to find enough images for INT8 calibration. Build FP mode..." << std::endl; + tensorrt_common::LOG_WARN(logger_) + << "Fail to find enough images for INT8 calibration. Build FP mode..." << std::endl; } } // Build engine - std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); if (!plan_) { - std::cout << "Fail to create serialized network" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create serialized network" << std::endl; + logger_.stop_throttle(log_thread); return; } engine_ = unique_ptr( runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!prepare()) { - std::cout << "Fail to create engine" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create engine" << std::endl; + logger_.stop_throttle(log_thread); return; } + logger_.stop_throttle(log_thread); } void Net::save(const std::string & path) const { - std::cout << "Writing to " << path << "..." << std::endl; + tensorrt_common::LOG_INFO(logger_) << "Writing to " << path << "..." << std::endl; std::ofstream file(path, std::ios::out | std::ios::binary); file.write(reinterpret_cast(plan_->data()), plan_->size()); } diff --git a/perception/tensorrt_yolo/package.xml b/perception/tensorrt_yolo/package.xml index 8a6756449b70f..12d07647093b5 100755 --- a/perception/tensorrt_yolo/package.xml +++ b/perception/tensorrt_yolo/package.xml @@ -16,6 +16,7 @@ rclcpp rclcpp_components sensor_msgs + tensorrt_common tier4_perception_msgs ament_lint_auto diff --git a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml index 343531f4a00f1..e96f21b8ff01b 100644 --- a/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml +++ b/perception/traffic_light_classifier/launch/traffic_light_classifier.launch.xml @@ -17,7 +17,7 @@ - + diff --git a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml index 6e32d3410c260..e7a68ea9b9e94 100644 --- a/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml +++ b/perception/traffic_light_fine_detector/launch/traffic_light_fine_detector.launch.xml @@ -12,7 +12,7 @@ - + diff --git a/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml b/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml index 714c4d288b603..ad2851ced39c6 100644 --- a/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml +++ b/perception/traffic_light_ssd_fine_detector/launch/traffic_light_ssd_fine_detector.launch.xml @@ -16,7 +16,7 @@ - + diff --git a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp index 52d411c253fe5..00c21cdcaf29e 100644 --- a/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp +++ b/perception/traffic_light_ssd_fine_detector/lib/include/trt_ssd.hpp @@ -15,6 +15,8 @@ #ifndef TRT_SSD_HPP_ #define TRT_SSD_HPP_ +#include + #include <./cuda_runtime.h> #include @@ -39,22 +41,6 @@ struct Deleter template using unique_ptr = std::unique_ptr; -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}; -}; - struct Shape { int channel, width, height; @@ -78,7 +64,7 @@ class Net // Create engine from serialized onnx model Net( const std::string & onnx_file_path, const std::string & precision, const int max_batch_size, - bool verbose = false, size_t workspace_size = (1ULL << 30)); + bool verbose = true, size_t workspace_size = (1ULL << 30)); ~Net(); @@ -127,6 +113,7 @@ class Net unique_ptr engine_ = nullptr; unique_ptr context_ = nullptr; cudaStream_t stream_ = nullptr; + tensorrt_common::Logger logger_; void load(const std::string & path); void prepare(); 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 22aa0f6bf3880..8aceb32d2ec58 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 @@ -52,10 +52,9 @@ void Net::prepare() cudaStreamCreate(&stream_); } -Net::Net(const std::string & path, bool verbose) +Net::Net(const std::string & path, bool verbose) : logger_(verbose) { - Logger logger(verbose); - runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger)); + runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger_)); load(path); prepare(); } @@ -70,9 +69,9 @@ Net::~Net() Net::Net( const std::string & onnx_file_path, const std::string & precision, const int max_batch_size, bool verbose, size_t workspace_size) +: logger_(verbose) { - Logger logger(verbose); - runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger)); + runtime_ = unique_ptr(nvinfer1::createInferRuntime(logger_)); if (!runtime_) { std::cout << "Fail to create runtime" << std::endl; return; @@ -81,7 +80,7 @@ Net::Net( bool int8 = precision.compare("INT8") == 0; // Create builder - auto builder = unique_ptr(nvinfer1::createInferBuilder(logger)); + auto builder = unique_ptr(nvinfer1::createInferBuilder(logger_)); if (!builder) { std::cout << "Fail to create builder" << std::endl; return; @@ -102,19 +101,22 @@ Net::Net( #endif // Parse ONNX FCN - std::cout << "Building " << precision << " core model..." << std::endl; + tensorrt_common::LOG_INFO(logger_) << "Building " << precision << " core model..." << std::endl; const auto flag = 1U << static_cast(nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH); auto network = unique_ptr(builder->createNetworkV2(flag)); if (!network) { - std::cout << "Fail to create network" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create network" << std::endl; return; } - auto parser = unique_ptr(nvonnxparser::createParser(*network, logger)); + auto parser = unique_ptr(nvonnxparser::createParser(*network, logger_)); if (!parser) { - std::cout << "Fail to create parser" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create parser" << std::endl; return; } + auto log_thread = logger_.log_throttle( + nvinfer1::ILogger::Severity::kINFO, + "Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5); parser->parseFromFile( onnx_file_path.c_str(), static_cast(nvinfer1::ILogger::Severity::kERROR)); @@ -141,28 +143,31 @@ Net::Net( config->addOptimizationProfile(profile); // Build engine - std::cout << "Applying optimizations and building TRT CUDA engine..." << std::endl; plan_ = unique_ptr(builder->buildSerializedNetwork(*network, *config)); if (!plan_) { - std::cout << "Fail to create serialized network" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create serialized network" << std::endl; + logger_.stop_throttle(log_thread); return; } engine_ = unique_ptr( runtime_->deserializeCudaEngine(plan_->data(), plan_->size())); if (!engine_) { - std::cout << "Fail to create engine" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create engine" << std::endl; + logger_.stop_throttle(log_thread); return; } context_ = unique_ptr(engine_->createExecutionContext()); if (!context_) { - std::cout << "Fail to create context" << std::endl; + tensorrt_common::LOG_ERROR(logger_) << "Fail to create context" << std::endl; + logger_.stop_throttle(log_thread); return; } + logger_.stop_throttle(log_thread); } void Net::save(const std::string & path) { - std::cout << "Writing to " << path << "..." << std::endl; + tensorrt_common::LOG_INFO(logger_) << "Writing to " << path << "..." << std::endl; std::ofstream file(path, std::ios::out | std::ios::binary); file.write(reinterpret_cast(plan_->data()), plan_->size()); } diff --git a/perception/traffic_light_ssd_fine_detector/package.xml b/perception/traffic_light_ssd_fine_detector/package.xml index 994f84bacdae4..cd44857e8fe86 100644 --- a/perception/traffic_light_ssd_fine_detector/package.xml +++ b/perception/traffic_light_ssd_fine_detector/package.xml @@ -16,6 +16,7 @@ rclcpp rclcpp_components sensor_msgs + tensorrt_common tier4_debug_msgs tier4_perception_msgs