Skip to content

Commit b56e359

Browse files
ktro2828miursh
authored andcommitted
refactor: update TRT build log (autowarefoundation#6117)
* feat: add support of throttle logging Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: replace custom `Logger` to `tensorrt_common::Logger` Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: update to display standard output on screen Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: update log message while building engine from onnx Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: update logger in `lidar_centerpoint` Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: update log message Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: set default verbose=true for bulding engine from onnx Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: remove including unused `rclcpp.hpp` Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> * refactor: update launcher to output logs on screen Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> --------- Signed-off-by: ktro2828 <kotaro.uetake@tier4.jp> Co-authored-by: Shunsuke Miura <37187849+miursh@users.noreply.github.com>
1 parent fd16f42 commit b56e359

File tree

13 files changed

+133
-100
lines changed

13 files changed

+133
-100
lines changed

common/tensorrt_common/include/tensorrt_common/logger.hpp

+56-7
Original file line numberDiff line numberDiff line change
@@ -19,13 +19,15 @@
1919

2020
#include "NvInferRuntimeCommon.h"
2121

22+
#include <atomic>
2223
#include <cassert>
2324
#include <ctime>
2425
#include <iomanip>
2526
#include <iostream>
2627
#include <ostream>
2728
#include <sstream>
2829
#include <string>
30+
#include <thread>
2931

3032
namespace tensorrt_common
3133
{
@@ -200,7 +202,15 @@ class Logger : public nvinfer1::ILogger // NOLINT
200202
public:
201203
// Logger(Severity severity = Severity::kWARNING)
202204
// Logger(Severity severity = Severity::kVERBOSE)
203-
explicit Logger(Severity severity = Severity::kINFO) : mReportableSeverity(severity) {}
205+
explicit Logger(Severity severity = Severity::kINFO)
206+
: mReportableSeverity(severity), mVerbose(true), mThrottleStopFlag(false)
207+
{
208+
}
209+
210+
explicit Logger(const bool verbose, Severity severity = Severity::kINFO)
211+
: mReportableSeverity(severity), mVerbose(verbose), mThrottleStopFlag(false)
212+
{
213+
}
204214

205215
//!
206216
//! \enum TestResult
@@ -234,7 +244,44 @@ class Logger : public nvinfer1::ILogger // NOLINT
234244
//!
235245
void log(Severity severity, const char * msg) noexcept override
236246
{
237-
LogStreamConsumer(mReportableSeverity, severity) << "[TRT] " << std::string(msg) << std::endl;
247+
if (mVerbose) {
248+
LogStreamConsumer(mReportableSeverity, severity) << "[TRT] " << std::string(msg) << std::endl;
249+
}
250+
}
251+
252+
/**
253+
* @brief Logging with throttle.
254+
*
255+
* @example
256+
* Logger logger();
257+
* auto log_thread = logger.log_throttle(nvinfer1::ILogger::Severity::kINFO, "SOME MSG", 1);
258+
* // some operation
259+
* logger.stop_throttle(log_thread);
260+
*
261+
* @param severity
262+
* @param msg
263+
* @param duration
264+
* @return std::thread
265+
*
266+
*/
267+
std::thread log_throttle(Severity severity, const char * msg, const int duration) noexcept
268+
{
269+
mThrottleStopFlag.store(false);
270+
auto log_func = [this](Severity s, const char * m, const int d) {
271+
while (!mThrottleStopFlag.load()) {
272+
this->log(s, m);
273+
std::this_thread::sleep_for(std::chrono::seconds(d));
274+
}
275+
};
276+
277+
std::thread log_thread(log_func, severity, msg, duration);
278+
return log_thread;
279+
}
280+
281+
void stop_throttle(std::thread & log_thread) noexcept
282+
{
283+
mThrottleStopFlag.store(true);
284+
log_thread.join();
238285
}
239286

240287
//!
@@ -430,6 +477,8 @@ class Logger : public nvinfer1::ILogger // NOLINT
430477
}
431478

432479
Severity mReportableSeverity;
480+
bool mVerbose;
481+
std::atomic<bool> mThrottleStopFlag;
433482
};
434483

435484
namespace
@@ -444,7 +493,7 @@ namespace
444493
//!
445494
inline LogStreamConsumer LOG_VERBOSE(const Logger & logger)
446495
{
447-
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE);
496+
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE) << "[TRT] ";
448497
}
449498

450499
//!
@@ -456,7 +505,7 @@ inline LogStreamConsumer LOG_VERBOSE(const Logger & logger)
456505
//!
457506
inline LogStreamConsumer LOG_INFO(const Logger & logger)
458507
{
459-
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO);
508+
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO) << "[TRT] ";
460509
}
461510

462511
//!
@@ -468,7 +517,7 @@ inline LogStreamConsumer LOG_INFO(const Logger & logger)
468517
//!
469518
inline LogStreamConsumer LOG_WARN(const Logger & logger)
470519
{
471-
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING);
520+
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING) << "[TRT] ";
472521
}
473522

474523
//!
@@ -480,7 +529,7 @@ inline LogStreamConsumer LOG_WARN(const Logger & logger)
480529
//!
481530
inline LogStreamConsumer LOG_ERROR(const Logger & logger)
482531
{
483-
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR);
532+
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR) << "[TRT] ";
484533
}
485534

486535
//!
@@ -494,7 +543,7 @@ inline LogStreamConsumer LOG_ERROR(const Logger & logger)
494543
//!
495544
inline LogStreamConsumer LOG_FATAL(const Logger & logger)
496545
{
497-
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR);
546+
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR) << "[TRT] ";
498547
}
499548

500549
} // anonymous namespace

common/tensorrt_common/src/tensorrt_common.cpp

+4
Original file line numberDiff line numberDiff line change
@@ -186,7 +186,11 @@ void TrtCommon::setup()
186186
} else {
187187
std::cout << "Building... " << cache_engine_path << std::endl;
188188
logger_.log(nvinfer1::ILogger::Severity::kINFO, "Start build engine");
189+
auto log_thread = logger_.log_throttle(
190+
nvinfer1::ILogger::Severity::kINFO,
191+
"Applying optimizations and building TRT CUDA engine. Please wait for a few minutes...", 5);
189192
buildEngineFromOnnx(model_file_path_, cache_engine_path);
193+
logger_.stop_throttle(log_thread);
190194
logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine");
191195
}
192196
engine_path = cache_engine_path;

perception/lidar_centerpoint/lib/network/network_trt.cpp

+2-5
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@
1414

1515
#include "lidar_centerpoint/network/network_trt.hpp"
1616

17-
#include <rclcpp/rclcpp.hpp>
18-
1917
namespace centerpoint
2018
{
2119
bool VoxelEncoderTRT::setProfile(
@@ -65,9 +63,8 @@ bool HeadTRT::setProfile(
6563
if (
6664
out_name == std::string("heatmap") &&
6765
network.getOutput(ci)->getDimensions().d[1] != static_cast<int32_t>(out_channel_sizes_[ci])) {
68-
RCLCPP_ERROR(
69-
rclcpp::get_logger("lidar_centerpoint"),
70-
"Expected and actual number of classes do not match");
66+
tensorrt_common::LOG_ERROR(logger_)
67+
<< "Expected and actual number of classes do not match" << std::endl;
7168
return false;
7269
}
7370
auto out_dims = nvinfer1::Dims4(

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

+19-21
Original file line numberDiff line numberDiff line change
@@ -14,8 +14,6 @@
1414

1515
#include "lidar_centerpoint/network/tensorrt_wrapper.hpp"
1616

17-
#include <rclcpp/rclcpp.hpp>
18-
1917
#include <NvOnnxParser.h>
2018

2119
#include <fstream>
@@ -42,7 +40,7 @@ bool TensorRTWrapper::init(
4240
runtime_ =
4341
tensorrt_common::TrtUniquePtr<nvinfer1::IRuntime>(nvinfer1::createInferRuntime(logger_));
4442
if (!runtime_) {
45-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create runtime");
43+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create runtime" << std::endl;
4644
return false;
4745
}
4846

@@ -51,7 +49,11 @@ bool TensorRTWrapper::init(
5149
if (engine_file.is_open()) {
5250
success = loadEngine(engine_path);
5351
} else {
52+
auto log_thread = logger_.log_throttle(
53+
nvinfer1::ILogger::Severity::kINFO,
54+
"Applying optimizations and building TRT CUDA engine. Please wait a minutes...", 5);
5455
success = parseONNX(onnx_path, engine_path, precision);
56+
logger_.stop_throttle(log_thread);
5557
}
5658
success &= createContext();
5759

@@ -61,15 +63,15 @@ bool TensorRTWrapper::init(
6163
bool TensorRTWrapper::createContext()
6264
{
6365
if (!engine_) {
64-
RCLCPP_ERROR(
65-
rclcpp::get_logger("lidar_centerpoint"), "Failed to create context: Engine was not created");
66+
tensorrt_common::LOG_ERROR(logger_)
67+
<< "Failed to create context: Engine was not created" << std::endl;
6668
return false;
6769
}
6870

6971
context_ =
7072
tensorrt_common::TrtUniquePtr<nvinfer1::IExecutionContext>(engine_->createExecutionContext());
7173
if (!context_) {
72-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create context");
74+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create context" << std::endl;
7375
return false;
7476
}
7577

@@ -83,14 +85,14 @@ bool TensorRTWrapper::parseONNX(
8385
auto builder =
8486
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilder>(nvinfer1::createInferBuilder(logger_));
8587
if (!builder) {
86-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create builder");
88+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create builder" << std::endl;
8789
return false;
8890
}
8991

9092
auto config =
9193
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilderConfig>(builder->createBuilderConfig());
9294
if (!config) {
93-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create config");
95+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create config" << std::endl;
9496
return false;
9597
}
9698
#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400
@@ -100,12 +102,11 @@ bool TensorRTWrapper::parseONNX(
100102
#endif
101103
if (precision == "fp16") {
102104
if (builder->platformHasFastFp16()) {
103-
RCLCPP_INFO(rclcpp::get_logger("lidar_centerpoint"), "Using TensorRT FP16 Inference");
105+
tensorrt_common::LOG_INFO(logger_) << "Using TensorRT FP16 Inference" << std::endl;
104106
config->setFlag(nvinfer1::BuilderFlag::kFP16);
105107
} else {
106-
RCLCPP_INFO(
107-
rclcpp::get_logger("lidar_centerpoint"),
108-
"TensorRT FP16 Inference isn't supported in this environment");
108+
tensorrt_common::LOG_INFO(logger_)
109+
<< "TensorRT FP16 Inference isn't supported in this environment" << std::endl;
109110
}
110111
}
111112

@@ -114,7 +115,7 @@ bool TensorRTWrapper::parseONNX(
114115
auto network =
115116
tensorrt_common::TrtUniquePtr<nvinfer1::INetworkDefinition>(builder->createNetworkV2(flag));
116117
if (!network) {
117-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create network");
118+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create network" << std::endl;
118119
return false;
119120
}
120121

@@ -123,23 +124,20 @@ bool TensorRTWrapper::parseONNX(
123124
parser->parseFromFile(onnx_path.c_str(), static_cast<int>(nvinfer1::ILogger::Severity::kERROR));
124125

125126
if (!setProfile(*builder, *network, *config)) {
126-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to set profile");
127+
tensorrt_common::LOG_ERROR(logger_) << "Failed to set profile" << std::endl;
127128
return false;
128129
}
129130

130-
RCLCPP_INFO_STREAM(
131-
rclcpp::get_logger("lidar_centerpoint"),
132-
"Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ...");
133131
plan_ = tensorrt_common::TrtUniquePtr<nvinfer1::IHostMemory>(
134132
builder->buildSerializedNetwork(*network, *config));
135133
if (!plan_) {
136-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create serialized network");
134+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create serialized network" << std::endl;
137135
return false;
138136
}
139137
engine_ = tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine>(
140138
runtime_->deserializeCudaEngine(plan_->data(), plan_->size()));
141139
if (!engine_) {
142-
RCLCPP_ERROR(rclcpp::get_logger("lidar_centerpoint"), "Failed to create engine");
140+
tensorrt_common::LOG_ERROR(logger_) << "Failed to create engine" << std::endl;
143141
return false;
144142
}
145143

@@ -148,7 +146,7 @@ bool TensorRTWrapper::parseONNX(
148146

149147
bool TensorRTWrapper::saveEngine(const std::string & engine_path)
150148
{
151-
RCLCPP_INFO_STREAM(rclcpp::get_logger("lidar_centerpoint"), "Writing to " << engine_path);
149+
tensorrt_common::LOG_INFO(logger_) << "Writing to " << engine_path << std::endl;
152150
std::ofstream file(engine_path, std::ios::out | std::ios::binary);
153151
file.write(reinterpret_cast<const char *>(plan_->data()), plan_->size());
154152
return true;
@@ -162,7 +160,7 @@ bool TensorRTWrapper::loadEngine(const std::string & engine_path)
162160
std::string engine_str = engine_buffer.str();
163161
engine_ = tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine>(runtime_->deserializeCudaEngine(
164162
reinterpret_cast<const void *>(engine_str.data()), engine_str.size()));
165-
RCLCPP_INFO_STREAM(rclcpp::get_logger("lidar_centerpoint"), "Loaded engine from " << engine_path);
163+
tensorrt_common::LOG_INFO(logger_) << "Loaded engine from " << engine_path << std::endl;
166164
return true;
167165
}
168166

perception/tensorrt_yolo/lib/include/trt_yolo.hpp

+3-17
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,7 @@
4141
#include <opencv2/core/core.hpp>
4242
#include <opencv2/highgui/highgui.hpp>
4343
#include <opencv2/opencv.hpp>
44+
#include <tensorrt_common/logger.hpp>
4445
#include <yolo_layer.hpp>
4546

4647
#include <NvInfer.h>
@@ -67,22 +68,6 @@ struct Deleter
6768
template <typename T>
6869
using unique_ptr = std::unique_ptr<T, Deleter>;
6970

70-
class Logger : public nvinfer1::ILogger
71-
{
72-
public:
73-
explicit Logger(bool verbose) : verbose_(verbose) {}
74-
75-
void log(Severity severity, const char * msg) noexcept override
76-
{
77-
if (verbose_ || ((severity != Severity::kINFO) && (severity != Severity::kVERBOSE))) {
78-
std::cout << msg << std::endl;
79-
}
80-
}
81-
82-
private:
83-
bool verbose_{false};
84-
};
85-
8671
struct Config
8772
{
8873
int num_anchors;
@@ -105,7 +90,7 @@ class Net
10590
Net(
10691
const std::string & onnx_file_path, const std::string & precision, const int max_batch_size,
10792
const Config & yolo_config, const std::vector<std::string> & calibration_images,
108-
const std::string & calibration_table, bool verbose = false,
93+
const std::string & calibration_table, bool verbose = true,
10994
size_t workspace_size = (1ULL << 30));
11095

11196
~Net();
@@ -138,6 +123,7 @@ class Net
138123
cuda::unique_ptr<float[]> out_scores_d_ = nullptr;
139124
cuda::unique_ptr<float[]> out_boxes_d_ = nullptr;
140125
cuda::unique_ptr<float[]> out_classes_d_ = nullptr;
126+
tensorrt_common::Logger logger_;
141127

142128
void load(const std::string & path);
143129
bool prepare();

0 commit comments

Comments
 (0)