spatial_mobilenet.cpp
Go to the documentation of this file.
1 #include <chrono>
2 #include <iostream>
3 
4 // Includes common necessary includes for development using depthai library
5 #include "depthai/depthai.hpp"
6 
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 static std::atomic<bool> syncNN{true};
12 
13 int main(int argc, char** argv) {
14  using namespace std;
15  using namespace std::chrono;
16  std::string nnPath(BLOB_PATH);
17 
18  // If path to blob specified, use that
19  if(argc > 1) {
20  nnPath = std::string(argv[1]);
21  }
22 
23  // Print which blob we are using
24  printf("Using blob at path: %s\n", nnPath.c_str());
25 
26  // Create pipeline
27  dai::Pipeline pipeline;
28 
29  // Define sources and outputs
30  auto camRgb = pipeline.create<dai::node::ColorCamera>();
31  auto spatialDetectionNetwork = pipeline.create<dai::node::MobileNetSpatialDetectionNetwork>();
32  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
33  auto monoRight = pipeline.create<dai::node::MonoCamera>();
34  auto stereo = pipeline.create<dai::node::StereoDepth>();
35 
36  auto xoutRgb = pipeline.create<dai::node::XLinkOut>();
37  auto xoutNN = pipeline.create<dai::node::XLinkOut>();
38  auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
39 
40  xoutRgb->setStreamName("rgb");
41  xoutNN->setStreamName("detections");
42  xoutDepth->setStreamName("depth");
43 
44  // Properties
45  camRgb->setPreviewSize(300, 300);
47  camRgb->setInterleaved(false);
48  camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR);
49 
51  monoLeft->setCamera("left");
53  monoRight->setCamera("right");
54 
55  // Setting node configs
56  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
57  // Align depth map to the perspective of RGB camera, on which inference is done
58  stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A);
59  stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight());
60 
61  spatialDetectionNetwork->setBlobPath(nnPath);
62  spatialDetectionNetwork->setConfidenceThreshold(0.5f);
63  spatialDetectionNetwork->input.setBlocking(false);
64  spatialDetectionNetwork->setBoundingBoxScaleFactor(0.5);
65  spatialDetectionNetwork->setDepthLowerThreshold(100);
66  spatialDetectionNetwork->setDepthUpperThreshold(5000);
67 
68  // Linking
69  monoLeft->out.link(stereo->left);
70  monoRight->out.link(stereo->right);
71 
72  camRgb->preview.link(spatialDetectionNetwork->input);
73  if(syncNN) {
74  spatialDetectionNetwork->passthrough.link(xoutRgb->input);
75  } else {
76  camRgb->preview.link(xoutRgb->input);
77  }
78 
79  spatialDetectionNetwork->out.link(xoutNN->input);
80 
81  stereo->depth.link(spatialDetectionNetwork->inputDepth);
82  spatialDetectionNetwork->passthroughDepth.link(xoutDepth->input);
83 
84  // Connect to device and start pipeline
85  dai::Device device(pipeline);
86 
87  auto previewQueue = device.getOutputQueue("rgb", 4, false);
88  auto detectionNNQueue = device.getOutputQueue("detections", 4, false);
89  auto depthQueue = device.getOutputQueue("depth", 4, false);
90 
91  auto startTime = steady_clock::now();
92  int counter = 0;
93  float fps = 0;
94  auto color = cv::Scalar(255, 255, 255);
95 
96  while(true) {
97  auto inPreview = previewQueue->get<dai::ImgFrame>();
98  auto inDet = detectionNNQueue->get<dai::SpatialImgDetections>();
99  auto depth = depthQueue->get<dai::ImgFrame>();
100 
101  counter++;
102  auto currentTime = steady_clock::now();
103  auto elapsed = duration_cast<duration<float>>(currentTime - startTime);
104  if(elapsed > seconds(1)) {
105  fps = counter / elapsed.count();
106  counter = 0;
107  startTime = currentTime;
108  }
109 
110  cv::Mat frame = inPreview->getCvFrame();
111  cv::Mat depthFrame = depth->getFrame(); // depthFrame values are in millimeters
112 
113  cv::Mat depthFrameColor;
114  cv::normalize(depthFrame, depthFrameColor, 255, 0, cv::NORM_INF, CV_8UC1);
115  cv::equalizeHist(depthFrameColor, depthFrameColor);
116  cv::applyColorMap(depthFrameColor, depthFrameColor, cv::COLORMAP_HOT);
117 
118  auto detections = inDet->detections;
119 
120  for(const auto& detection : detections) {
121  auto roiData = detection.boundingBoxMapping;
122  auto roi = roiData.roi;
123  roi = roi.denormalize(depthFrameColor.cols, depthFrameColor.rows);
124  auto topLeft = roi.topLeft();
125  auto bottomRight = roi.bottomRight();
126  auto xmin = (int)topLeft.x;
127  auto ymin = (int)topLeft.y;
128  auto xmax = (int)bottomRight.x;
129  auto ymax = (int)bottomRight.y;
130  cv::rectangle(depthFrameColor, cv::Rect(cv::Point(xmin, ymin), cv::Point(xmax, ymax)), color, cv::FONT_HERSHEY_SIMPLEX);
131 
132  int x1 = detection.xmin * frame.cols;
133  int y1 = detection.ymin * frame.rows;
134  int x2 = detection.xmax * frame.cols;
135  int y2 = detection.ymax * frame.rows;
136 
137  uint32_t labelIndex = detection.label;
138  std::string labelStr = to_string(labelIndex);
139  if(labelIndex < labelMap.size()) {
140  labelStr = labelMap[labelIndex];
141  }
142  cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
143  std::stringstream confStr;
144  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
145  cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 35), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
146 
147  std::stringstream depthX;
148  depthX << "X: " << (int)detection.spatialCoordinates.x << " mm";
149  cv::putText(frame, depthX.str(), cv::Point(x1 + 10, y1 + 50), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
150  std::stringstream depthY;
151  depthY << "Y: " << (int)detection.spatialCoordinates.y << " mm";
152  cv::putText(frame, depthY.str(), cv::Point(x1 + 10, y1 + 65), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
153  std::stringstream depthZ;
154  depthZ << "Z: " << (int)detection.spatialCoordinates.z << " mm";
155  cv::putText(frame, depthZ.str(), cv::Point(x1 + 10, y1 + 80), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
156 
157  cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
158  }
159 
160  std::stringstream fpsStr;
161  fpsStr << "NN fps: " << std::fixed << std::setprecision(2) << fps;
162  cv::putText(frame, fpsStr.str(), cv::Point(2, inPreview->getHeight() - 4), cv::FONT_HERSHEY_TRIPLEX, 0.4, color);
163 
164  cv::imshow("depth", depthFrameColor);
165  cv::imshow("preview", frame);
166 
167  int key = cv::waitKey(1);
168  if(key == 'q' || key == 'Q') {
169  return 0;
170  }
171  }
172  return 0;
173 }
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
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
main
int main(int argc, char **argv)
Definition: spatial_mobilenet.cpp:13
fps
static constexpr int fps
Definition: rgb_depth_aligned.cpp:12
dai::CameraBoardSocket::CAM_A
@ CAM_A
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::node::ColorCamera
ColorCamera node. For use with color sensors.
Definition: ColorCamera.hpp:16
dai::SpatialImgDetections
Definition: SpatialImgDetections.hpp:15
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
syncNN
static std::atomic< bool > syncNN
Definition: spatial_mobilenet.cpp:11
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::ImgFrame::getCvFrame
void getCvFrame(T...)
Definition: ImgFrame.hpp:222
dai::ColorCameraProperties::ColorOrder::BGR
@ BGR
dai::ImgFrame
Definition: ImgFrame.hpp:25
nanorpc::core::exception::to_string
std::string to_string(std::exception const &e)
Definition: exception.h:46
dai::node::MobileNetSpatialDetectionNetwork
Definition: SpatialDetectionNetwork.hpp:109
dai::ColorCameraProperties::SensorResolution::THE_1080_P
@ THE_1080_P
1920 × 1080
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
dai::node::ColorCamera::preview
Output preview
Definition: ColorCamera.hpp:69
std
Definition: Node.hpp:366
labelMap
static const std::vector< std::string > labelMap
Definition: spatial_mobilenet.cpp:7
dai::Node::Output::link
void link(const Input &in)
Definition: Node.cpp:84
dai::node::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13


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