Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor: update TRT build log #6117

Merged
merged 11 commits into from
Jan 29, 2024
63 changes: 56 additions & 7 deletions common/tensorrt_common/include/tensorrt_common/logger.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,13 +19,15 @@

#include "NvInferRuntimeCommon.h"

#include <atomic>
#include <cassert>
#include <ctime>
#include <iomanip>
#include <iostream>
#include <ostream>
#include <sstream>
#include <string>
#include <thread>

namespace tensorrt_common
{
Expand Down Expand Up @@ -200,7 +202,15 @@
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)

Check warning on line 206 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L206

Added line #L206 was not covered by tests
{
}

explicit Logger(const bool verbose, Severity severity = Severity::kINFO)
: mReportableSeverity(severity), mVerbose(verbose), mThrottleStopFlag(false)
{
}

//!
//! \enum TestResult
Expand Down Expand Up @@ -234,7 +244,44 @@
//!
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;

Check warning on line 248 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L247-L248

Added lines #L247 - L248 were not covered by tests
}
}

Check warning on line 250 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L250

Added line #L250 was not covered by tests

/**
* @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

Check warning on line 267 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L267

Added line #L267 was not covered by tests
{
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));

Check warning on line 273 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L270-L273

Added lines #L270 - L273 were not covered by tests
}
};

Check warning on line 275 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L275

Added line #L275 was not covered by tests

std::thread log_thread(log_func, severity, msg, duration);
return log_thread;

Check warning on line 278 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L277-L278

Added lines #L277 - L278 were not covered by tests
}

void stop_throttle(std::thread & log_thread) noexcept
{
mThrottleStopFlag.store(true);
log_thread.join();

Check warning on line 284 in common/tensorrt_common/include/tensorrt_common/logger.hpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/include/tensorrt_common/logger.hpp#L284

Added line #L284 was not covered by tests
}

//!
Expand Down Expand Up @@ -430,6 +477,8 @@
}

Severity mReportableSeverity;
bool mVerbose;
std::atomic<bool> mThrottleStopFlag;
};

namespace
Expand All @@ -444,7 +493,7 @@
//!
inline LogStreamConsumer LOG_VERBOSE(const Logger & logger)
{
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE);
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kVERBOSE) << "[TRT] ";
}

//!
Expand All @@ -456,7 +505,7 @@
//!
inline LogStreamConsumer LOG_INFO(const Logger & logger)
{
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO);
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINFO) << "[TRT] ";
}

//!
Expand All @@ -468,7 +517,7 @@
//!
inline LogStreamConsumer LOG_WARN(const Logger & logger)
{
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING);
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kWARNING) << "[TRT] ";
}

//!
Expand All @@ -480,7 +529,7 @@
//!
inline LogStreamConsumer LOG_ERROR(const Logger & logger)
{
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR);
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kERROR) << "[TRT] ";
}

//!
Expand All @@ -494,7 +543,7 @@
//!
inline LogStreamConsumer LOG_FATAL(const Logger & logger)
{
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR);
return LogStreamConsumer(logger.getReportableSeverity(), Severity::kINTERNAL_ERROR) << "[TRT] ";
}

} // anonymous namespace
Expand Down
4 changes: 4 additions & 0 deletions common/tensorrt_common/src/tensorrt_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,11 @@
} 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);

Check warning on line 191 in common/tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

Codecov / codecov/patch

common/tensorrt_common/src/tensorrt_common.cpp#L191

Added line #L191 was not covered by tests
buildEngineFromOnnx(model_file_path_, cache_engine_path);
logger_.stop_throttle(log_thread);

Check warning on line 193 in common/tensorrt_common/src/tensorrt_common.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

TrtCommon::setup already has high cyclomatic complexity, and now it increases in Lines of Code from 79 to 83. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
logger_.log(nvinfer1::ILogger::Severity::kINFO, "End build engine");
}
engine_path = cache_engine_path;
Expand Down
7 changes: 2 additions & 5 deletions perception/lidar_centerpoint/lib/network/network_trt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@

#include "lidar_centerpoint/network/network_trt.hpp"

#include <rclcpp/rclcpp.hpp>

namespace centerpoint
{
bool VoxelEncoderTRT::setProfile(
Expand Down Expand Up @@ -65,9 +63,8 @@
if (
out_name == std::string("heatmap") &&
network.getOutput(ci)->getDimensions().d[1] != static_cast<int32_t>(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_)

Check warning on line 66 in perception/lidar_centerpoint/lib/network/network_trt.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/network_trt.cpp#L66

Added line #L66 was not covered by tests
<< "Expected and actual number of classes do not match" << std::endl;
return false;
}
auto out_dims = nvinfer1::Dims4(
Expand Down
40 changes: 19 additions & 21 deletions perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@

#include "lidar_centerpoint/network/tensorrt_wrapper.hpp"

#include <rclcpp/rclcpp.hpp>

#include <NvOnnxParser.h>

#include <fstream>
Expand All @@ -42,7 +40,7 @@
runtime_ =
tensorrt_common::TrtUniquePtr<nvinfer1::IRuntime>(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;

Check warning on line 43 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L43

Added line #L43 was not covered by tests
return false;
}

Expand All @@ -51,7 +49,11 @@
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);

Check warning on line 54 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L54

Added line #L54 was not covered by tests
success = parseONNX(onnx_path, engine_path, precision);
logger_.stop_throttle(log_thread);
}
success &= createContext();

Expand All @@ -61,15 +63,15 @@
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_)

Check warning on line 66 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L66

Added line #L66 was not covered by tests
<< "Failed to create context: Engine was not created" << std::endl;
return false;
}

context_ =
tensorrt_common::TrtUniquePtr<nvinfer1::IExecutionContext>(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;

Check warning on line 74 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L74

Added line #L74 was not covered by tests
return false;
}

Expand All @@ -83,14 +85,14 @@
auto builder =
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilder>(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;

Check warning on line 88 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L88

Added line #L88 was not covered by tests
return false;
}

auto config =
tensorrt_common::TrtUniquePtr<nvinfer1::IBuilderConfig>(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;

Check warning on line 95 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L95

Added line #L95 was not covered by tests
return false;
}
#if (NV_TENSORRT_MAJOR * 1000) + (NV_TENSORRT_MINOR * 100) + NV_TENSOR_PATCH >= 8400
Expand All @@ -100,12 +102,11 @@
#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;

Check warning on line 105 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L105

Added line #L105 was not covered by tests
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_)

Check warning on line 108 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L108

Added line #L108 was not covered by tests
<< "TensorRT FP16 Inference isn't supported in this environment" << std::endl;
}
}

Expand All @@ -114,7 +115,7 @@
auto network =
tensorrt_common::TrtUniquePtr<nvinfer1::INetworkDefinition>(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;

Check warning on line 118 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L118

Added line #L118 was not covered by tests
return false;
}

Expand All @@ -123,23 +124,20 @@
parser->parseFromFile(onnx_path.c_str(), static_cast<int>(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;

Check warning on line 127 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L127

Added line #L127 was not covered by tests
return false;
}

RCLCPP_INFO_STREAM(
rclcpp::get_logger("lidar_centerpoint"),
"Applying optimizations and building TRT CUDA engine (" << onnx_path << ") ...");
plan_ = tensorrt_common::TrtUniquePtr<nvinfer1::IHostMemory>(
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;

Check warning on line 134 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L134

Added line #L134 was not covered by tests
return false;
}
engine_ = tensorrt_common::TrtUniquePtr<nvinfer1::ICudaEngine>(
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;

Check warning on line 140 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L140

Added line #L140 was not covered by tests
return false;
}

Expand All @@ -148,7 +146,7 @@

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;

Check warning on line 149 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L149

Added line #L149 was not covered by tests
std::ofstream file(engine_path, std::ios::out | std::ios::binary);
file.write(reinterpret_cast<const char *>(plan_->data()), plan_->size());
return true;
Expand All @@ -162,7 +160,7 @@
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()));
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;

Check warning on line 163 in perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp

View check run for this annotation

Codecov / codecov/patch

perception/lidar_centerpoint/lib/network/tensorrt_wrapper.cpp#L163

Added line #L163 was not covered by tests
return true;
}

Expand Down
20 changes: 3 additions & 17 deletions perception/tensorrt_yolo/lib/include/trt_yolo.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@
#include <opencv2/core/core.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/opencv.hpp>
#include <tensorrt_common/logger.hpp>
#include <yolo_layer.hpp>

#include <NvInfer.h>
Expand All @@ -67,22 +68,6 @@ struct Deleter
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};
};

struct Config
{
int num_anchors;
Expand All @@ -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<std::string> & 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();
Expand Down Expand Up @@ -138,6 +123,7 @@ class Net
cuda::unique_ptr<float[]> out_scores_d_ = nullptr;
cuda::unique_ptr<float[]> out_boxes_d_ = nullptr;
cuda::unique_ptr<float[]> out_classes_d_ = nullptr;
tensorrt_common::Logger logger_;

void load(const std::string & path);
bool prepare();
Expand Down
Loading
Loading