rgb_encoding_mono_mobilenet_depth.cpp
Go to the documentation of this file.
1 #include <cstdio>
2 #include <iostream>
3 
4 // Includes common necessary includes for development using depthai library
5 #include "depthai/depthai.hpp"
6 
7 // MobilenetSSD label texts
8 static const std::vector<std::string> labelMap = {"background", "aeroplane", "bicycle", "bird", "boat", "bottle", "bus",
9  "car", "cat", "chair", "cow", "diningtable", "dog", "horse",
10  "motorbike", "person", "pottedplant", "sheep", "sofa", "train", "tvmonitor"};
11 
12 int main(int argc, char** argv) {
13  using namespace std;
14  // Default blob path provided by Hunter private data download
15  // Applicable for easier example usage only
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 videoEncoder = pipeline.create<dai::node::VideoEncoder>();
32  auto monoRight = pipeline.create<dai::node::MonoCamera>();
33  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
34  auto depth = pipeline.create<dai::node::StereoDepth>();
35  auto manip = pipeline.create<dai::node::ImageManip>();
36  auto nn = pipeline.create<dai::node::MobileNetDetectionNetwork>();
37 
38  auto videoOut = pipeline.create<dai::node::XLinkOut>();
39  auto xoutRight = pipeline.create<dai::node::XLinkOut>();
40  auto disparityOut = pipeline.create<dai::node::XLinkOut>();
41  auto manipOut = pipeline.create<dai::node::XLinkOut>();
42  auto nnOut = pipeline.create<dai::node::XLinkOut>();
43 
44  videoOut->setStreamName("h265");
45  xoutRight->setStreamName("right");
46  disparityOut->setStreamName("disparity");
47  manipOut->setStreamName("manip");
48  nnOut->setStreamName("nn");
49 
50  // Properties
51  camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
53  monoRight->setCamera("right");
55  monoLeft->setCamera("left");
57  videoEncoder->setDefaultProfilePreset(30, dai::VideoEncoderProperties::Profile::H265_MAIN);
58 
59  depth->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
60  depth->setRectifyEdgeFillColor(0); // Black, to better see the cutout
61 
62  nn->setConfidenceThreshold(0.5);
63  nn->setBlobPath(nnPath);
64  nn->setNumInferenceThreads(2);
65  nn->input.setBlocking(false);
66 
67  // The NN model expects BGR input-> By default ImageManip output type would be same as input (gray in this case)
68  manip->initialConfig.setFrameType(dai::ImgFrame::Type::BGR888p);
69  manip->initialConfig.setResize(300, 300);
70 
71  // Linking
72  camRgb->video.link(videoEncoder->input);
73  videoEncoder->bitstream.link(videoOut->input);
74  monoRight->out.link(xoutRight->input);
75  monoRight->out.link(depth->right);
76  monoLeft->out.link(depth->left);
77  depth->disparity.link(disparityOut->input);
78  depth->rectifiedRight.link(manip->inputImage);
79  manip->out.link(nn->input);
80  manip->out.link(manipOut->input);
81  nn->out.link(nnOut->input);
82 
83  // Disparity range is used for normalization
84  float disparityMultiplier = 255 / depth->initialConfig.getMaxDisparity();
85 
86  // Connect to device and start pipeline
87  dai::Device device(pipeline);
88 
89  // Queues
90  int queueSize = 8;
91  auto qRight = device.getOutputQueue("right", queueSize);
92  auto qDisparity = device.getOutputQueue("disparity", queueSize);
93  auto qManip = device.getOutputQueue("manip", queueSize);
94  auto qDet = device.getOutputQueue("nn", queueSize);
95  auto qRgbEnc = device.getOutputQueue("h265", 30, true);
96 
97  cv::Mat frame;
98  cv::Mat frameManip;
99  cv::Mat frameDisparity;
100  std::vector<dai::ImgDetection> detections;
101  int offsetX = (monoRight->getResolutionWidth() - monoRight->getResolutionHeight()) / 2;
102  auto color = cv::Scalar(255, 0, 0);
103 
104  auto videoFile = std::ofstream("video.h265", std::ios::binary);
105  cv::namedWindow("right", cv::WINDOW_NORMAL);
106  cv::namedWindow("manip", cv::WINDOW_NORMAL);
107 
108  while(true) {
109  auto inRight = qRight->tryGet<dai::ImgFrame>();
110  auto inManip = qManip->tryGet<dai::ImgFrame>();
111  auto inDet = qDet->tryGet<dai::ImgDetections>();
112  auto inDisparity = qDisparity->tryGet<dai::ImgFrame>();
113 
114  auto out1 = qRgbEnc->get<dai::ImgFrame>();
115  videoFile.write((char*)out1->getData().data(), out1->getData().size());
116 
117  if(inRight) {
118  frame = inRight->getCvFrame();
119  }
120 
121  if(inManip) {
122  frameManip = inManip->getCvFrame();
123  }
124 
125  if(inDisparity) {
126  frameDisparity = inDisparity->getCvFrame();
127  frameDisparity.convertTo(frameDisparity, CV_8UC1, disparityMultiplier);
128  cv::applyColorMap(frameDisparity, frameDisparity, cv::COLORMAP_JET);
129  }
130 
131  if(inDet) {
132  detections = inDet->detections;
133  }
134 
135  if(!frame.empty()) {
136  for(auto& detection : detections) {
137  int x1 = detection.xmin * monoRight->getResolutionHeight() + offsetX;
138  int y1 = detection.ymin * monoRight->getResolutionHeight();
139  int x2 = detection.xmax * monoRight->getResolutionHeight() + offsetX;
140  int y2 = detection.ymax * monoRight->getResolutionHeight();
141 
142  uint32_t labelIndex = detection.label;
143  std::string labelStr = to_string(labelIndex);
144  if(labelIndex < labelMap.size()) {
145  labelStr = labelMap[labelIndex];
146  }
147  cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
148  std::stringstream confStr;
149  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
150  cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
151  cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
152  }
153  // Show the right cam frame
154  cv::imshow("right", frame);
155  }
156 
157  if(!frameDisparity.empty()) {
158  for(auto& detection : detections) {
159  int x1 = detection.xmin * monoRight->getResolutionHeight() + offsetX;
160  int y1 = detection.ymin * monoRight->getResolutionHeight();
161  int x2 = detection.xmax * monoRight->getResolutionHeight() + offsetX;
162  int y2 = detection.ymax * monoRight->getResolutionHeight();
163 
164  uint32_t labelIndex = detection.label;
165  std::string labelStr = to_string(labelIndex);
166  if(labelIndex < labelMap.size()) {
167  labelStr = labelMap[labelIndex];
168  }
169  cv::putText(frameDisparity, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
170  std::stringstream confStr;
171  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
172  cv::putText(frameDisparity, confStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
173  cv::rectangle(frameDisparity, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
174  }
175  // Show the disparity frame
176  cv::imshow("disparity", frameDisparity);
177  }
178 
179  if(!frameManip.empty()) {
180  for(auto& detection : detections) {
181  int x1 = detection.xmin * frameManip.cols;
182  int y1 = detection.ymin * frameManip.rows;
183  int x2 = detection.xmax * frameManip.cols;
184  int y2 = detection.ymax * frameManip.rows;
185 
186  uint32_t labelIndex = detection.label;
187  std::string labelStr = to_string(labelIndex);
188  if(labelIndex < labelMap.size()) {
189  labelStr = labelMap[labelIndex];
190  }
191  cv::putText(frameManip, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
192  std::stringstream confStr;
193  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
194  cv::putText(frameManip, confStr.str(), cv::Point(x1 + 10, y1 + 40), cv::FONT_HERSHEY_TRIPLEX, 0.5, color);
195  cv::rectangle(frameManip, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
196  }
197  // Show the manip frame
198  cv::imshow("manip", frameManip);
199  }
200 
201  int key = cv::waitKey(1);
202  if(key == 'q' || key == 'Q') {
203  break;
204  }
205  }
206  cout << "To view the encoded data, convert the stream file (.h265) into a video file (.mp4), using a command below:" << endl;
207  cout << "ffmpeg -framerate 30 -i video.h265 -c copy video.mp4" << endl;
208  return 0;
209 }
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::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
main
int main(int argc, char **argv)
Definition: rgb_encoding_mono_mobilenet_depth.cpp:12
dai::CameraBoardSocket::CAM_A
@ CAM_A
dai::node::MonoCamera
MonoCamera node. For use with grayscale sensors.
Definition: MonoCamera.hpp:17
dai::Buffer::getData
std::vector< std::uint8_t > & getData() const
Get non-owning reference to internal buffer.
Definition: Buffer.cpp:13
dai::node::ColorCamera
ColorCamera node. For use with color sensors.
Definition: ColorCamera.hpp:16
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::node::VideoEncoder::out
Output out
Definition: VideoEncoder.hpp:35
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::getCvFrame
void getCvFrame(T...)
Definition: ImgFrame.hpp:222
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::ImageManip
ImageManip node. Capability to crop, resize, warp, ... incoming image frames.
Definition: ImageManip.hpp:15
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::VideoEncoderProperties::Profile::H265_MAIN
@ H265_MAIN
labelMap
static const std::vector< std::string > labelMap
Definition: rgb_encoding_mono_mobilenet_depth.cpp:8
std
Definition: Node.hpp:366
dai::node::VideoEncoder
VideoEncoder node. Encodes frames into MJPEG, H264 or H265.
Definition: VideoEncoder.hpp:14
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