mono_depth_mobilenetssd.cpp
Go to the documentation of this file.
1 #include <iostream>
2 
3 // Includes common necessary includes for development using depthai library
4 #include "depthai/depthai.hpp"
5 
6 // MobilenetSSD label texts
7 static const std::vector<std::string> labelMap = {"background", "aeroplane", "bicycle", "bird", "boat", "bottle", "bus",
8  "car", "cat", "chair", "cow", "diningtable", "dog", "horse",
9  "motorbike", "person", "pottedplant", "sheep", "sofa", "train", "tvmonitor"};
10 
11 int main(int argc, char** argv) {
12  using namespace std;
13  // Default blob path provided by Hunter private data download
14  // Applicable for easier example usage only
15  std::string nnPath(BLOB_PATH);
16 
17  // If path to blob specified, use that
18  if(argc > 1) {
19  nnPath = std::string(argv[1]);
20  }
21 
22  // Print which blob we are using
23  printf("Using blob at path: %s\n", nnPath.c_str());
24 
25  // Create pipeline
26  dai::Pipeline pipeline;
27 
28  // Define sources and outputs
29  auto monoRight = pipeline.create<dai::node::MonoCamera>();
30  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
31  auto stereo = pipeline.create<dai::node::StereoDepth>();
32  auto manip = pipeline.create<dai::node::ImageManip>();
33  auto nn = pipeline.create<dai::node::MobileNetDetectionNetwork>();
34 
35  auto disparityOut = pipeline.create<dai::node::XLinkOut>();
36  auto xoutRight = pipeline.create<dai::node::XLinkOut>();
37  auto nnOut = pipeline.create<dai::node::XLinkOut>();
38 
39  disparityOut->setStreamName("disparity");
40  xoutRight->setStreamName("rectifiedRight");
41  nnOut->setStreamName("nn");
42 
43  // Properties
44  monoRight->setCamera("right");
46  monoLeft->setCamera("left");
48  // Produce the depth map (using disparity output as it's easier to visualize depth this way)
49  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
50  stereo->setRectifyEdgeFillColor(0); // Black, to better see the cutout from rectification (black stripe on the edges)
51  // Convert the grayscale frame into the nn-acceptable form
52  manip->initialConfig.setResize(300, 300);
53  // The NN model expects BGR input. By default ImageManip output type would be same as input (gray in this case)
54  manip->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p);
55 
56  // Define a neural network that will make predictions based on the source frames
57  nn->setConfidenceThreshold(0.5);
58  nn->setBlobPath(nnPath);
59  nn->setNumInferenceThreads(2);
60  nn->input.setBlocking(false);
61 
62  // Linking
63  monoRight->out.link(stereo->right);
64  monoLeft->out.link(stereo->left);
65  stereo->rectifiedRight.link(manip->inputImage);
66  stereo->disparity.link(disparityOut->input);
67  manip->out.link(nn->input);
68  manip->out.link(xoutRight->input);
69  nn->out.link(nnOut->input);
70 
71  // Connect to device and start pipeline
72  dai::Device device(pipeline);
73 
74  // Output queues will be used to get the grayscale / depth frames and nn data from the outputs defined above
75  auto qRight = device.getOutputQueue("rectifiedRight", 4, false);
76  auto qDisparity = device.getOutputQueue("disparity", 4, false);
77  auto qDet = device.getOutputQueue("nn", 4, false);
78 
79  cv::Mat rightFrame;
80  cv::Mat disparityFrame;
81  std::vector<dai::ImgDetection> detections;
82 
83  // Add bounding boxes and text to the frame and show it to the user
84  auto show = [](std::string name, cv::Mat frame, std::vector<dai::ImgDetection>& detections) {
85  auto color = cv::Scalar(255, 192, 203);
86  // nn data, being the bounding box locations, are in <0..1> range - they need to be normalized with frame width/height
87  for(auto& detection : detections) {
88  int x1 = detection.xmin * frame.cols;
89  int y1 = detection.ymin * frame.rows;
90  int x2 = detection.xmax * frame.cols;
91  int y2 = detection.ymax * frame.rows;
92 
93  uint32_t labelIndex = detection.label;
94  std::string labelStr = to_string(labelIndex);
95  if(labelIndex < labelMap.size()) {
96  labelStr = labelMap[labelIndex];
97  }
98  cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
99  std::stringstream confStr;
100  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
101  cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
102  cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
103  }
104  // Show the frame
105  cv::imshow(name, frame);
106  };
107 
108  float disparityMultiplier = 255 / stereo->initialConfig.getMaxDisparity();
109 
110  while(true) {
111  // Instead of get (blocking), we use tryGet (non-blocking) which will return the available data or None otherwise
112  auto inRight = qRight->tryGet<dai::ImgFrame>();
113  auto inDet = qDet->tryGet<dai::ImgDetections>();
114  auto inDisparity = qDisparity->tryGet<dai::ImgFrame>();
115 
116  if(inDisparity) {
117  // Frame is transformed, normalized, and color map will be applied to highlight the depth info
118  disparityFrame = inDisparity->getFrame();
119  disparityFrame.convertTo(disparityFrame, CV_8UC1, disparityMultiplier);
120  // Available color maps: https://docs.opencv.org/3.4/d3/d50/group__imgproc__colormap.html
121  cv::applyColorMap(disparityFrame, disparityFrame, cv::COLORMAP_JET);
122  show("disparity", disparityFrame, detections);
123  }
124 
125  if(!rightFrame.empty()) {
126  show("rectified right", rightFrame, detections);
127  }
128 
129  int key = cv::waitKey(1);
130  if(key == 'q' || key == 'Q') return 0;
131  }
132  return 0;
133 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
dai::node::XLinkOut
XLinkOut node. Sends messages over XLink.
Definition: XLinkOut.hpp:14
dai::node::MonoCamera::setCamera
void setCamera(std::string name)
Definition: MonoCamera.cpp:36
dai::Pipeline
Represents the pipeline, set of nodes and connections between them.
Definition: Pipeline.hpp:100
labelMap
static const std::vector< std::string > labelMap
Definition: mono_depth_mobilenetssd.cpp:7
dai::node::StereoDepth::initialConfig
StereoDepthConfig initialConfig
Definition: StereoDepth.hpp:52
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::RawImgFrame::Type::BGR888p
@ BGR888p
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
dai::MonoCameraProperties::SensorResolution::THE_400_P
@ THE_400_P
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::MonoCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: MonoCamera.cpp:82
dai::node::ImageManip::out
Output out
Definition: ImageManip.hpp:51
dai::ImgFrame
Definition: ImgFrame.hpp:25
nanorpc::core::exception::to_string
std::string to_string(std::exception const &e)
Definition: exception.h:46
main
int main(int argc, char **argv)
Definition: mono_depth_mobilenetssd.cpp:11
dai::node::ImageManip
ImageManip node. Capability to crop, resize, warp, ... incoming image frames.
Definition: ImageManip.hpp:15
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
std
Definition: Node.hpp:366
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
dai::node::MobileNetDetectionNetwork
MobileNetDetectionNetwork node. Parses MobileNet results.
Definition: DetectionNetwork.hpp:56
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
dai::ImgDetections
Definition: ImgDetections.hpp:14


depthai
Author(s): Martin Peterlin
autogenerated on Sat Mar 22 2025 02:58:19