Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
tutorial-dnn-tensorrt-live.cpp
1 // This tutorial uses NVIDIA TensorRT inference framework to perform object detection.
2 // The object detection model is provided as a `.onnx` file. The model will be parsed
3 // and a GPU Inference Engine (GIE) will be created if it doesn't exist. This GIE is
4 // specific to the platform you're using.
5 //
6 // This tutorial was tested on NVIDIA Jetson TX2.
7 //
8 // The object detection model used is `SSD_Mobilenet V1` (Single Shot MultiBox Detector)
9 // pre-trained on PASCAL VOC dataset. It can detect 20 classes.
10 // For more information about the model, see this link:
11 //
12 // https://github.com/qfgaohao/pytorch-ssd
13 //
14 
15 #include <iostream>
16 #include <visp3/core/vpConfig.h>
17 
18 #if defined(VISP_HAVE_TENSORRT) && defined(VISP_HAVE_OPENCV)
19 
20 #if defined(HAVE_OPENCV_CUDEV) && defined(HAVE_OPENCV_CUDAWARPING) && defined(HAVE_OPENCV_CUDAARITHM) && \
21  defined(HAVE_OPENCV_DNN) && defined(HAVE_OPENCV_VIDEOIO)
22 #include <visp3/core/vpImageConvert.h>
23 #include <visp3/core/vpIoTools.h>
24 #include <visp3/gui/vpDisplayX.h>
25 
26 #include <opencv2/videoio.hpp>
27 
29 #include <opencv2/core/cuda.hpp>
30 #include <opencv2/cudaarithm.hpp>
31 #include <opencv2/cudawarping.hpp>
32 #include <opencv2/dnn.hpp>
34 
36 #include <cuda_runtime_api.h>
38 
40 #include <NvInfer.h>
41 #include <NvOnnxParser.h>
43 
44 #include <sys/stat.h>
45 
46 #ifdef ENABLE_VISP_NAMESPACE
47 using namespace VISP_NAMESPACE_NAME;
48 #endif
49 
51 void preprocessImage(cv::Mat &img, float *gpu_input, const nvinfer1::Dims &dims, float meanR, float meanG, float meanB)
52 {
53  if (img.empty()) {
54  std::cerr << "Image is empty." << std::endl;
55  return;
56  }
57 
58  cv::cuda::GpuMat gpu_frame;
59  // Upload image to GPU
60  gpu_frame.upload(img);
61 
62  // input_dims is in NxCxHxW format.
63  auto input_width = dims.d[3];
64  auto input_height = dims.d[2];
65  auto channels = dims.d[1];
66  auto input_size = cv::Size(input_width, input_height);
67 
68  // Resize
69  cv::cuda::GpuMat resized;
70  cv::cuda::resize(gpu_frame, resized, input_size, 0, 0, cv::INTER_NEAREST);
71 
72  // Normalize
73  cv::cuda::GpuMat flt_image;
74  resized.convertTo(flt_image, CV_32FC3);
75  cv::cuda::subtract(flt_image, cv::Scalar(meanR, meanG, meanB), flt_image, cv::noArray(), -1);
76  cv::cuda::divide(flt_image, cv::Scalar(127.5f, 127.5f, 127.5f), flt_image, 1, -1);
77 
78  // To tensor
79  std::vector<cv::cuda::GpuMat> chw;
80  for (int i = 0; i < channels; ++i)
81  chw.emplace_back(cv::cuda::GpuMat(input_size, CV_32FC1, gpu_input + i * input_width * input_height));
82  cv::cuda::split(flt_image, chw);
83 }
85 
87 size_t getSizeByDim(const nvinfer1::Dims &dims)
88 {
89  size_t size = 1;
90  for (int i = 0; i < dims.nbDims; ++i)
91  size *= dims.d[i];
92  return size;
93 }
95 
97 std::vector<cv::Rect> postprocessResults(std::vector<void *> buffers, const std::vector<nvinfer1::Dims> &output_dims,
98  int batch_size, int image_width, int image_height, float confThresh,
99  float nmsThresh, std::vector<int> &classIds)
100 {
101  // private variables of vpDetectorDNN
102  std::vector<cv::Rect> m_boxes, m_boxesNMS;
103  std::vector<int> m_classIds;
104  std::vector<float> m_confidences;
105  std::vector<int> m_indices;
106 
107  // copy results from GPU to CPU
108  std::vector<std::vector<float> > cpu_outputs;
109  for (size_t i = 0; i < output_dims.size(); i++) {
110  cpu_outputs.push_back(std::vector<float>(getSizeByDim(output_dims[i]) * batch_size));
111  cudaMemcpy(cpu_outputs[i].data(), (float *)buffers[1 + i], cpu_outputs[i].size() * sizeof(float),
112  cudaMemcpyDeviceToHost);
113  }
114 
115  // post process
116  int N = output_dims[0].d[1], C = output_dims[0].d[2]; // (1 x N x C format); N: Number of output detection boxes
117  // (fixed in the model), C: Number of classes.
118  for (int i = 0; i < N; i++) // for all N (boxes)
119  {
120  uint32_t maxClass = 0;
121  float maxScore = -1000.0f;
122 
123  for (int j = 1; j < C; j++) // ignore background (classId = 0).
124  {
125  const float score = cpu_outputs[0][i * C + j];
126 
127  if (score < confThresh)
128  continue;
129 
130  if (score > maxScore) {
131  maxScore = score;
132  maxClass = j;
133  }
134  }
135 
136  if (maxScore > confThresh) {
137  int left = (int)(cpu_outputs[1][4 * i] * image_width);
138  int top = (int)(cpu_outputs[1][4 * i + 1] * image_height);
139  int right = (int)(cpu_outputs[1][4 * i + 2] * image_width);
140  int bottom = (int)(cpu_outputs[1][4 * i + 3] * image_height);
141  int width = right - left + 1;
142  int height = bottom - top + 1;
143 
144  m_boxes.push_back(cv::Rect(left, top, width, height));
145  m_classIds.push_back(maxClass);
146  m_confidences.push_back(maxScore);
147  }
148  }
149 
150  cv::dnn::NMSBoxes(m_boxes, m_confidences, confThresh, nmsThresh, m_indices);
151  m_boxesNMS.resize(m_indices.size());
152  for (size_t i = 0; i < m_indices.size(); ++i) {
153  int idx = m_indices[i];
154  m_boxesNMS[i] = m_boxes[idx];
155  }
156 
157  classIds = m_classIds; // Returning detected objects class Ids.
158  return m_boxesNMS;
159 }
161 
162 class Logger : public nvinfer1::ILogger
163 {
164 public:
165  void log(Severity severity, const char *msg) noexcept // override
166  {
167  if ((severity == Severity::kERROR) || (severity == Severity::kINTERNAL_ERROR) || (severity == Severity::kVERBOSE))
168  std::cout << msg << std::endl;
169  }
170 } gLogger;
171 
172 // destroy TensoRT objects if something goes wrong
173 struct TRTDestroy
174 {
175  template <class T> void operator()(T *obj) const
176  {
177  if (obj)
178  obj->destroy();
179  }
180 };
181 
182 template <class T> using TRTUniquePtr = std::unique_ptr<T, TRTDestroy>;
183 
185 bool parseOnnxModel(const std::string &model_path, TRTUniquePtr<nvinfer1::ICudaEngine> &engine,
186  TRTUniquePtr<nvinfer1::IExecutionContext> &context)
188 {
189  // this section of code is from jetson-inference's `tensorNet`, to test if the GIE already exists.
190  char cache_prefix[FILENAME_MAX];
191  char cache_path[FILENAME_MAX];
192 
193  snprintf(cache_prefix, FILENAME_MAX, "%s", model_path.c_str());
194  snprintf(cache_path, FILENAME_MAX, "%s.engine", cache_prefix);
195 
196  std::cout << "attempting to open engine cache file " << cache_path << std::endl;
197 
199  if (vpIoTools::checkFilename(cache_path)) {
200  char *engineStream = nullptr;
201  size_t engineSize = 0;
202 
203  // determine the file size of the engine
204  struct stat filestat;
205  stat(cache_path, &filestat);
206  engineSize = filestat.st_size;
207 
208  // allocate memory to hold the engine
209  engineStream = (char *)malloc(engineSize);
210 
211  // open the engine cache file from disk
212  FILE *cacheFile = nullptr;
213  cacheFile = fopen(cache_path, "rb");
214 
215  // read the serialized engine into memory
216  const size_t bytesRead = fread(engineStream, 1, engineSize, cacheFile);
217 
218  if (bytesRead != engineSize) // Problem while deserializing.
219  {
220  std::cerr << "Error reading serialized engine into memory." << std::endl;
221  return false;
222  }
223 
224  // close the plan cache
225  fclose(cacheFile);
226 
227  // Recreate the inference runtime
228  TRTUniquePtr<nvinfer1::IRuntime> infer { nvinfer1::createInferRuntime(gLogger) };
229  engine.reset(infer->deserializeCudaEngine(engineStream, engineSize, nullptr));
230  context.reset(engine->createExecutionContext());
231 
232  return true;
233  }
235 
237  else {
238  if (!vpIoTools::checkFilename(model_path)) {
239  std::cerr << "Could not parse ONNX model. File not found" << std::endl;
240  return false;
241  }
242 
243  TRTUniquePtr<nvinfer1::IBuilder> builder { nvinfer1::createInferBuilder(gLogger) };
244  TRTUniquePtr<nvinfer1::INetworkDefinition> network {
245  builder->createNetworkV2(1U << (uint32_t)nvinfer1::NetworkDefinitionCreationFlag::kEXPLICIT_BATCH) };
246  TRTUniquePtr<nvonnxparser::IParser> parser { nvonnxparser::createParser(*network, gLogger) };
247 
248  // parse ONNX
249  if (!parser->parseFromFile(model_path.c_str(), static_cast<int>(nvinfer1::ILogger::Severity::kINFO))) {
250  std::cerr << "ERROR: could not parse the model." << std::endl;
251  return false;
252  }
253 
254  TRTUniquePtr<nvinfer1::IBuilderConfig> config { builder->createBuilderConfig() };
255  // allow TRT to use up to 1GB of GPU memory for tactic selection
256  config->setMaxWorkspaceSize(32 << 20);
257  // use FP16 mode if possible
258  if (builder->platformHasFastFp16()) {
259  config->setFlag(nvinfer1::BuilderFlag::kFP16);
260  }
261 
262  builder->setMaxBatchSize(1);
263 
264  engine.reset(builder->buildEngineWithConfig(*network, *config));
265  context.reset(engine->createExecutionContext());
266 
267  TRTUniquePtr<nvinfer1::IHostMemory> serMem { engine->serialize() };
268 
269  if (!serMem) {
270  std::cout << "Failed to serialize CUDA engine." << std::endl;
271  return false;
272  }
273 
274  const char *serData = (char *)serMem->data();
275  const size_t serSize = serMem->size();
276 
277  // allocate memory to store the bitstream
278  char *engineMemory = (char *)malloc(serSize);
279 
280  if (!engineMemory) {
281  std::cout << "Failed to allocate memory to store CUDA engine." << std::endl;
282  return false;
283  }
284 
285  memcpy(engineMemory, serData, serSize);
286 
287  // write the cache file
288  FILE *cacheFile = nullptr;
289  cacheFile = fopen(cache_path, "wb");
290 
291  fwrite(engineMemory, 1, serSize, cacheFile);
292  fclose(cacheFile);
293 
294  return true;
295  }
297 }
298 
299 int main(int argc, char **argv)
300 {
301  int opt_device = 0;
302  unsigned int opt_scale = 1;
303  std::string input = "";
304  std::string modelFile = vpIoTools::getViSPImagesDataPath() + "/dnn/object_detection/ssd-mobilenet.onnx";
305  std::string labelFile = vpIoTools::getViSPImagesDataPath() + "/dnn/object_detection/pascal-voc-labels.txt";
306  std::string config = "";
307  float meanR = 127.5f, meanG = 127.5f, meanB = 127.5f;
308  float confThresh = 0.5f;
309  float nmsThresh = 0.4f;
310 
311  for (int i = 1; i < argc; i++) {
312  if (std::string(argv[i]) == "--device" && i + 1 < argc) {
313  opt_device = atoi(argv[i + 1]);
314  }
315  else if (std::string(argv[i]) == "--input" && i + 1 < argc) {
316  input = std::string(argv[i + 1]);
317  }
318  else if (std::string(argv[i]) == "--model" && i + 1 < argc) {
319  modelFile = std::string(argv[i + 1]);
320  }
321  else if (std::string(argv[i]) == "--config" && i + 1 < argc) {
322  config = std::string(argv[i + 1]);
323  }
324  else if (std::string(argv[i]) == "--input-scale" && i + 1 < argc) {
325  opt_scale = atoi(argv[i + 1]);
326  }
327  else if (std::string(argv[i]) == "--mean" && i + 3 < argc) {
328  meanR = atof(argv[i + 1]);
329  meanG = atof(argv[i + 2]);
330  meanB = atof(argv[i + 3]);
331  }
332  else if (std::string(argv[i]) == "--confThresh" && i + 1 < argc) {
333  confThresh = (float)atof(argv[i + 1]);
334  }
335  else if (std::string(argv[i]) == "--nmsThresh" && i + 1 < argc) {
336  nmsThresh = (float)atof(argv[i + 1]);
337  }
338  else if (std::string(argv[i]) == "--labels" && i + 1 < argc) {
339  labelFile = std::string(argv[i + 1]);
340  }
341  else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
342  std::cout << argv[0]
343  << " [--device <camera device number>] [--input <path to image or video>"
344  " (camera is used if input is empty)] [--model <path to net trained weights>]"
345  " [--config <path to net config file>]"
346  " [--input-scale <input scale factor>] [--mean <meanR meanG meanB>]"
347  " [--confThresh <confidence threshold>]"
348  " [--nmsThresh <NMS threshold>] [--labels <path to label file>]"
349  << std::endl;
350  return EXIT_SUCCESS;
351  }
352  }
353 
354  std::string model_path(modelFile);
355  int batch_size = 1;
356 
357  std::vector<std::string> labels;
358  if (!labelFile.empty()) {
359  std::ifstream f_label(labelFile);
360  std::string line;
361  while (std::getline(f_label, line)) {
362  labels.push_back(line);
363  }
364  }
365 
367  // Parse the model and initialize the engine and the context.
368  TRTUniquePtr<nvinfer1::ICudaEngine> engine { nullptr };
369  TRTUniquePtr<nvinfer1::IExecutionContext> context { nullptr };
370  if (!parseOnnxModel(model_path, engine, context)) // Problem parsing Onnx model
371  {
372  std::cout << "Make sure the model file exists. To see available models, plese visit: "
373  "\n\twww.github.com/lagadic/visp-images/dnn/object_detection/"
374  << std::endl;
375  return EXIT_FAILURE;
376  }
378 
379  std::vector<nvinfer1::Dims> input_dims;
380  std::vector<nvinfer1::Dims> output_dims;
381  std::vector<void *> buffers(engine->getNbBindings()); // buffers for input and output data.
382 
384  for (int i = 0; i < engine->getNbBindings(); ++i) {
385  auto binding_size = getSizeByDim(engine->getBindingDimensions(i)) * batch_size * sizeof(float);
386  cudaMalloc(&buffers[i], binding_size);
387 
388  if (engine->bindingIsInput(i)) {
389  input_dims.emplace_back(engine->getBindingDimensions(i));
390  }
391  else {
392  output_dims.emplace_back(engine->getBindingDimensions(i));
393  }
394  }
395 
396  if (input_dims.empty() || output_dims.empty()) {
397  std::cerr << "Expect at least one input and one output for network" << std::endl;
398  return EXIT_FAILURE;
399  }
401 
403  cv::VideoCapture capture;
404 
405  if (input.empty()) {
406  capture.open(opt_device);
407  }
408  else {
409  capture.open(input);
410  }
411 
412  if (!capture.isOpened()) { // check if we succeeded
413  std::cout << "Failed to open the camera" << std::endl;
414  return EXIT_FAILURE;
415  }
416 
417  int cap_width = (int)capture.get(cv::CAP_PROP_FRAME_WIDTH);
418  int cap_height = (int)capture.get(cv::CAP_PROP_FRAME_HEIGHT);
419  capture.set(cv::CAP_PROP_FRAME_WIDTH, cap_width / opt_scale);
420  capture.set(cv::CAP_PROP_FRAME_HEIGHT, cap_height / opt_scale);
422 
423  vpImage<vpRGBa> I;
424  cv::Mat frame;
425  capture >> frame;
426 
427  if (input.empty()) {
428  int i = 0;
429  while ((i++ < 20) && !capture.read(frame)) {
430  }; // warm up camera by skiping unread frames
431  }
432 
433  vpImageConvert::convert(frame, I);
434  int height = I.getHeight(), width = I.getWidth();
435 
436  std::cout << "Image size: " << width << " x " << height << std::endl;
437 
438  std::vector<cv::Rect> boxesNMS;
439  std::vector<int> classIds;
440 
441  vpDisplayX d(I);
442 
443  double start, stop;
445  while (!vpDisplay::getClick(I, false)) {
446  // get frame.
447  capture >> frame;
448 
449  vpImageConvert::convert(frame, I);
450 
451  start = vpTime::measureTimeMs();
452  // preprocess
453  preprocessImage(frame, (float *)buffers[0], input_dims[0], meanR, meanG, meanB);
454 
455  // inference.
456  context->enqueue(batch_size, buffers.data(), 0, nullptr);
457 
458  // post-process
459  boxesNMS = postprocessResults(buffers, output_dims, batch_size, width, height, confThresh, nmsThresh, classIds);
460 
461  stop = vpTime::measureTimeMs();
462  // display.
464  vpDisplay::displayText(I, 10, 10, std::to_string(stop - start), vpColor::red);
465 
466  for (unsigned int i = 0; i < boxesNMS.size(); i++) {
467  vpDisplay::displayRectangle(I, vpRect(boxesNMS[i].x, boxesNMS[i].y, boxesNMS[i].width, boxesNMS[i].height),
468  vpColor::red, false, 2);
469  vpDisplay::displayText(I, boxesNMS[i].y - 10, boxesNMS[i].x, labels[classIds[i]], vpColor::red);
470  }
471 
472  vpDisplay::flush(I);
473  }
475 
476  for (void *buf : buffers)
477  cudaFree(buf);
478 
479  return EXIT_SUCCESS;
480 }
481 #else
482 int main()
483 {
484  std::cout << "OpenCV is not built with CUDA." << std::endl;
485 
486  return EXIT_SUCCESS;
487 }
488 #endif
489 
490 #else
491 int main()
492 {
493  std::cout << "ViSP is not built with TensorRT." << std::endl;
494 
495  return EXIT_SUCCESS;
496 }
497 #endif
static const vpColor red
Definition: vpColor.h:217
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void flush(const vpImage< unsigned char > &I)
static void displayRectangle(const vpImage< unsigned char > &I, const vpImagePoint &topLeft, unsigned int width, unsigned int height, const vpColor &color, bool fill=false, unsigned int thickness=1)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getHeight() const
Definition: vpImage.h:181
static std::string getViSPImagesDataPath()
Definition: vpIoTools.cpp:1053
static bool checkFilename(const std::string &filename)
Definition: vpIoTools.cpp:786
Defines a rectangle in the plane.
Definition: vpRect.h:79
VISP_EXPORT double measureTimeMs()