1 #include <opencv2/opencv.hpp>
5 constexpr
auto FPS = 30.0;
14 auto now = std::chrono::steady_clock::now();
23 auto duration = std::chrono::duration_cast<std::chrono::milliseconds>(
frameTimes.back() -
frameTimes.front()).count();
24 return (
frameTimes.size() - 1) * 1000.0 / duration;
28 std::queue<std::chrono::steady_clock::time_point>
frameTimes;
32 cv::Mat invalidMask = (frameDepth == 0);
33 cv::Mat depthFrameColor;
35 double minDepth = 0.0;
36 double maxDepth = 0.0;
37 cv::minMaxIdx(frameDepth, &minDepth, &maxDepth,
nullptr,
nullptr, ~invalidMask);
38 if(minDepth == maxDepth) {
39 depthFrameColor = cv::Mat::zeros(frameDepth.size(), CV_8UC3);
40 return depthFrameColor;
43 frameDepth.convertTo(logDepth, CV_32F);
45 logDepth.setTo(
log(minDepth), invalidMask);
46 cv::normalize(logDepth, logDepth, 0, 255, cv::NORM_MINMAX, CV_8UC1);
47 cv::applyColorMap(logDepth, depthFrameColor, cv::COLORMAP_JET);
48 depthFrameColor.setTo(cv::Scalar(0, 0, 0), invalidMask);
49 }
catch(
const std::exception& e) {
50 depthFrameColor = cv::Mat::zeros(frameDepth.size(), CV_8UC3);
52 return depthFrameColor;
59 rgbWeight =
static_cast<double>(percentRgb) / 100.0;
80 camRgb->setIspScale(1, 2);
82 xout->setStreamName(
"out");
84 sync->setSyncThreshold(std::chrono::milliseconds(
static_cast<int>(1000 /
FPS)));
86 camRgb->isp.link(sync->inputs[
"rgb"]);
87 camTof->
raw.link(tof->input);
88 tof->depth.link(align->input);
89 align->outputAligned.link(sync->inputs[
"depth_aligned"]);
90 camRgb->isp.link(align->inputAlignTo);
91 sync->out.link(xout->
input);
98 std::string rgbDepthWindowName =
"rgb-depth";
99 cv::namedWindow(rgbDepthWindowName);
100 cv::createTrackbar(
"RGB Weight %", rgbDepthWindowName,
nullptr, 100,
updateBlendWeights);
107 auto frameDepth = messageGroup->get<
dai::ImgFrame>(
"depth_aligned");
109 if(frameRgb && frameDepth) {
113 cv::putText(alignedDepthColorized,
116 cv::FONT_HERSHEY_SIMPLEX,
118 cv::Scalar(255, 255, 255),
121 cv::imshow(
"depth", alignedDepthColorized);
125 cv::imshow(rgbDepthWindowName, blended);
128 int key = cv::waitKey(1);
129 if(key ==
'q' || key ==
'Q') {