5 #include <unordered_map>
12 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
13 #include <opencv2/opencv.hpp>
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);
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"};
46 static std::atomic<bool>
alive{
true};
51 int main(
int argc,
char** argv) {
53 using namespace std::chrono;
56 std::string nnPath(BLOB_PATH);
85 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
107 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
114 ve1Out->setStreamName(
"ve1Out");
121 const auto edgeLeftStr =
"edge left";
122 const auto edgeRightStr =
"edge right";
123 const auto edgeRgbStr =
"edge rgb";
124 const auto edgeCfgStr =
"edge cfg";
128 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
138 camRgb->setPreviewSize(416, 416);
139 camRgb->setInterleaved(
false);
161 spatialDetectionNetwork->setBlobPath(nnPath);
162 spatialDetectionNetwork->setConfidenceThreshold(0.5f);
164 spatialDetectionNetwork->setBoundingBoxScaleFactor(0.5);
165 spatialDetectionNetwork->setDepthLowerThreshold(100);
166 spatialDetectionNetwork->setDepthUpperThreshold(5000);
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);
177 sysLog->setRate(0.2f);
179 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
180 std::string source1 = R
"(
187 dict = {'counter1': counter}
188 b.setData(json.dumps(dict).encode('utf-8'))
189 node.io['out'].send(b)
191 counter = counter + 1
193 std::string source2 = R"(
198 MIN_BUFFER_SIZE = 128
200 t = int( time.time() * 1000.0 )
201 x = ( ((t & 0xff000000) >> 24) + ((t & 0x00ff0000) >> 8) + ((t & 0x0000ff00) << 8) + ((t & 0x000000ff) << 24))
204 buffers = node.io['in'].tryGetAll()
208 data = node.io['in'].get().getData()
209 jsonStr = str(data, 'utf-8')
210 dict = json.loads(jsonStr)
211 dict['counter2'] = counter
214 dicts.append({'counter1': None, 'counter2': counter})
217 b = Buffer(MIN_BUFFER_SIZE + rand * 16)
218 b.setData(json.dumps(dict).encode('utf-8'))
219 node.io['out'].send(b)
221 time.sleep(rand / 1000)
222 counter = counter + 1
225 script1->setScript(source1);
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))
242 counter = counter + rand
256 monoLeft->out.link(ve1->input);
260 ve1->bitstream.link(ve1Out->input);
264 monoLeft->out.link(stereo->left);
265 monoRight->
out.
link(stereo->right);
267 camRgb->preview.link(spatialDetectionNetwork->
input);
268 camRgb->preview.link(xoutRgb->
input);
271 stereo->depth.link(spatialDetectionNetwork->inputDepth);
272 spatialDetectionNetwork->passthroughDepth.link(xoutDepth->
input);
274 monoLeft->out.link(edgeDetectorLeft->inputImage);
276 camRgb->video.link(edgeDetectorRgb->
inputImage);
277 edgeDetectorLeft->outputImage.link(xoutEdgeLeft->
input);
279 sysLog->out.link(xoutSysLog->
input);
283 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
284 script1->outputs[
"out"].link(script2->
inputs[
"in"]);
309 auto detectionNNQueue = device.
getOutputQueue(
"detections", 4,
false);
310 auto edgeLeftQueue = device.
getOutputQueue(edgeLeftStr, 8,
false);
311 auto edgeRightQueue = device.
getOutputQueue(edgeRightStr, 8,
false);
314 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
322 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
323 auto startTime = steady_clock::now();
326 auto color = cv::Scalar(255, 255, 255);
330 unordered_map<std::string, int> counters;
332 thread countingThread([&countersMtx, &counters, &device, &usb_speed,
TEST_TIMEOUT]() {
334 this_thread::sleep_for(5s);
336 auto timeoutStopwatch = steady_clock::now();
337 auto fiveFpsCounter = steady_clock::now();
339 if(steady_clock::now() - fiveFpsCounter >= 5s) {
340 unique_lock<mutex> l(countersMtx);
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) {
349 cout << kv.first <<
": " << kv.second / 5.0f <<
", ";
354 cout <<
"Didn't recieve enough frames in time...\n";
359 fiveFpsCounter = steady_clock::now();
362 if(steady_clock::now() - timeoutStopwatch >
TEST_TIMEOUT) {
367 this_thread::sleep_for(500ms);
371 this_thread::sleep_for(5s);
384 auto edgeRights = edgeRightQueue->tryGetAll<
dai::ImgFrame>();
388 printf(
"----------------------------------------\n");
389 std::cout <<
"Usb speed: " << usb_speed << std::endl;
391 printf(
"----------------------------------------\n");
393 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
394 auto script = scriptQueue->tryGetAll<
dai::Buffer>();
395 auto script2 = script2Queue->tryGetAll<
dai::Buffer>();
404 unique_lock<mutex> l(countersMtx);
405 counters[
"out1"] += out1.size();
406 counters[
"out2"] += out2.size();
407 counters[
"out3"] += out3.size();
408 counters[
"imgFrame"]++;
411 counters[
"edgeLefts"] += edgeLefts.size();
412 counters[
"edgeRights"] += edgeRights.size();
414 #ifdef DEPTHAI_STABILITY_TEST_SCRIPT
415 counters[
"script"] += script.size();
416 counters[
"script2"] += script2.size();
422 #ifdef DEPTHAI_STABILITY_TEST_DEBUG
425 for(
const auto& edgeLeft : edgeLefts) {
426 cv::Mat edgeLeftFrame = edgeLeft->getFrame();
427 cv::imshow(edgeLeftStr, edgeLeftFrame);
429 for(
const auto& edgeRight : edgeRights) {
430 cv::Mat edgeRightFrame = edgeRight->getFrame();
431 cv::imshow(edgeRightStr, edgeRightFrame);
439 cv::Mat depthFrame = depth->getFrame();
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);
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();
452 startTime = currentTime;
455 auto detections = inDet->detections;
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);
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;
474 uint32_t labelIndex = detection.label;
475 std::string labelStr =
to_string(labelIndex);
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);
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);
494 cv::rectangle(frame, cv::Rect(cv::Point(x1, y1), cv::Point(x2, y2)), color, cv::FONT_HERSHEY_SIMPLEX);
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);
501 cv::imshow(
"depth", depthFrameColor);
502 cv::imshow(
"rgb", frame);
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;
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;
517 int key = cv::waitKey(1);
518 if(key ==
'q' || key ==
'Q') {
528 if(countingThread.joinable()) countingThread.join();