stability_stress_test.cpp
Go to the documentation of this file.
1 // std
2 #include <chrono>
3 #include <csignal>
4 #include <iostream>
5 #include <unordered_map>
6 
7 // Includes common necessary includes for development using depthai library
8 #include "depthai/depthai.hpp"
9 
10 // #define DEPTHAI_STABILITY_TEST_SCRIPT
11 
12 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
13  #include <opencv2/opencv.hpp>
14 #endif
15 
16 static constexpr int RGB_FPS = 20;
17 static constexpr int MONO_FPS = 20;
18 static constexpr int ENCODER_FPS = 10;
19 
21  printf("Ddr used / total - %.2f / %.2f MiB\n", info.ddrMemoryUsage.used / (1024.0f * 1024.0f), info.ddrMemoryUsage.total / (1024.0f * 1024.0f));
22  printf("Cmx used / total - %.2f / %.2f MiB\n", info.cmxMemoryUsage.used / (1024.0f * 1024.0f), info.cmxMemoryUsage.total / (1024.0f * 1024.0f));
23  printf("LeonCss heap used / total - %.2f / %.2f MiB\n",
24  info.leonCssMemoryUsage.used / (1024.0f * 1024.0f),
25  info.leonCssMemoryUsage.total / (1024.0f * 1024.0f));
26  printf("LeonMss heap used / total - %.2f / %.2f MiB\n",
27  info.leonMssMemoryUsage.used / (1024.0f * 1024.0f),
28  info.leonMssMemoryUsage.total / (1024.0f * 1024.0f));
29  const auto& t = info.chipTemperature;
30  printf("Chip temperature - average: %.2f, css: %.2f, mss: %.2f, upa: %.2f, dss: %.2f\n", t.average, t.css, t.mss, t.upa, t.dss);
31  printf("Cpu usage - Leon CSS: %.2f %%, Leon MSS: %.2f %%\n", info.leonCssCpuUsage.average * 100, info.leonMssCpuUsage.average * 100);
32 }
33 
34 static const std::vector<std::string> labelMap = {
35  "person", "bicycle", "car", "motorbike", "aeroplane", "bus", "train", "truck", "boat",
36  "traffic light", "fire hydrant", "stop sign", "parking meter", "bench", "bird", "cat", "dog", "horse",
37  "sheep", "cow", "elephant", "bear", "zebra", "giraffe", "backpack", "umbrella", "handbag",
38  "tie", "suitcase", "frisbee", "skis", "snowboard", "sports ball", "kite", "baseball bat", "baseball glove",
39  "skateboard", "surfboard", "tennis racket", "bottle", "wine glass", "cup", "fork", "knife", "spoon",
40  "bowl", "banana", "apple", "sandwich", "orange", "broccoli", "carrot", "hot dog", "pizza",
41  "donut", "cake", "chair", "sofa", "pottedplant", "bed", "diningtable", "toilet", "tvmonitor",
42  "laptop", "mouse", "remote", "keyboard", "cell phone", "microwave", "oven", "toaster", "sink",
43  "refrigerator", "book", "clock", "vase", "scissors", "teddy bear", "hair drier", "toothbrush"};
44 
45 // Keyboard interrupt (Ctrl + C) detected
46 static std::atomic<bool> alive{true};
47 static void sigintHandler(int signum) {
48  alive = false;
49 }
50 
51 int main(int argc, char** argv) {
52  using namespace std;
53  using namespace std::chrono;
54  std::signal(SIGINT, &sigintHandler);
55 
56  std::string nnPath(BLOB_PATH);
57 
58  // // If path to blob specified, use that
59  // if(argc > 1) {
60  // nnPath = std::string(argv[1]);
61  // }
62 
63  seconds TEST_TIMEOUT{24 * 60 * 60};
64  if(argc > 1) {
65  TEST_TIMEOUT = seconds{stoi(argv[1])};
66  }
67 
68  // Create pipeline
69  dai::Pipeline pipeline;
70  pipeline.setXLinkChunkSize(0);
71 
72  // Define sources and outputs
73  auto camRgb = pipeline.create<dai::node::ColorCamera>();
74  auto monoLeft = pipeline.create<dai::node::MonoCamera>();
75  auto monoRight = pipeline.create<dai::node::MonoCamera>();
76  auto ve1 = pipeline.create<dai::node::VideoEncoder>();
77  auto ve2 = pipeline.create<dai::node::VideoEncoder>();
78  auto ve3 = pipeline.create<dai::node::VideoEncoder>();
79  auto spatialDetectionNetwork = pipeline.create<dai::node::YoloSpatialDetectionNetwork>();
80  auto stereo = pipeline.create<dai::node::StereoDepth>();
81  auto edgeDetectorLeft = pipeline.create<dai::node::EdgeDetector>();
82  auto edgeDetectorRight = pipeline.create<dai::node::EdgeDetector>();
83  auto edgeDetectorRgb = pipeline.create<dai::node::EdgeDetector>();
84  auto sysLog = pipeline.create<dai::node::SystemLogger>();
85 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
86  auto script1 = pipeline.create<dai::node::Script>();
87  auto script2 = pipeline.create<dai::node::Script>();
88  auto script3 = pipeline.create<dai::node::Script>();
89  auto script4 = pipeline.create<dai::node::Script>();
90  auto scriptBurn = pipeline.create<dai::node::Script>();
91 #endif
92 
93  // TODO(themarpe) - enable specific parts separatelly, to control load
94  // auto featureTrackerLeft = pipeline.create<dai::node::FeatureTracker>();
95  // auto featureTrackerRight = pipeline.create<dai::node::FeatureTracker>();
96 
97  auto ve1Out = pipeline.create<dai::node::XLinkOut>();
98  auto ve2Out = pipeline.create<dai::node::XLinkOut>();
99  auto ve3Out = pipeline.create<dai::node::XLinkOut>();
100  auto xoutDepth = pipeline.create<dai::node::XLinkOut>();
101  auto xoutNN = pipeline.create<dai::node::XLinkOut>();
102  auto xoutRgb = pipeline.create<dai::node::XLinkOut>();
103  auto xoutEdgeLeft = pipeline.create<dai::node::XLinkOut>();
104  auto xoutEdgeRight = pipeline.create<dai::node::XLinkOut>();
105  auto xoutEdgeRgb = pipeline.create<dai::node::XLinkOut>();
106  auto xoutSysLog = pipeline.create<dai::node::XLinkOut>();
107 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
108  auto scriptOut = pipeline.create<dai::node::XLinkOut>();
109  auto scriptOut2 = pipeline.create<dai::node::XLinkOut>();
110 #endif
111  // auto xoutTrackedFeaturesLeft = pipeline.create<dai::node::XLinkOut>();
112  // auto xoutTrackedFeaturesRight = pipeline.create<dai::node::XLinkOut>();
113 
114  ve1Out->setStreamName("ve1Out");
115  ve2Out->setStreamName("ve2Out");
116  ve3Out->setStreamName("ve3Out");
117  xoutDepth->setStreamName("depth");
118  xoutNN->setStreamName("detections");
119  xoutRgb->setStreamName("rgb");
120  xoutSysLog->setStreamName("sysinfo");
121  const auto edgeLeftStr = "edge left";
122  const auto edgeRightStr = "edge right";
123  const auto edgeRgbStr = "edge rgb";
124  const auto edgeCfgStr = "edge cfg";
125  xoutEdgeLeft->setStreamName(edgeLeftStr);
126  xoutEdgeRight->setStreamName(edgeRightStr);
127  xoutEdgeRgb->setStreamName(edgeRgbStr);
128 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
129  scriptOut->setStreamName("script");
130  scriptOut2->setStreamName("script2");
131 #endif
132  // xoutTrackedFeaturesLeft->setStreamName("trackedFeaturesLeft");
133  // xoutTrackedFeaturesRight->setStreamName("trackedFeaturesRight");
134 
135  // Properties
136  camRgb->setBoardSocket(dai::CameraBoardSocket::CAM_A);
138  camRgb->setPreviewSize(416, 416);
139  camRgb->setInterleaved(false);
140  camRgb->setColorOrder(dai::ColorCameraProperties::ColorOrder::BGR);
141  camRgb->setFps(RGB_FPS);
142 
143  monoLeft->setCamera("left");
145  monoLeft->setFps(MONO_FPS);
146 
147  monoRight->setCamera("right");
149  monoRight->setFps(MONO_FPS);
150 
151  // Setting to 26fps will trigger error
152  ve1->setDefaultProfilePreset(ENCODER_FPS, dai::VideoEncoderProperties::Profile::H264_MAIN);
155 
156  stereo->setDefaultProfilePreset(dai::node::StereoDepth::PresetMode::HIGH_DENSITY);
157  // Align depth map to the perspective of RGB camera, on which inference is done
158  stereo->setDepthAlign(dai::CameraBoardSocket::CAM_A);
159  stereo->setOutputSize(monoLeft->getResolutionWidth(), monoLeft->getResolutionHeight());
160 
161  spatialDetectionNetwork->setBlobPath(nnPath);
162  spatialDetectionNetwork->setConfidenceThreshold(0.5f);
163  spatialDetectionNetwork->input.setBlocking(false);
164  spatialDetectionNetwork->setBoundingBoxScaleFactor(0.5);
165  spatialDetectionNetwork->setDepthLowerThreshold(100);
166  spatialDetectionNetwork->setDepthUpperThreshold(5000);
167 
168  // yolo specific parameters
169  spatialDetectionNetwork->setNumClasses(80);
170  spatialDetectionNetwork->setCoordinateSize(4);
171  spatialDetectionNetwork->setAnchors({10, 14, 23, 27, 37, 58, 81, 82, 135, 169, 344, 319});
172  spatialDetectionNetwork->setAnchorMasks({{"side26", {1, 2, 3}}, {"side13", {3, 4, 5}}});
173  spatialDetectionNetwork->setIouThreshold(0.5f);
174 
175  edgeDetectorRgb->setMaxOutputFrameSize(8294400);
176 
177  sysLog->setRate(0.2f);
178 
179 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
180  std::string source1 = R"(
181  import time
182  import json
183 
184  counter = 0
185  while True:
186  b = Buffer(64)
187  dict = {'counter1': counter}
188  b.setData(json.dumps(dict).encode('utf-8'))
189  node.io['out'].send(b)
190  time.sleep(0.01)
191  counter = counter + 1
192  )";
193  std::string source2 = R"(
194  import json
195  import time
196 
197  counter = 0
198  MIN_BUFFER_SIZE = 128
199  while True:
200  t = int( time.time() * 1000.0 )
201  x = ( ((t & 0xff000000) >> 24) + ((t & 0x00ff0000) >> 8) + ((t & 0x0000ff00) << 8) + ((t & 0x000000ff) << 24))
202  rand = x % 500
203 
204  buffers = node.io['in'].tryGetAll()
205 
206  dicts = []
207  for b in buffers:
208  data = node.io['in'].get().getData()
209  jsonStr = str(data, 'utf-8')
210  dict = json.loads(jsonStr)
211  dict['counter2'] = counter
212  dicts.append(dict)
213 
214  dicts.append({'counter1': None, 'counter2': counter})
215 
216  for dict in dicts:
217  b = Buffer(MIN_BUFFER_SIZE + rand * 16)
218  b.setData(json.dumps(dict).encode('utf-8'))
219  node.io['out'].send(b)
220 
221  time.sleep(rand / 1000)
222  counter = counter + 1
223  )";
224 
225  script1->setScript(source1);
226  script2->setScript(source2);
227  script3->setScript(source1);
228  script4->setScript(source2);
231 
232  scriptBurn->setScript(R"(
233  import json
234  import time
235  counter = 0
236  while True:
237  rand = 0
238  for x in range(0, 10):
239  t = int( time.time() * 1000.0 )
240  x = ( ((t & 0xff000000) >> 24) + ((t & 0x00ff0000) >> 8) + ((t & 0x0000ff00) << 8) + ((t & 0x000000ff) << 24))
241  rand = x % 50
242  counter = counter + rand
243  time.sleep(0.001)
244  )");
246 #endif
247 
248  // // By default the least mount of resources are allocated
249  // // increasing it improves performance when optical flow is enabled
250  // auto numShaves = 2;
251  // auto numMemorySlices = 2;
252  // featureTrackerLeft->setHardwareResources(numShaves, numMemorySlices);
253  // featureTrackerRight->setHardwareResources(numShaves, numMemorySlices);
254 
255  // Linking
256  monoLeft->out.link(ve1->input);
257  camRgb->video.link(ve2->input);
258  monoRight->out.link(ve3->input);
259 
260  ve1->bitstream.link(ve1Out->input);
261  ve2->bitstream.link(ve2Out->input);
262  ve3->bitstream.link(ve3Out->input);
263 
264  monoLeft->out.link(stereo->left);
265  monoRight->out.link(stereo->right);
266 
267  camRgb->preview.link(spatialDetectionNetwork->input);
268  camRgb->preview.link(xoutRgb->input);
269  spatialDetectionNetwork->out.link(xoutNN->input);
270 
271  stereo->depth.link(spatialDetectionNetwork->inputDepth);
272  spatialDetectionNetwork->passthroughDepth.link(xoutDepth->input);
273 
274  monoLeft->out.link(edgeDetectorLeft->inputImage);
275  monoRight->out.link(edgeDetectorRight->inputImage);
276  camRgb->video.link(edgeDetectorRgb->inputImage);
277  edgeDetectorLeft->outputImage.link(xoutEdgeLeft->input);
278  edgeDetectorRight->outputImage.link(xoutEdgeRight->input);
279  sysLog->out.link(xoutSysLog->input);
280  xoutSysLog->input.setBlocking(false);
281  xoutSysLog->input.setQueueSize(1);
282 
283 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
284  script1->outputs["out"].link(script2->inputs["in"]);
285  script2->outputs["out"].link(scriptOut->input);
286  script3->outputs["out"].link(script4->inputs["in"]);
287  script4->outputs["out"].link(scriptOut2->input);
288 #endif
289 
290  // monoLeft->out.link(featureTrackerLeft->inputImage);
291  // featureTrackerLeft->outputFeatures.link(xoutTrackedFeaturesLeft->input);
292  // monoRight->out.link(featureTrackerRight->inputImage);
293  // featureTrackerRight->outputFeatures.link(xoutTrackedFeaturesRight->input);
294 
295  // Do not send out rgb edge
296  // edgeDetectorRgb->outputImage.link(xoutEdgeRgb->input);
297 
298  // Connect to device and start pipeline
299  dai::Device device(pipeline);
300 
301  auto usb_speed = device.getUsbSpeed();
302 
303  // Output queues will be used to get the encoded data from the output defined above
304  auto outQ1 = device.getOutputQueue("ve1Out", 30, false);
305  auto outQ2 = device.getOutputQueue("ve2Out", 30, false);
306  auto outQ3 = device.getOutputQueue("ve3Out", 30, false);
307  auto previewQueue = device.getOutputQueue("rgb", 4, false);
308  auto depthQueue = device.getOutputQueue("depth", 4, false);
309  auto detectionNNQueue = device.getOutputQueue("detections", 4, false);
310  auto edgeLeftQueue = device.getOutputQueue(edgeLeftStr, 8, false);
311  auto edgeRightQueue = device.getOutputQueue(edgeRightStr, 8, false);
312  auto edgeRgbQueue = device.getOutputQueue(edgeRgbStr, 8, false);
313  auto qSysInfo = device.getOutputQueue("sysinfo", 4, false);
314 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
315  auto scriptQueue = device.getOutputQueue("script", 8, false);
316  auto script2Queue = device.getOutputQueue("script2", 8, false);
317 #endif
318 
319  // auto outputFeaturesLeftQueue = device.getOutputQueue("trackedFeaturesLeft", 8, false);
320  // auto outputFeaturesRightQueue = device.getOutputQueue("trackedFeaturesRight", 8, false);
321 
322 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
323  auto startTime = steady_clock::now();
324  int counter = 0;
325  float fps = 0;
326  auto color = cv::Scalar(255, 255, 255);
327 #endif
328 
329  mutex countersMtx;
330  unordered_map<std::string, int> counters;
331 
332  thread countingThread([&countersMtx, &counters, &device, &usb_speed, TEST_TIMEOUT]() {
333  // Initial delay
334  this_thread::sleep_for(5s);
335 
336  auto timeoutStopwatch = steady_clock::now();
337  auto fiveFpsCounter = steady_clock::now();
338  while(alive) {
339  if(steady_clock::now() - fiveFpsCounter >= 5s) {
340  unique_lock<mutex> l(countersMtx);
341 
342  bool failed = counters.size() == 0;
343  cout << "[" << duration_cast<seconds>(steady_clock::now() - timeoutStopwatch).count() << "s] " << "Usb speed " << usb_speed << " " << "FPS: ";
344  for(const auto& kv : counters) {
345  if(kv.second == 0) {
346  failed = true;
347  }
348 
349  cout << kv.first << ": " << kv.second / 5.0f << ", ";
350  }
351  cout << "\n";
352 
353  if(failed) {
354  cout << "Didn't recieve enough frames in time...\n";
355  exit(1);
356  }
357 
358  counters = {};
359  fiveFpsCounter = steady_clock::now();
360  }
361 
362  if(steady_clock::now() - timeoutStopwatch > TEST_TIMEOUT) {
363  alive = false;
364  break;
365  }
366 
367  this_thread::sleep_for(500ms);
368  }
369 
370  // give 5s for graceful shutdown
371  this_thread::sleep_for(5s);
372  device.close();
373  });
374 
375  while(alive) {
376  auto out1 = outQ1->tryGetAll<dai::ImgFrame>();
377  auto out2 = outQ2->tryGetAll<dai::ImgFrame>();
378  auto out3 = outQ3->tryGetAll<dai::ImgFrame>();
379  auto imgFrame = previewQueue->get<dai::ImgFrame>();
380  auto inDet = detectionNNQueue->get<dai::SpatialImgDetections>();
381  auto depth = depthQueue->get<dai::ImgFrame>();
382 
383  auto edgeLefts = edgeLeftQueue->tryGetAll<dai::ImgFrame>();
384  auto edgeRights = edgeRightQueue->tryGetAll<dai::ImgFrame>();
385 
386  auto sysInfo = qSysInfo->tryGet<dai::SystemInformation>();
387  if(sysInfo) {
388  printf("----------------------------------------\n");
389  std::cout << "Usb speed: " << usb_speed << std::endl;
390  printSystemInformation(*sysInfo);
391  printf("----------------------------------------\n");
392  }
393 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
394  auto script = scriptQueue->tryGetAll<dai::Buffer>();
395  auto script2 = script2Queue->tryGetAll<dai::Buffer>();
396 #endif
397 
398  // auto edgeRgbs = edgeRgbQueue->getAll<dai::ImgFrame>();
399 
400  // auto trackedLefts = outputFeaturesLeftQueue->getAll<dai::TrackedFeatures>();
401  // auto trackedRigths = outputFeaturesRightQueue->getAll<dai::TrackedFeatures>();
402 
403  {
404  unique_lock<mutex> l(countersMtx);
405  counters["out1"] += out1.size();
406  counters["out2"] += out2.size();
407  counters["out3"] += out3.size();
408  counters["imgFrame"]++;
409  counters["inDet"]++;
410  counters["depth"]++;
411  counters["edgeLefts"] += edgeLefts.size();
412  counters["edgeRights"] += edgeRights.size();
413 
414 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
415  counters["script"] += script.size();
416  counters["script2"] += script2.size();
417 #endif
418  // counters["trackedLefts"] += trackedLefts.size();
419  // counters["trackedRights"] += trackedRigths.size();
420  }
421 
422 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
423 
425  for(const auto& edgeLeft : edgeLefts) {
426  cv::Mat edgeLeftFrame = edgeLeft->getFrame();
427  cv::imshow(edgeLeftStr, edgeLeftFrame);
428  }
429  for(const auto& edgeRight : edgeRights) {
430  cv::Mat edgeRightFrame = edgeRight->getFrame();
431  cv::imshow(edgeRightStr, edgeRightFrame);
432  }
433  // for(const auto& edgeRgb : edgeRgbs) {
434  // cv::Mat edgeRgbFrame = edgeRgb->getFrame();
435  // cv::imshow(edgeRgbStr, edgeRgbFrame);
436  // }
437 
438  cv::Mat frame = imgFrame->getCvFrame();
439  cv::Mat depthFrame = depth->getFrame(); // depthFrame values are in millimeters
440 
441  cv::Mat depthFrameColor;
442  cv::normalize(depthFrame, depthFrameColor, 255, 0, cv::NORM_INF, CV_8UC1);
443  cv::equalizeHist(depthFrameColor, depthFrameColor);
444  cv::applyColorMap(depthFrameColor, depthFrameColor, cv::COLORMAP_HOT);
445 
446  counter++;
447  auto currentTime = steady_clock::now();
448  auto elapsed = duration_cast<duration<float>>(currentTime - startTime);
449  if(elapsed > seconds(1)) {
450  fps = counter / elapsed.count();
451  counter = 0;
452  startTime = currentTime;
453  }
454 
455  auto detections = inDet->detections;
456 
457  for(const auto& detection : detections) {
458  auto roiData = detection.boundingBoxMapping;
459  auto roi = roiData.roi;
460  roi = roi.denormalize(depthFrameColor.cols, depthFrameColor.rows);
461  auto topLeft = roi.topLeft();
462  auto bottomRight = roi.bottomRight();
463  auto xmin = (int)topLeft.x;
464  auto ymin = (int)topLeft.y;
465  auto xmax = (int)bottomRight.x;
466  auto ymax = (int)bottomRight.y;
467  cv::rectangle(depthFrameColor, cv::Rect(cv::Point(xmin, ymin), cv::Point(xmax, ymax)), color, cv::FONT_HERSHEY_SIMPLEX);
468 
469  int x1 = detection.xmin * frame.cols;
470  int y1 = detection.ymin * frame.rows;
471  int x2 = detection.xmax * frame.cols;
472  int y2 = detection.ymax * frame.rows;
473 
474  uint32_t labelIndex = detection.label;
475  std::string labelStr = to_string(labelIndex);
476  if(labelIndex < labelMap.size()) {
477  labelStr = labelMap[labelIndex];
478  }
479  cv::putText(frame, labelStr, cv::Point(x1 + 10, y1 + 20), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
480  std::stringstream confStr;
481  confStr << std::fixed << std::setprecision(2) << detection.confidence * 100;
482  cv::putText(frame, confStr.str(), cv::Point(x1 + 10, y1 + 35), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
483 
484  std::stringstream depthX;
485  depthX << "X: " << (int)detection.spatialCoordinates.x << " mm";
486  cv::putText(frame, depthX.str(), cv::Point(x1 + 10, y1 + 50), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
487  std::stringstream depthY;
488  depthY << "Y: " << (int)detection.spatialCoordinates.y << " mm";
489  cv::putText(frame, depthY.str(), cv::Point(x1 + 10, y1 + 65), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
490  std::stringstream depthZ;
491  depthZ << "Z: " << (int)detection.spatialCoordinates.z << " mm";
492  cv::putText(frame, depthZ.str(), cv::Point(x1 + 10, y1 + 80), cv::FONT_HERSHEY_TRIPLEX, 0.5, 255);
493 
494  cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
495  }
496 
497  std::stringstream fpsStr;
498  fpsStr << std::fixed << std::setprecision(2) << fps;
499  cv::putText(frame, fpsStr.str(), cv::Point(2, imgFrame->getHeight() - 4), cv::FONT_HERSHEY_TRIPLEX, 0.4, color);
500 
501  cv::imshow("depth", depthFrameColor);
502  cv::imshow("rgb", frame);
503 
504  #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
505  for(auto json : script) {
506  if(json != nullptr) {
507  std::cout << "Script: " << std::string((const char*)json->getData().data(), json->getData().size()) << std::endl;
508  }
509  }
510  for(auto json : script2) {
511  if(json != nullptr) {
512  std::cout << "Script2: " << std::string((const char*)json->getData().data(), json->getData().size()) << std::endl;
513  }
514  }
515  #endif
516 
517  int key = cv::waitKey(1);
518  if(key == 'q' || key == 'Q') {
519  alive = false;
520  break;
521  }
522 
523 #endif
524  }
525 
526  // Clean up the counting thread
527  alive = false;
528  if(countingThread.joinable()) countingThread.join();
529 
530  return 0;
531 }
dai::node::MonoCamera::out
Output out
Definition: MonoCamera.hpp:47
dai::node::VideoEncoder::bitstream
Output bitstream
Definition: VideoEncoder.hpp:30
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::MonoCamera::setFps
void setFps(float fps)
Definition: MonoCamera.cpp:98
sigintHandler
static void sigintHandler(int signum)
Definition: stability_stress_test.cpp:47
dai::node::ColorCamera::setResolution
void setResolution(Properties::SensorResolution resolution)
Set sensor resolution.
Definition: ColorCamera.cpp:169
dai::DeviceBase::close
void close()
Definition: DeviceBase.cpp:516
dai::node::StereoDepth
StereoDepth node. Compute stereo disparity and depth from left-right image pair.
Definition: StereoDepth.hpp:15
dai::node::ColorCamera::setFps
void setFps(float fps)
Definition: ColorCamera.cpp:176
dai::node::ColorCamera::getResolutionWidth
int getResolutionWidth() const
Get sensor resolution width.
Definition: ColorCamera.cpp:429
RGB_FPS
static constexpr int RGB_FPS
Definition: stability_stress_test.cpp:16
labelMap
static const std::vector< std::string > labelMap
Definition: stability_stress_test.cpp:34
alive
static std::atomic< bool > alive
Definition: stability_stress_test.cpp:46
fps
static constexpr int fps
Definition: rgb_depth_aligned.cpp:12
dai::CameraBoardSocket::CAM_A
@ CAM_A
dai::logger::info
void info(const FormatString &fmt, Args &&...args)
Definition: Logging.hpp:78
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::ColorCameraProperties::SensorResolution::THE_4_K
@ THE_4_K
3840 × 2160
printSystemInformation
void printSystemInformation(dai::SystemInformation info)
Definition: stability_stress_test.cpp:20
dai::node::EdgeDetector::setMaxOutputFrameSize
void setMaxOutputFrameSize(int maxFrameSize)
Definition: EdgeDetector.cpp:36
TEST_TIMEOUT
constexpr auto TEST_TIMEOUT
Definition: multiple_devices_test.cpp:14
MONO_FPS
static constexpr int MONO_FPS
Definition: stability_stress_test.cpp:17
dai::Pipeline::setXLinkChunkSize
void setXLinkChunkSize(int sizeBytes)
Definition: Pipeline.hpp:266
dai::SpatialImgDetections
Definition: SpatialImgDetections.hpp:15
dai::node::SystemLogger
SystemLogger node. Send system information periodically.
Definition: SystemLogger.hpp:14
dai::ProcessorType::LEON_MSS
@ LEON_MSS
dai::Device::getOutputQueue
std::shared_ptr< DataOutputQueue > getOutputQueue(const std::string &name)
Definition: Device.cpp:86
dai::ImgFrame::getHeight
unsigned int getHeight() const
Definition: pipeline/datatype/ImgFrame.cpp:56
dai::MonoCameraProperties::SensorResolution::THE_400_P
@ THE_400_P
dai::node::YoloSpatialDetectionNetwork
Definition: SpatialDetectionNetwork.hpp:117
dai::node::EdgeDetector
EdgeDetector node. Performs edge detection using 3x3 Sobel filter.
Definition: EdgeDetector.hpp:19
dai::node::XLinkOut::input
Input input
Definition: XLinkOut.hpp:27
depthai.hpp
dai::node::VideoEncoder::setDefaultProfilePreset
void setDefaultProfilePreset(float fps, Properties::Profile profile)
dai::node::VideoEncoder::out
Output out
Definition: VideoEncoder.hpp:35
dai::node::Script::setScript
void setScript(const std::string &script, const std::string &name="")
Definition: Script.cpp:32
dai::Pipeline::create
std::shared_ptr< N > create()
Definition: Pipeline.hpp:145
dai::node::Script
Definition: Script.hpp:15
dai::SystemInformation
Definition: SystemInformation.hpp:14
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
main
int main(int argc, char **argv)
Definition: stability_stress_test.cpp:51
dai::node::Script::setProcessor
void setProcessor(ProcessorType type)
Definition: Script.cpp:53
dai::node::ColorCamera::getResolutionHeight
int getResolutionHeight() const
Get sensor resolution height.
Definition: ColorCamera.cpp:433
dai::Buffer
Base message - buffer of binary data.
Definition: Buffer.hpp:13
dai::Node::Input::setBlocking
void setBlocking(bool blocking)
Definition: Node.cpp:94
dai::node::ColorCamera::video
Output video
Definition: ColorCamera.hpp:62
dai::node::StereoDepth::PresetMode::HIGH_DENSITY
@ HIGH_DENSITY
dai::Device
Definition: Device.hpp:21
dai::node::Script::inputs
InputMap inputs
Definition: Script.hpp:30
dai::VideoEncoderProperties::Profile::H265_MAIN
@ H265_MAIN
ENCODER_FPS
static constexpr int ENCODER_FPS
Definition: stability_stress_test.cpp:18
dai::DeviceBase::getUsbSpeed
UsbSpeed getUsbSpeed()
Definition: DeviceBase.cpp:1184
std
Definition: Node.hpp:366
dai::node::EdgeDetector::outputImage
Output outputImage
Definition: EdgeDetector.hpp:52
dai::node::Script::outputs
OutputMap outputs
Definition: Script.hpp:35
dai::VideoEncoderProperties::Profile::H264_MAIN
@ H264_MAIN
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::XLinkOut::setStreamName
void setStreamName(const std::string &name)
Definition: XLinkOut.cpp:13
dai::node::VideoEncoder::input
Input input
Definition: VideoEncoder.hpp:25
dai::Node::Input::setQueueSize
void setQueueSize(int size)
Definition: Node.cpp:105
dai::node::EdgeDetector::inputImage
Input inputImage
Definition: EdgeDetector.hpp:47
dai::node::ColorCamera::setCamera
void setCamera(std::string name)
Definition: ColorCamera.cpp:44


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