Visual Servoing Platform  version 3.6.1 under development (2024-11-15)
Tutorial: Deep learning object detection

Introduction

This tutorial shows how to use the vpDetectorDNNOpenCV class (DNN stands for Deep Neural Network), which is a wrapper over the OpenCV DNN module. The vpDetectorDNNOpenCV class provides convenient ways to perform image classification and to retrieve detection bounding boxes, class ids and confidence values of a single or of multiple classes. For other tasks such as image segmentation or more complicated uses, you should use directly the OpenCV DNN API.

This class supports Faster-RCNN, SSD-MobileNet, ResNet 10, Yolo v3, Yolo v4, Yolo v5, Yolo v7, Yolo v8 and Yolo v11 convolutional networks that simultaneously predict object boundaries and prediction scores at each position. If you want to use another type of network, you can define your own parsing method of the DNN detection results and give it to the vpDetectorDNNOpenCV object.

This class can be initialized from a JSON file if ViSP has been compiled with NLOHMANN JSON (see JSON for modern C++ to see how to do it). Examples of such JSON files can be found in the tutorial folder.

In the next section you will find an example that shows how to perform face detection in a single image or in images acquired from a camera connected to your computer.

Note that all the material (source code and network model) described in this tutorial is part of ViSP source code (in tutorial/detection/dnn folder) and could be found in https://github.com/lagadic/visp/tree/master/tutorial/detection/dnn.

Requirements

To enable vpDetectorDNNOpenCV class usage, and thus use this tutorial, you need to have a version of ViSP build with OpenCV. If you have a GPU, we recommend you to refer to the Build OpenCV with GPU acceleration section. Otherwise, you can refer to the Install OpenCV from package section.

Build OpenCV with GPU acceleration

OpenCV can be built with GPU acceleration thanks to the Cuda and CuDNN libraries.

  1. First you need to install the Cuda library following the official documentation.
  2. Then, you need to install the CuDNN library following the official documentation. Please ensure to install a CuDNN version that is compatible with your version of Cuda.
  3. Then, you need to determine the Compute capability of your GPU either from the NVidia website or using the nvidia-smi tool. On a Debian distribution, you would run:
    $ export GPU_CAPABILITIES=$(nvidia-smi --query-gpu=compute_cap --format=csv,noheader)
  4. Check if the package already installed on your computer. On a Debian distribution, you would run:

    $ apt list --installed | grep -i opencv

    If this command does not return an empty line, please run (if you are sure that it is not required by another software installed on your computer):

    $ sudo apt remove libopencv-dev
  5. Install OpenCV dependencies. On a Debian distribution, you would run:
    # libx11-dev is a recommended ViSP 3rd parties
    # If you installed another version of CUDA, please install the version of CuDNN which is compatible with your version
    $ sudo apt update
    $ sudo apt install libgtk-3-dev \
    cmake \
    git \
    pip \
    cmake-curses-gui \
    locate \
    libx11-dev
  6. Get the sources. The vpDetectorDNNOpenCV has been tested with OpenCV 4.7 and OpenCV 4.10. First, get the OpenCV_contrib sources, that contain the Cuda DNN module. On a Debian distribution, you would run:
    $ cd ${HOME}/visp_ws/3rdparty/
    $ git clone --branch 4.10.0 https://github.com/opencv/opencv_contrib
    $ git clone --branch 4.10.0 https://github.com/opencv/opencv
  7. Compile OpenCV and install it from source. On a Debian distribution, you would run:
    $ mkdir -p ${HOME}/visp_ws/3rdparty/opencv/build && cd ${HOME}/visp_ws/3rdparty/opencv/build
    $ cmake .. \
    -DCMAKE_BUILD_TYPE=RELEASE \
    -DCMAKE_INSTALL_PREFIX=/usr \
    -DCMAKE_INSTALL_LIBDIR=lib \
    -DWITH_CUDA=ON \
    -DWITH_CUDNN=ON \
    -DOPENCV_DNN_CUDA=ON \
    -DENABLE_FAST_MATH=1 \
    -DCUDA_FAST_MATH=1 \
    -DCUDA_ARCH_BIN=${GPU_CAPABILITIES} \
    -DWITH_CUBLAS=1 \
    -DOPENCV_EXTRA_MODULES_PATH=${HOME}/visp_ws/3rdparty/opencv_contrib/modules \
    -DBUILD_PERF_TESTS=Off \
    -DBUILD_TESTS=Off \
    -DBUILD_EXAMPLES=Off \
    -DBUILD_opencv_apps=Off \
    -DBUILD_opencv_java_bindings_generator=Off \
    -DBUILD_opencv_js=Off
  8. Compile and install OpenCV. On a Debian distribution, you would run:
    $ make -j$(nproc)
    $ sudo make install
  9. When using the vpDetectorDNNOpenCV class, please first call the methods vpDetectorDNNOpenCV::setPreferableBackend() and vpDetectorDNNOpenCV::setPreferableTarget() before running the inference if you want to benefit from GPU acceleration:
    vpDetectorDNNOpenCV::NetConfig my_config;
    // Set my_config to match your needs
    vpDetectorDNNOpenCV::DNNResultsParsingType parsingType = USER_SPECIFIED;
    // Either define your parsing method or change the parsing type for one that is supported
    void (*dummyParsingMethod)(DetectionCandidates &, std::vector<cv::Mat> &, const NetConfig &) =
    [](DetectionCandidates &, std::vector<cv::Mat> &, const NetConfig &)
    {
    std::cout << "Hello world" << std::endl;
    };
    vpDetectorDNNOpenCV network(my_config, dummyParsingMethod);
    // Here are the important calls to use GPU acceleration
    network.setPreferableBackend(cv::dnn::DNN_BACKEND_CUDA);
    network.setPreferableTarget(cv::dnn::DNN_TARGET_CUDA);

Install OpenCV from package

Please follow the instuctions described in the installation guidelines for OpenCV .

Object detection example explained

The following example also available in tutorial-dnn-object-detection-live.cpp allows object detection by making inference on DNN models learned from the following networks:

  • Faster-RCNN
  • SSD MobileNet
  • ResNet 10
  • Yolo v3
  • Yolo v4
  • Yolo v5
  • Yolo v7
  • Yolo v8
  • Yolo v11

It uses video capture capability from OpenCV to capture images from a camera and detect objects using a DNN model learned using one of the previous networks.

#include <visp3/core/vpConfig.h>
#include <visp3/core/vpIoTools.h>
#include <visp3/detection/vpDetectorDNNOpenCV.h>
#include <visp3/gui/vpDisplayGDI.h>
#include <visp3/gui/vpDisplayOpenCV.h>
#include <visp3/gui/vpDisplayX.h>
#if defined(HAVE_OPENCV_VIDEOIO)
#include <opencv2/videoio.hpp>
#endif
#ifdef VISP_HAVE_NLOHMANN_JSON
#include VISP_NLOHMANN_JSON(json.hpp)
using json = nlohmann::json;
#endif
#ifdef ENABLE_VISP_NAMESPACE
using namespace VISP_NAMESPACE_NAME;
#endif
typedef enum
{
DETECTION_CONTAINER_MAP = 0,
DETECTION_CONTAINER_VECTOR = 1,
DETECTION_CONTAINER_BOTH = 2,
DETECTION_CONTAINER_COUNT = 3
} ChosenDetectionContainer;
std::string chosenDetectionContainerToString(const ChosenDetectionContainer &choice)
{
switch (choice) {
case DETECTION_CONTAINER_MAP:
return "map";
case DETECTION_CONTAINER_VECTOR:
return "vector";
case DETECTION_CONTAINER_BOTH:
return "both";
default:
break;
}
return "unknown";
}
ChosenDetectionContainer chosenDetectionContainerFromString(const std::string &choiceStr)
{
ChosenDetectionContainer choice(DETECTION_CONTAINER_COUNT);
bool hasFoundMatch = false;
for (unsigned int i = 0; i < DETECTION_CONTAINER_COUNT && !hasFoundMatch; i++) {
ChosenDetectionContainer candidate = (ChosenDetectionContainer)i;
hasFoundMatch = (chosenDetectionContainerToString(candidate) == vpIoTools::toLowerCase(choiceStr));
if (hasFoundMatch) {
choice = candidate;
}
}
return choice;
}
std::string getAvailableDetectionContainer()
{
std::string availableContainers("< ");
for (unsigned int i = 0; i < DETECTION_CONTAINER_COUNT - 1; i++) {
std::string name = chosenDetectionContainerToString((ChosenDetectionContainer)i);
availableContainers += name + " , ";
}
availableContainers +=
chosenDetectionContainerToString((ChosenDetectionContainer)(DETECTION_CONTAINER_COUNT - 1)) + " >";
return availableContainers;
}
int main(int argc, const char *argv[])
{
// Check if std:c++17 or higher
#if defined(HAVE_OPENCV_DNN) && defined(HAVE_OPENCV_VIDEOIO) && \
((__cplusplus >= 201703L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201703L)))
try {
std::string opt_device("0");
std::string opt_dnn_model = "opencv_face_detector_uint8.pb";
std::string opt_dnn_config = "opencv_face_detector.pbtxt";
std::string opt_dnn_framework = "none";
std::string opt_dnn_label_file = "";
vpDetectorDNNOpenCV::DNNResultsParsingType opt_dnn_type = vpDetectorDNNOpenCV::RESNET_10;
int opt_dnn_width = 300, opt_dnn_height = 300;
double opt_dnn_meanR = 104.0, opt_dnn_meanG = 177.0, opt_dnn_meanB = 123.0;
double opt_dnn_scale_factor = 1.0;
bool opt_dnn_swapRB = false;
bool opt_step_by_step = false;
float opt_dnn_confThresh = 0.5f;
float opt_dnn_nmsThresh = 0.4f;
double opt_dnn_filterThresh = 0.25;
ChosenDetectionContainer opt_dnn_containerType = DETECTION_CONTAINER_MAP;
bool opt_verbose = false;
std::string opt_input_json = "";
std::string opt_output_json = "";
for (int i = 1; i < argc; i++) {
if (std::string(argv[i]) == "--device" && i + 1 < argc) {
opt_device = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--step-by-step") {
opt_step_by_step = true;
}
else if (std::string(argv[i]) == "--model" && i + 1 < argc) {
opt_dnn_model = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--type" && i + 1 < argc) {
opt_dnn_type = vpDetectorDNNOpenCV::dnnResultsParsingTypeFromString(std::string(argv[++i]));
}
else if (std::string(argv[i]) == "--config" && i + 1 < argc) {
opt_dnn_config = std::string(argv[++i]);
if (opt_dnn_config.find("none") != std::string::npos) {
opt_dnn_config = std::string();
}
}
else if (std::string(argv[i]) == "--framework" && i + 1 < argc) {
opt_dnn_framework = std::string(argv[++i]);
if (opt_dnn_framework.find("none") != std::string::npos) {
opt_dnn_framework = std::string();
}
}
else if (std::string(argv[i]) == "--width" && i + 1 < argc) {
opt_dnn_width = atoi(argv[++i]);
}
else if (std::string(argv[i]) == "--height" && i + 1 < argc) {
opt_dnn_height = atoi(argv[++i]);
}
else if (std::string(argv[i]) == "--mean" && i + 3 < argc) {
opt_dnn_meanR = atof(argv[++i]);
opt_dnn_meanG = atof(argv[++i]);
opt_dnn_meanB = atof(argv[++i]);
}
else if (std::string(argv[i]) == "--scale" && i + 1 < argc) {
opt_dnn_scale_factor = atof(argv[++i]);
}
else if (std::string(argv[i]) == "--swapRB") {
opt_dnn_swapRB = true;
}
else if (std::string(argv[i]) == "--confThresh" && i + 1 < argc) {
opt_dnn_confThresh = (float)atof(argv[++i]);
}
else if (std::string(argv[i]) == "--nmsThresh" && i + 1 < argc) {
opt_dnn_nmsThresh = (float)atof(argv[++i]);
}
else if (std::string(argv[i]) == "--filterThresh" && i + 1 < argc) {
opt_dnn_filterThresh = atof(argv[++i]);
}
else if (std::string(argv[i]) == "--labels" && i + 1 < argc) {
opt_dnn_label_file = std::string(argv[++i]);
}
else if (std::string(argv[i]) == "--container" && i + 1 < argc) {
opt_dnn_containerType = chosenDetectionContainerFromString(std::string(argv[++i]));
}
else if (std::string(argv[i]) == "--input-json" && i + 1 < argc) {
opt_input_json = std::string(std::string(argv[++i]));
}
else if (std::string(argv[i]) == "--output-json" && i + 1 < argc) {
opt_output_json = std::string(std::string(argv[++i]));
}
else if (std::string(argv[i]) == "--verbose" || std::string(argv[i]) == "-v") {
opt_verbose = true;
}
else if (std::string(argv[i]) == "--help" || std::string(argv[i]) == "-h") {
std::cout << "\nSYNOPSIS " << std::endl
<< argv[0] << " [--device <video>]"
<< " [--model <dnn weights file>]"
<< " [--type <dnn type>]"
<< " [--config <dnn config file]"
<< " [--framework <name>]"
<< " [--width <blob width>] [--height <blob height>]"
<< " [--mean <meanR meanG meanB>]"
<< " [--scale <scale factor>]"
<< " [--swapRB]"
<< " [--confThresh <threshold>]"
<< " [--nmsThresh <threshold>]"
<< " [--filterThresh <threshold>]"
<< " [--labels <file>]"
<< " [--container <type>]"
<< " [--input-json <path_to_input_json>]"
<< " [--output-json <path_to_output_json>]"
<< " [--step-by-step]"
<< " [--verbose, -v]"
<< " [--help, -h]" << std::endl;
std::cout << "\nOPTIONS " << std::endl
<< " --device <video>" << std::endl
<< " Camera device number or video name used to stream images." << std::endl
<< " To use the first camera found on the bus set 0. On Ubuntu setting 0" << std::endl
<< " will use /dev/video0 device. To use a video simply put the name of" << std::endl
<< " the video, like \"path/my-video.mp4\" or \"path/image-%04d.png\"" << std::endl
<< " if your video is a sequence of images." << std::endl
<< " Default: " << opt_device << std::endl
<< std::endl
<< " --model <dnn weights file>" << std::endl
<< " Path to dnn network trained weights." << std::endl
<< " Default: " << opt_dnn_model << std::endl
<< std::endl
<< " --type <dnn type>" << std::endl
<< " Type of dnn network. Admissible values are in " << std::endl
<< " " << vpDetectorDNNOpenCV::getAvailableDnnResultsParsingTypes() << std::endl
<< " Default: " << opt_dnn_type << std::endl
<< std::endl
<< " --config <dnn config file>" << std::endl
<< " Path to dnn network config file or \"none\" not to use one. " << std::endl
<< " Default: " << opt_dnn_config << std::endl
<< std::endl
<< " --framework <name>" << std::endl
<< " Framework name or \"none\" not to specify one. " << std::endl
<< " Default: " << opt_dnn_framework << std::endl
<< std::endl
<< " --width <blob width>" << std::endl
<< " Input images will be resized to this width. " << std::endl
<< " Default: " << opt_dnn_width << std::endl
<< std::endl
<< " --height <blob height>" << std::endl
<< " Input images will be resized to this height. " << std::endl
<< " Default: " << opt_dnn_height << std::endl
<< std::endl
<< " --mean <meanR meanG meanB>" << std::endl
<< " Mean RGB subtraction values. " << std::endl
<< " Default: " << opt_dnn_meanR << " " << opt_dnn_meanG << " " << opt_dnn_meanB << std::endl
<< std::endl
<< " --scale <scale factor>" << std::endl
<< " Scale factor used to normalize the range of pixel values. " << std::endl
<< " Default: " << opt_dnn_scale_factor << std::endl
<< std::endl
<< " --swapRB" << std::endl
<< " When used this option allows to swap Red and Blue channels. " << std::endl
<< std::endl
<< " --confThresh <threshold>" << std::endl
<< " Confidence threshold. " << std::endl
<< " Default: " << opt_dnn_confThresh << std::endl
<< std::endl
<< " --nmsThresh <threshold>" << std::endl
<< " Non maximum suppression threshold. " << std::endl
<< " Default: " << opt_dnn_nmsThresh << std::endl
<< std::endl
<< " --filterThresh <threshold >" << std::endl
<< " Filter threshold. Set 0. to disable." << std::endl
<< " Default: " << opt_dnn_filterThresh << std::endl
<< std::endl
<< " --labels <file>" << std::endl
<< " Path to label file either in txt or yaml format. Keep empty if unknown." << std::endl
<< " Default: \"" << opt_dnn_label_file << "\"" << std::endl
<< std::endl
<< " --container <type>" << std::endl
<< " Container type in " << getAvailableDetectionContainer() << std::endl
<< " Default: " << chosenDetectionContainerToString(opt_dnn_containerType) << std::endl
<< std::endl
<< " --input-json <path_to_input_json>" << std::endl
<< " Input JSON file used to configure the DNN. If set, the other arguments will be used to override the values set in the json file." << std::endl
<< " Default: empty" << std::endl
<< std::endl
<< " --output-json <type>" << std::endl
<< " Output JSON file where will be saved the DNN configuration. If empty, does not save the configuration." << std::endl
<< " Default: empty" << std::endl
<< std::endl
<< " --step-by-step" << std::endl
<< " Enable step by step mode, waiting for a user click to process next image." << std::endl
<< std::endl
<< " --verbose, -v" << std::endl
<< " Enable verbose mode." << std::endl
<< std::endl
<< " --help, -h" << std::endl
<< " Display this helper message." << std::endl
<< std::endl;
return EXIT_SUCCESS;
}
}
std::cout << "Video device : " << opt_device << std::endl;
std::cout << "Label file (optional): " << (opt_dnn_label_file.empty() ? "None" : opt_dnn_label_file) << std::endl;
cv::VideoCapture capture;
bool hasCaptureOpeningSucceeded;
if (vpMath::isNumber(opt_device)) {
hasCaptureOpeningSucceeded = capture.open(std::atoi(opt_device.c_str()));
}
else {
hasCaptureOpeningSucceeded = capture.open(opt_device);
}
if (!hasCaptureOpeningSucceeded) {
std::cout << "Capture from camera: " << opt_device << " didn't work" << std::endl;
return EXIT_FAILURE;
}
#if defined(VISP_HAVE_X11)
vpDisplayX d;
#elif defined(VISP_HAVE_GDI)
#elif defined(HAVE_OPENCV_HIGHGUI)
#endif
if (!opt_dnn_label_file.empty() && !vpIoTools::checkFilename(opt_dnn_label_file)) {
"The file containing the classes labels \"" + opt_dnn_label_file + "\" does not exist !"));
}
vpDetectorDNNOpenCV dnn;
#ifdef VISP_HAVE_NLOHMANN_JSON
if (!opt_input_json.empty()) {
dnn.initFromJSON(opt_input_json);
}
#else
if (!opt_input_json.empty()) {
std::cerr << "Error: NLOHMANN JSON library is not installed, please install it following ViSP documentation to configure the vpDetectorDNNOpenCV from a JSON file." << std::endl;
return EXIT_FAILURE;
}
#endif
else {
vpDetectorDNNOpenCV::NetConfig netConfig(opt_dnn_confThresh, opt_dnn_nmsThresh, opt_dnn_label_file
, cv::Size(opt_dnn_width, opt_dnn_height), opt_dnn_filterThresh, cv::Scalar(opt_dnn_meanR, opt_dnn_meanG, opt_dnn_meanB)
, opt_dnn_scale_factor, opt_dnn_swapRB, opt_dnn_type
, opt_dnn_model, opt_dnn_config, opt_dnn_framework
);
dnn.setNetConfig(netConfig);
}
std::cout << dnn.getNetConfig() << std::endl;
#ifdef VISP_HAVE_NLOHMANN_JSON
if (!opt_output_json.empty()) {
dnn.saveConfigurationInJSON(opt_output_json);
}
#else
if (!opt_output_json.empty()) {
std::cerr << "Error: NLOHMANN JSON library is not installed, please install it following ViSP documentation to save the configuration in a JSON file." << std::endl;
}
#endif
cv::Mat frame;
while (true) {
capture >> frame;
if (frame.type() == CV_8UC4) {
// RGBa format is not supported by the class, converting to BGR format
cv::Mat cpy = frame;
cv::cvtColor(cpy, frame, cv::COLOR_RGBA2BGR);
}
if (frame.empty())
break;
if (I.getSize() == 0) {
d.init(I);
vpDisplay::setTitle(I, "DNN object detection");
if (opt_verbose) {
std::cout << "Process image: " << I.getWidth() << " x " << I.getHeight() << std::endl;
}
}
else {
}
if (opt_verbose) {
std::cout << "Process new image" << std::endl;
}
if (opt_dnn_containerType == DETECTION_CONTAINER_MAP || opt_dnn_containerType == DETECTION_CONTAINER_BOTH) {
double t = vpTime::measureTimeMs();
std::map<std::string, std::vector<vpDetectorDNNOpenCV::DetectedFeatures2D> > detections;
dnn.detect(frame, detections);
for (auto key_val : detections) {
if (opt_verbose) {
std::cout << " Class name : " << key_val.first << std::endl;
}
for (vpDetectorDNNOpenCV::DetectedFeatures2D detection : key_val.second) {
if (opt_verbose) {
std::cout << " Bounding box : " << detection.getBoundingBox() << std::endl;
std::cout << " Class Id : " << detection.getClassId() << std::endl;
if (detection.getClassName())
std::cout << " Class name : " << detection.getClassName().value() << std::endl;
std::cout << " Confidence score: " << detection.getConfidenceScore() << std::endl;
}
detection.display(I);
}
}
std::ostringstream oss_map;
oss_map << "Detection time (map): " << t << " ms";
if (opt_verbose) {
// Displaying timing result in console
std::cout << " " << oss_map.str() << std::endl;
}
// Displaying timing result on the image
vpDisplay::displayText(I, 60, 20, oss_map.str(), vpColor::red);
}
if (opt_dnn_containerType == DETECTION_CONTAINER_VECTOR || opt_dnn_containerType == DETECTION_CONTAINER_BOTH) {
double t_vector = vpTime::measureTimeMs();
std::vector<vpDetectorDNNOpenCV::DetectedFeatures2D> detections_vec;
dnn.detect(frame, detections_vec);
t_vector = vpTime::measureTimeMs() - t_vector;
for (auto detection : detections_vec) {
if (opt_verbose) {
std::cout << " Bounding box : " << detection.getBoundingBox() << std::endl;
std::cout << " Class Id : " << detection.getClassId() << std::endl;
std::optional<std::string> classname_opt = detection.getClassName();
std::cout << " Class name : " << (classname_opt ? *classname_opt : "Not known") << std::endl;
std::cout << " Confidence score: " << detection.getConfidenceScore() << std::endl;
}
detection.display(I);
}
std::ostringstream oss_vec;
oss_vec << "Detection time (vector): " << t_vector << " ms";
if (opt_verbose) {
// Displaying timing result in console
std::cout << " " << oss_vec.str() << std::endl;
}
// Displaying timing result on the image
vpDisplay::displayText(I, 80, 20, oss_vec.str(), vpColor::red);
}
// // UI display
if (opt_step_by_step) {
vpDisplay::displayText(I, 20, 20, "Left click to display next image", vpColor::red);
}
vpDisplay::displayText(I, 40, 20, "Right click to quit", vpColor::red);
if (vpDisplay::getClick(I, button, opt_step_by_step)) {
if (button == vpMouseButton::button1) {
// Left click => next image
continue;
}
else if (button == vpMouseButton::button3) {
// Right click => stop the program
break;
}
}
}
}
catch (const vpException &e) {
std::cout << e.what() << std::endl;
}
#else
(void)argc;
(void)argv;
#endif
return EXIT_SUCCESS;
}
static const vpColor red
Definition: vpColor.h:217
Display for windows using GDI (available on any windows 32 platform).
Definition: vpDisplayGDI.h:130
The vpDisplayOpenCV allows to display image using the OpenCV library. Thus to enable this class OpenC...
void init(vpImage< unsigned char > &I, int winx=-1, int winy=-1, const std::string &title="") VP_OVERRIDE
void setDownScalingFactor(unsigned int scale)
static bool getClick(const vpImage< unsigned char > &I, bool blocking=true)
static void display(const vpImage< unsigned char > &I)
static void setTitle(const vpImage< unsigned char > &I, const std::string &windowtitle)
static void flush(const vpImage< unsigned char > &I)
@ SCALE_AUTO
Definition: vpDisplay.h:184
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
error that can be emitted by ViSP classes.
Definition: vpException.h:60
@ fatalError
Fatal error.
Definition: vpException.h:72
const char * what() const
Definition: vpException.cpp:71
static void convert(const vpImage< unsigned char > &src, vpImage< vpRGBa > &dest)
unsigned int getWidth() const
Definition: vpImage.h:242
unsigned int getSize() const
Definition: vpImage.h:221
unsigned int getHeight() const
Definition: vpImage.h:181
static std::string toLowerCase(const std::string &input)
Return a lower-case version of the string input . Numbers and special characters stay the same.
Definition: vpIoTools.cpp:1339
static bool checkFilename(const std::string &filename)
Definition: vpIoTools.cpp:786
static bool isNumber(const std::string &str)
Definition: vpMath.cpp:214
VISP_EXPORT double measureTimeMs()

Default DNN model and config files perform human faces detection.

std::string opt_dnn_model = "opencv_face_detector_uint8.pb";
std::string opt_dnn_config = "opencv_face_detector.pbtxt";
std::string opt_dnn_framework = "none";
std::string opt_dnn_label_file = "";
vpDetectorDNNOpenCV::DNNResultsParsingType opt_dnn_type = vpDetectorDNNOpenCV::RESNET_10;

This network is provided by OpenCV and has been trained with the following characteristics:

This is a brief description of training process which has been used to get res10_300x300_ssd_iter_140000.caffemodel. The model was created with SSD framework using ResNet-10 like architecture as a backbone. Channels count in ResNet-10 convolution layers was significantly dropped (2x- or 4x- fewer channels). The model was trained in Caffe framework on some huge and available online dataset.

More specifically, the model used (opencv_face_detector_uint8.pb) has been quantized (with the TensorFlow library) on 8-bit unsigned int to reduce the size of the training model (2.7 mo vs 10.7 mo for res10_300x300_ssd_iter_140000.caffemodel).

The following lines permit to create the DNN object detector:

vpDetectorDNNOpenCV::NetConfig netConfig(opt_dnn_confThresh, opt_dnn_nmsThresh, opt_dnn_label_file
, cv::Size(opt_dnn_width, opt_dnn_height), opt_dnn_filterThresh, cv::Scalar(opt_dnn_meanR, opt_dnn_meanG, opt_dnn_meanB)
, opt_dnn_scale_factor, opt_dnn_swapRB, opt_dnn_type
, opt_dnn_model, opt_dnn_config, opt_dnn_framework
);
dnn.setNetConfig(netConfig);

To construct netConfig object some configuration parameters of the DNN are required:

  • confThresh, which is the confidence threshold used to filter the detections after inference
  • nmsThresh, which is the Non-Maximum Threshold used to filter multiple detections that can occur approximatively at the same locations
  • labelFile, which is the path towards the file containing the list of classes the DNN can detect
  • inputWidth and inputHeight, which are the dimensions to resize the input image into the blob that is fed in entry of the network
  • filterThresh, which is a double that, if greater than 0., indicates that the user wants to perform an additional filtering on the detection outputs based on the size of these detections
  • meanR, meanG and meanB are the values used for mean subtraction
  • scaleFactor is used to normalize the data range
  • swapRB should be set to true when the model has been trained on RGB data. Since OpenCV used the BGR convention, R and B channel should be swapped
  • dnn_type is the type of parsing method to use to parse the DNN raw results. See vpDetectorDNNOpenCV::DNNResultsParsingType to determine which parsing methods are available
  • model is the network trained weights, config is the network topology description and framework is the weights framework.

Alternatively, if ViSP has been compiled with the NLOHMANN JSON library, one can initialize the vpDetectorDNNOpenCV object using the following method:

dnn.initFromJSON(opt_input_json);

You can directly refer to the OpenCV model zoo for the parameters values.

After setting the correct parameters, if you want to get the data as a map, where the keys will be the class names (or ID if no label file was given), you can easily detect object in an image with:

std::map<std::string, std::vector<vpDetectorDNNOpenCV::DetectedFeatures2D> > detections;
dnn.detect(frame, detections);

Alternatively, you can get the results in a non-sorted vector with

std::vector<vpDetectorDNNOpenCV::DetectedFeatures2D> detections_vec;
dnn.detect(frame, detections_vec);

Class ids and detection confidence scores can be retrieved for a map with:

for (auto key_val : detections) {
if (opt_verbose) {
std::cout << " Class name : " << key_val.first << std::endl;
}
for (vpDetectorDNNOpenCV::DetectedFeatures2D detection : key_val.second) {
if (opt_verbose) {
std::cout << " Bounding box : " << detection.getBoundingBox() << std::endl;
std::cout << " Class Id : " << detection.getClassId() << std::endl;
if (detection.getClassName())
std::cout << " Class name : " << detection.getClassName().value() << std::endl;
std::cout << " Confidence score: " << detection.getConfidenceScore() << std::endl;
}
detection.display(I);
}
}

or for a non-sorted vector with:

for (auto detection : detections_vec) {
if (opt_verbose) {
std::cout << " Bounding box : " << detection.getBoundingBox() << std::endl;
std::cout << " Class Id : " << detection.getClassId() << std::endl;
std::optional<std::string> classname_opt = detection.getClassName();
std::cout << " Class name : " << (classname_opt ? *classname_opt : "Not known") << std::endl;
std::cout << " Confidence score: " << detection.getConfidenceScore() << std::endl;
}
detection.display(I);
}

Use case

Generic usage

The default behavior is to detect human faces, but you can input another model to detect the objects you want. To see which are the options, run:

$ cd $VISP_WS/visp-build/tutorial/detection/dnn
$ ./tutorial-dnn-object-detection-live --help

Face detection

The default behavior is to detect human faces using a model provided by OpenCV and learned over a ResNet 10 network. If you have a laptop, simply run:

$ cd $VISP_WS/visp-build/tutorial/detection/dnn
$ ./tutorial-dnn-object-detection-live

The previous command is similar to the next one:

$ CONFIG=opencv_face_detector.pbtxt \
MODEL=opencv_face_detector_uint8.pb \
LABELS=class.txt \
TYPE=resnet-10 \
FRAMEWORK=none \
WIDTH=300; HEIGHT=300
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--confThresh 0.35 --filterThresh -0.25 --scale 1

COCO dataset objects detection

COCO is a large-scale object detection, segmentation, and captioning dataset. It contains over 330 000 images, each annotated with 80 object categories. In the following sections, we show how to use the DNN models learned with the different networks, to detect objects among the list of 80 objects in the COCO dataset.

Faster-RCNN

You can find the config file (config.pbtxt) here, the weights (frozen_inference_graph.pb) there and the labels (coco_classes.txt) here.

To run the tutorial with the Faster-RCNN network, please run the following commands:

$ cd $VISP_WS/visp-build/tutorial/detection/dnn
$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=${DNN_PATH}/Faster-RCNN/cfg/config.pbtxt \
MODEL=${DNN_PATH}/Faster-RCNN/weights/faster_rcnn_inception_v2_coco_2018_01_28/frozen_inference_graph.pb \
LABELS=${DNN_PATH}/Faster-RCNN/cfg/coco_classes.txt \
TYPE=faster-rcnn \
FRAMEWORK=none \
WIDTH=300; HEIGHT=300
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--confThresh 0.35 --filterThresh -0.25 --scale 1

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_faster-rcnn.json

If you want to train your own Faster-RCNN model, please refer to this tutorial.

MobileNet SSD

If you want to use Mobilenet V1, you can find the config file (ssd_mobilenet_v1_coco_2017_11_17.pbtxt) here, the weights (frozen_inference_graph.pb) there and the labels (coco_classes.txt) here.

The parameters to use with this network were found there.

To run the tutorial with the Mobilenet V1 network, please run the following commands:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=${DNN_PATH}/MobileNet-SSD/cfg/ssd_mobilenet_v1_coco_2017_11_17.pbtxt \
MODEL=${DNN_PATH}/MobileNet-SSD/weights/frozen_inference_graph.pb \
LABELS=${DNN_PATH}/MobileNet-SSD/cfg/coco_classes.txt \
TYPE=ssd-mobilenet \
FRAMEWORK=none \
WIDTH=300 HEIGHT=300
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 1

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_ssd-mobilenet_v1.json

If you would rather use the v3 of Mobilenet-SSD, please download the config file (ssd_mobilenet_v3_large_coco_2020_01_14.pbtxt) here, the weights (frozen_inference_graph.pb) there and the labels (coco_classes.txt) here.

Then, to run the tutorial with the Mobilenet V3 network, please run the following commands:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=${DNN_PATH}/MobileNet-SSD/cfg/ssd_mobilenet_v3_large_coco_2020_01_14.pbtxt \
MODEL=${DNN_PATH}/MobileNet-SSD/weights/frozen_inference_graph.pb \
LABELS=${DNN_PATH}/MobileNet-SSD/cfg/coco_classes.txt \
TYPE=ssd-mobilenet \
FRAMEWORK=none \
WIDTH=320 HEIGHT=320
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0.0019 0.0019 0.0019 \
--filterThresh -0.25 --scale 0.00389

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_ssd-mobilenet_v3.json

If you want to train your own MobileNet SSD model, please refer to this tutorial or the Keras documentation for instance.

Yolo v3

You can find the config file (yolov3.cfg) here, the weights (yolov3.weights) there and the labels (coco_classes.txt) here.

To run the tutorial program tutorial-dnn-object-detection-live.cpp, use the following commands:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=${DNN_PATH}/yolov3/cfg/yolov3.cfg \
MODEL=${DNN_PATH}/yolov3/weights/yolov3.weights \
LABELS=${DNN_PATH}/yolov3/cfg/coco_classes.txt \
TYPE=yolov3 \
FRAMEWORK=darknet \
WIDTH=416 HEIGHT=416
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_yolov3.json

If you want to train your own YoloV3 model, please refer to the official documentation.

Yolo v4

You can find the the config file (yolov4-tiny.cfg) here, the weights (yolov4-tiny.weights) there and the labels (coco_classes.txt) here.

To run the tutorial program tutorial-dnn-object-detection-live.cpp, use the following commands:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=${DNN_PATH}/yolov4/cfg/yolov4-tiny.cfg \
MODEL=${DNN_PATH}/yolov4/weights/yolov4-tiny.weights \
LABELS=${DNN_PATH}/yolov4/cfg/coco_classes.txt \
TYPE=yolov4 \
FRAMEWORK=darknet \
WIDTH=416 HEIGHT=416
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_yolov4.json

If you want to train your own YoloV4 model, please refer to the official documentation.

Yolo v5

You can find the weights (yolov5n.onnx) in ONNX format here and the labels (coco_classes.txt) here.

Note
You do not need a config file when using a network saved in ONNX format.

To run the tutorial program tutorial-dnn-object-detection-live.cpp, use the following commands:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=none \
MODEL=${DNN_PATH}/yolov5/weights/yolov5n.onnx \
LABELS=${DNN_PATH}/yolov5/cfg/coco_classes.txt \
TYPE=yolov5 \
FRAMEWORK=onnx \
WIDTH=640 HEIGHT=640
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_yolov5.json

If you want to train your own YoloV5 model, please refer to the official documentation.

Yolo v7

To be able to use YoloV7 with the class vpDetectorDNNOpenCV, you must first download the weights (yolov7-tiny.pt) in the Pytorch format from here.

Then, convert it in ONNX format using the export.py script that you can find on the YoloV7 repo with the following arguments:

$ python3 export.py --weights ../weights/yolov7-tiny.pt --grid --simplify --topk-all 100 --iou-thres 0.65 --conf-thres 0.35 --img-size 640 640 --max-wh 640

Finally, use the following commands to run the tutorial program:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=none \
MODEL=${DNN_PATH}/yolov7/weights/yolov7-tiny.onnx \
LABELS=${DNN_PATH}/yolov7/cfg/coco_classes.txt \
TYPE=yolov7 \
FRAMEWORK=onnx \
WIDTH=640 HEIGHT=640
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039
Note
You do not need a config file when using a network saved in ONNX format.

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_yolov7.json

If you want to train your own YoloV7 model, please refer to the official documentation. If your dataset is rather small (only hundreds of pictures), you may want to consider to base your training on yolov7-tiny network, as it tends to get better results.

Warning
If you train your own model, be sure to use the same image size in the python train.py, python export.py and ./tutorial-dnn-object-detection-live commands. Otherwise, it can lead to either an error thrown by OpenCV or the absence of detection by the ONNX model while the Pytorch model works perfectly using the python detect.py command.

Yolo v8

You can find the weights (yolov8s.onnx) in ONNX format here and the labels (coco_classes.txt) here.

Please use the following commands to run the tutorial program:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=none \
MODEL=${DNN_PATH}/yolov8/weights/yolov8s.onnx \
LABELS=${DNN_PATH}/yolov8/cfg/coco_classes.txt \
TYPE=yolov8 \
FRAMEWORK=onnx \
WIDTH=640 HEIGHT=480
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039

Alternatively, if you have installed the NLOHMANN JSON library and you are using the weights quoted above, you can use the following command line:

$ ./tutorial-dnn-object-detection-live --input-json ./default_yolov8.json
Note
You do not need a config file when using a network saved in ONNX format.

If you want to train your own YoloV8 model, please refer to the official documentation.

Yolo v11

Please follow the official documentation to install Ultralytics tools in order to be able to train or export a model. The installation using Docker has been tested for the sake of this tutorial.

You can get the pre-trained YoloV11 models here. For this tutorial, we tested the YOLO11s pre-trained model.

To export a model stored in Pytorch format into an ONNX format, you can use the Ultralytics tool:

$ sudo docker run -it --ipc=host --gpus all ultralytics/ultralytics:latest
root@8efe0fdbe196:/ultralytics# yolo export model=/path/to/yolo11s.pt format=onnx imgsz=640 opset=12
Note
The opset option permits to set the version of ONNX to use to export the model. If you use OpenCV 4.10.0 this option does not seem to be required.
It seems that OpenCV 4.7.0 is not compatible with Yolo v11. To upgrade OpenCV please follow the instructions in the section Fix by upgrading OpenCV from source below.

Please use the following commands to run the tutorial program:

$ DNN_PATH=/path/to/my/dnn/folder \
CONFIG=none \
MODEL=${DNN_PATH}/yolov11/weights/yolov11s.onnx \
LABELS=${DNN_PATH}/yolov11/cfg/coco_classes.txt \
TYPE=yolov11 \
FRAMEWORK=onnx \
WIDTH=640 HEIGHT=640
$ ./tutorial-dnn-object-detection-live --model $MODEL --labels $LABELS --config $CONFIG --type $TYPE \
--framework $FRAMEWORK --width $WIDTH --height $HEIGHT --nmsThresh 0.5 --mean 0 0 0 \
--filterThresh -0.25 --scale 0.0039

Other dnn models

OpenCV model zoo

You can find more models in the OpenCV model zoo repository.

Troubleshootings

When using the vpDetectorDNNOpenCV class, you may face the following errors:

Error in the DNN input size

[ERROR:0@1.3.nosp@m.38] global net_impl.cpp:1161 getLayerShapesRecursively OPENCV/DNN: [Reshape]:(onnx_node!Reshape_219): getMemoryShapes() throws exception. inputs=1 outputs=1/1 blobs=0 [ERROR:0@1.3.nosp@m.38] global net_impl.cpp:1167 getLayerShapesRecursively input[0] = [ 1 64 8400 ] [ERROR:0@1.3.nosp@m.38] global net_impl.cpp:1171 getLayerShapesRecursively output[0] = [ ] [ERROR:0@1.3.nosp@m.38] global net_impl.cpp:1177 getLayerShapesRecursively Exception message: OpenCV(4.7.0) ${HOME}/visp_ws/3rdparty/opencv/modules/dnn/src/layers/reshape_layer.cpp:109: error: (-215:Assertion failed) total(srcShape, srcRange.start, srcRange.end) == maskTotal in function 'computeShapeByReshapeMask'

terminate called after throwing an instance of 'cv::Exception' what(): OpenCV(4.7.0) ${HOME}/visp_ws/3rdparty/opencv/modules/dnn/src/layers/reshape_layer.cpp:109: error: (-215:Assertion failed) total(srcShape, srcRange.start, srcRange.end) == maskTotal in function 'computeShapeByReshapeMask'

This error may occur if you mistook the input size of the DNN (i.e. if you are asking to resize the input images to a size that does not match the one expected by the DNN).

YoloV3: transpose weights is not functionNotImplementedError

terminate called after throwing an instance of 'cv::Exception'
what(): OpenCV(4.7.0) error: (-213:The function/feature is not implemented) Transpose the weights (except for convolutional) is not
implemented in function 'ReadDarknetFromWeightsStream'

Following the proposition found here to download once again the weights from here permitted to solve this error.

YoloV7: can't create NonMaxSuppression layer

When using a YoloV7 model exported in onnx format, one can face the following error:

[ERROR:0@0.335] global onnx_importer.cpp:1054 handleNode DNN/ONNX: ERROR during processing node with 5 inputs and 1 outputs: [NonMaxSuppression]onnx_node!/end2end/NonMaxSuppression) from domain='ai.onnx'
terminate called after throwing an instance of 'cv::Exception'
what(): OpenCV(4.7.0) opencv/modules/dnn/src/onnx/onnx_importer.cpp:1073: error: (-2:Unspecified error) in function 'handleNode'
Node [NonMaxSuppression@ai.onnx]onnx_node!/end2end/NonMaxSuppression) parse error: OpenCV(4.7.0) opencv/modules/dnn/src/net_impl.hpp:108: error: (-2:Unspecified error) Can't create layer "onnx_node!/end2end/NonMaxSuppression" of type "NonMaxSuppression" in function 'getLayerInstance'
Aborted (core dumped)

You may have been missing the onnxsim library or forgotten to remove the --end2end option during the export of the network.

Yolo v11: Known issues

ONNX version mismatch

You may face the following error:

what(): OpenCV(4.7.0) /root/3rdparty/opencv/modules/dnn/src/onnx/onnx_importer.cpp:1073: error: (-2:Unspecified error) in function 'handleNode'
> Node [Split@ai.onnx]:(onnx_node!/model.10/m/m.0/attn/Split) parse error: OpenCV(4.7.0) /root/3rdparty/opencv/modules/dnn/src/layers/slice_layer.cpp:274: error: (-215:Assertion failed) splits > 0 && inpShape[axis_rw] % splits == 0 in function 'getMemoryShapes'

It is because the version of ONNX used to export the model does not match the one that OpenCV uses. Please be sure that you used the opset option in the export command as stated in Yolo v11 section, such as follow:

$ yolo export model=/path/to/yolo11s.pt format=onnx imgsz=640 opset=12
Note
The opset option does not seem to be needed with OpenCV 4.10.0 .

OpenCV version too old

You may also face the following error when trying to run the tutorial with a Yolo v11 model:

terminate called after throwing an instance of 'cv::Exception'
what(): OpenCV(4.7.0) /root/3rdparty/opencv/modules/dnn/src/net_impl_fuse.cpp:252: error: (-215:Assertion failed) biasLayerData->outputBlobs.size() == 1 in function 'fuseLayers'

It is because the OpenCV version that you use is too old. Please update OpenCV following the instructions presented in the Fix by upgrading OpenCV from source below.

Fix by upgrading OpenCV from source

We suppose that OpenCV has been installed from source as described in the section Build OpenCV with GPU acceleration above.

To upgrade OpenCV to version 4.10.0, please follow the steps below:

$ cd $VISP_WS/3rdparty/opencv
$ git fetch
$ git checkout 4.10.0
$ cd build
$ cmake .. \
-DCMAKE_BUILD_TYPE=RELEASE \
-DCMAKE_INSTALL_PREFIX=/usr \
-DCMAKE_INSTALL_LIBDIR=lib \
-DWITH_CUDA=ON \
-DWITH_CUDNN=ON \
-DOPENCV_DNN_CUDA=ON \
-DENABLE_FAST_MATH=1 \
-DCUDA_FAST_MATH=1 \
-DCUDA_ARCH_BIN=${GPU_CAPABILITIES} \
-DWITH_CUBLAS=1 \
-DOPENCV_EXTRA_MODULES_PATH=${HOME}/visp_ws/3rdparty/opencv_contrib/modules \
-DBUILD_PERF_TESTS=Off \
-DBUILD_TESTS=Off \
-DBUILD_EXAMPLES=Off \
-DBUILD_opencv_apps=Off \
-DBUILD_opencv_java_bindings_generator=Off \
-DBUILD_opencv_js=Off
$ make -j$(nproc)
$ sudo make install

Once OpenCV is build and installed, you need to rebuild ViSP:

$ cd $VISP_WS/visp-build
$ cmake ../visp
$ make -j$(nproc)

Next tutorial

You may continue following Tutorial: Deep learning object detection on NVIDIA GPU with TensorRT.