37 #include <opencv2/calib3d/calib3d.hpp> 38 #include <opencv2/imgproc/imgproc.hpp> 39 #include <opencv2/video/tracking.hpp> 40 #include <opencv2/highgui/highgui.hpp> 41 #include <opencv2/imgproc/types_c.h> 45 #if CV_MAJOR_VERSION >= 3 46 #include <opencv2/photo/photo.hpp> 56 float ssd(
const cv::Mat & windowLeft,
const cv::Mat & windowRight)
58 UASSERT_MSG(windowLeft.type() == CV_8UC1 || windowLeft.type() == CV_32FC1 || windowLeft.type() == CV_16SC2,
uFormat(
"Type=%d", windowLeft.type()).c_str());
59 UASSERT(windowLeft.type() == windowRight.type());
60 UASSERT_MSG(windowLeft.rows == windowRight.rows,
uFormat(
"%d vs %d", windowLeft.rows, windowRight.rows).c_str());
61 UASSERT_MSG(windowLeft.cols == windowRight.cols,
uFormat(
"%d vs %d", windowLeft.cols, windowRight.cols).c_str());
64 for(
int v=0; v<windowLeft.rows; ++v)
66 for(
int u=0; u<windowLeft.cols; ++u)
69 if(windowLeft.type() == CV_8UC1)
71 s = float(windowLeft.at<
unsigned char>(v,u))-float(windowRight.at<
unsigned char>(v,u));
73 else if(windowLeft.type() == CV_32FC1)
75 s = windowLeft.at<
float>(v,u)-windowRight.at<
float>(v,u);
77 else if(windowLeft.type() == CV_16SC2)
79 float sL = float(windowLeft.at<cv::Vec2s>(v,u)[0])*0.5f+float(windowLeft.at<cv::Vec2s>(v,u)[1])*0.5f;
80 float sR = float(windowRight.at<cv::Vec2s>(v,u)[0])*0.5f+float(windowRight.at<cv::Vec2s>(v,u)[1])*0.5f;
91 float sad(
const cv::Mat & windowLeft,
const cv::Mat & windowRight)
93 UASSERT_MSG(windowLeft.type() == CV_8UC1 || windowLeft.type() == CV_32FC1 || windowLeft.type() == CV_16SC2,
uFormat(
"Type=%d", windowLeft.type()).c_str());
94 UASSERT(windowLeft.type() == windowRight.type());
95 UASSERT_MSG(windowLeft.rows == windowRight.rows,
uFormat(
"%d vs %d", windowLeft.rows, windowRight.rows).c_str());
96 UASSERT_MSG(windowLeft.cols == windowRight.cols,
uFormat(
"%d vs %d", windowLeft.cols, windowRight.cols).c_str());
99 for(
int v=0; v<windowLeft.rows; ++v)
101 for(
int u=0; u<windowLeft.cols; ++u)
103 if(windowLeft.type() == CV_8UC1)
105 score += fabs(
float(windowLeft.at<
unsigned char>(v,u))-
float(windowRight.at<
unsigned char>(v,u)));
107 else if(windowLeft.type() == CV_32FC1)
109 score += fabs(windowLeft.at<
float>(v,u)-windowRight.at<
float>(v,u));
111 else if(windowLeft.type() == CV_16SC2)
113 float sL = float(windowLeft.at<cv::Vec2s>(v,u)[0])*0.5f+float(windowLeft.at<cv::Vec2s>(v,u)[1])*0.5f;
114 float sR = float(windowRight.at<cv::Vec2s>(v,u)[0])*0.5f+float(windowRight.at<cv::Vec2s>(v,u)[1])*0.5f;
115 score += fabs(sL - sR);
123 const cv::Mat & leftImage,
124 const cv::Mat & rightImage,
125 const std::vector<cv::Point2f> & leftCorners,
126 std::vector<unsigned char> & status,
134 UDEBUG(
"winSize=(%d,%d)", winSize.width, winSize.height);
135 UDEBUG(
"maxLevel=%d", maxLevel);
136 UDEBUG(
"minDisparity=%f", minDisparityF);
137 UDEBUG(
"maxDisparity=%f", maxDisparityF);
138 UDEBUG(
"iterations=%d", iterations);
139 UDEBUG(
"ssdApproach=%d", ssdApproach?1:0);
140 UASSERT(minDisparityF >= 0.0
f && minDisparityF <= maxDisparityF);
143 if(winSize.width%2 == 0)
147 if(winSize.height%2 == 0)
152 cv::Size halfWin((winSize.width-1)/2, (winSize.height-1)/2);
155 double pyramidTime = 0.0;
156 double disparityTime = 0.0;
157 double subpixelTime = 0.0;
159 std::vector<cv::Point2f> rightCorners(leftCorners.size());
160 std::vector<cv::Mat> leftPyramid, rightPyramid;
161 maxLevel = cv::buildOpticalFlowPyramid( leftImage, leftPyramid, winSize, maxLevel,
false);
162 maxLevel = cv::buildOpticalFlowPyramid( rightImage, rightPyramid, winSize, maxLevel,
false);
163 pyramidTime = timer.
ticks();
165 status = std::vector<unsigned char>(leftCorners.size(), 0);
166 int totalIterations = 0;
171 for(
unsigned int i=0; i<leftCorners.size(); ++i)
174 float bestScore = -1.0f;
175 int bestScoreIndex = -1;
176 int tmpMinDisparity = minDisparity;
177 int tmpMaxDisparity = maxDisparity;
179 int iterationsDone = 0;
180 for(
int level=maxLevel; level>=0; --level)
182 UASSERT(level < (
int)leftPyramid.size());
184 cv::Point2i center(
int(leftCorners[i].x/
float(1<<level)),
int(leftCorners[i].y/
float(1<<level)));
189 int localMaxDisparity = -tmpMaxDisparity / (1<<level);
190 int localMinDisparity = -tmpMinDisparity / (1<<level);
192 if(center.x-halfWin.width-(level==0?1:0) >=0 && center.x+halfWin.width+(level==0?1:0) < leftPyramid[level].cols &&
193 center.y-halfWin.height >=0 && center.y+halfWin.height < leftPyramid[level].rows)
195 cv::Mat windowLeft(leftPyramid[level],
196 cv::Range(center.y-halfWin.height,center.y+halfWin.height+1),
197 cv::Range(center.x-halfWin.width,center.x+halfWin.width+1));
198 int minCol = center.x+localMaxDisparity-halfWin.width;
201 localMaxDisparity -= minCol;
204 if(localMinDisparity > localMaxDisparity)
206 int length = localMinDisparity-localMaxDisparity+1;
207 std::vector<float> scores = std::vector<float>(
length, 0.0f);
209 for(
int d=localMinDisparity;
d>localMaxDisparity; --
d)
212 cv::Mat windowRight(rightPyramid[level],
213 cv::Range(center.y-halfWin.height,center.y+halfWin.height+1),
214 cv::Range(center.x+
d-halfWin.width,center.x+
d+halfWin.width+1));
215 scores[oi] = ssdApproach?
ssd(windowLeft, windowRight):
sad(windowLeft, windowRight);
216 if(scores[oi] > 0 && (bestScore < 0.0
f || scores[oi] < bestScore))
219 bestScore = scores[oi];
226 float m =
uMean(scores);
234 if(bestScoreIndex>=0)
236 if(bestScoreIndex>=0 && level>0)
238 tmpMaxDisparity = tmpMinDisparity+(bestScoreIndex+1)*(1<<level);
239 tmpMaxDisparity+=tmpMaxDisparity%level;
240 if(tmpMaxDisparity > maxDisparity)
242 tmpMaxDisparity = maxDisparity;
244 tmpMinDisparity = tmpMinDisparity+(bestScoreIndex-1)*(1<<level);
245 tmpMinDisparity -= tmpMinDisparity%level;
246 if(tmpMinDisparity < minDisparity)
248 tmpMinDisparity = minDisparity;
255 disparityTime+=timer.
ticks();
256 totalIterations+=iterationsDone;
258 if(bestScoreIndex>=0)
261 int d = -(tmpMinDisparity+bestScoreIndex);
263 cv::Mat windowLeft(winSize, CV_32FC1);
264 cv::Mat windowRight(winSize, CV_32FC1);
265 cv::getRectSubPix(leftPyramid[0],
270 if(leftCorners[i].x !=
float(
int(leftCorners[i].x)))
273 cv::getRectSubPix(rightPyramid[0],
275 cv::Point2f(leftCorners[i].x+
float(d), leftCorners[i].y),
278 bestScore = ssdApproach?
ssd(windowLeft, windowRight):
sad(windowLeft, windowRight);
281 float xc = leftCorners[i].x+float(d);
282 float vc = bestScore;
284 std::map<float, float> cache;
286 for(
int it=0; it<iterations; ++it)
290 float v1 =
uValue(cache, x1, 0.0
f);
291 float v2 =
uValue(cache, x2, 0.0
f);
294 cv::getRectSubPix(rightPyramid[0],
296 cv::Point2f(x1, leftCorners[i].y),
299 v1 = ssdApproach?
ssd(windowLeft, windowRight):
sad(windowLeft, windowRight);
303 cv::getRectSubPix(rightPyramid[0],
305 cv::Point2f(x2, leftCorners[i].y),
308 v2 = ssdApproach?
ssd(windowLeft, windowRight):
sad(windowLeft, windowRight);
311 float previousXc = xc;
312 float previousVc = vc;
314 xc = v1<vc&&v1<v2?x1:v2<vc&&v2<v1?x2:xc;
315 vc = v1<vc&&v1<v2?v1:v2<vc&&v2<v1?v2:vc;
323 cache.insert(std::make_pair(previousXc, previousVc));
327 float(leftCorners[i].x - xc) <= minDisparityF)
334 rightCorners[i] = cv::Point2f(xc, leftCorners[i].y);
335 status[i] = reject?0:1;
338 if(leftCorners[i].x+
float(d) != xc)
345 subpixelTime+=timer.
ticks();
347 UDEBUG(
"SubPixel=%d/%d added (total=%d)", noSubPixel, added, (
int)status.size());
348 UDEBUG(
"totalIterations=%d", totalIterations);
349 UDEBUG(
"Time pyramid = %f s", pyramidTime);
350 UDEBUG(
"Time disparity = %f s", disparityTime);
351 UDEBUG(
"Time sub-pixel = %f s", subpixelTime);
358 #define CV_DESCALE(x,n) (((x) + (1 << ((n)-1))) >> (n)) 372 cv::InputArray _prevPts, cv::InputOutputArray _nextPts,
373 cv::OutputArray _status, cv::OutputArray _err,
374 cv::Size winSize,
int maxLevel,
375 cv::TermCriteria criteria,
376 int flags,
double minEigThreshold )
378 cv::Mat prevPtsMat = _prevPts.getMat();
379 const int derivDepth = cv::DataType<short>::depth;
381 CV_Assert( maxLevel >= 0 && winSize.width > 2 && winSize.height > 2 );
383 int level=0, i, npoints;
384 CV_Assert( (npoints = prevPtsMat.checkVector(2, CV_32F,
true)) >= 0 );
394 if( !(flags & cv::OPTFLOW_USE_INITIAL_FLOW) )
395 _nextPts.create(prevPtsMat.size(), prevPtsMat.type(), -1,
true);
397 cv::Mat nextPtsMat = _nextPts.getMat();
398 CV_Assert( nextPtsMat.checkVector(2, CV_32F,
true) == npoints );
400 const cv::Point2f* prevPts = prevPtsMat.ptr<cv::Point2f>();
401 cv::Point2f* nextPts = nextPtsMat.ptr<cv::Point2f>();
403 _status.create((
int)npoints, 1, CV_8U, -1,
true);
404 cv::Mat statusMat = _status.getMat(), errMat;
405 CV_Assert( statusMat.isContinuous() );
406 uchar* status = statusMat.ptr();
409 for( i = 0; i < npoints; i++ )
414 _err.create((
int)npoints, 1, CV_32F, -1,
true);
415 errMat = _err.getMat();
416 CV_Assert( errMat.isContinuous() );
417 err = errMat.ptr<
float>();
420 std::vector<cv::Mat> prevPyr, nextPyr;
427 if(_prevImg.kind() != cv::_InputArray::STD_VECTOR_MAT)
430 maxLevel = cv::buildOpticalFlowPyramid(_prevImg, prevPyr, winSize, maxLevel,
true);
432 else if(_prevImg.kind() == cv::_InputArray::STD_VECTOR_MAT)
434 _prevImg.getMatVector(prevPyr);
437 levels1 = int(prevPyr.size()) - 1;
438 CV_Assert(levels1 >= 0);
440 if (levels1 % 2 == 1 && prevPyr[0].channels() * 2 == prevPyr[1].channels() && prevPyr[1].depth() == derivDepth)
451 prevPyr[lvlStep1].locateROI(fullSize, ofs);
452 CV_Assert(ofs.x >= winSize.width && ofs.y >= winSize.height
453 && ofs.x + prevPyr[lvlStep1].cols + winSize.width <= fullSize.width
454 && ofs.y + prevPyr[lvlStep1].rows + winSize.height <= fullSize.height);
457 if(levels1 < maxLevel)
460 if(_nextImg.kind() != cv::_InputArray::STD_VECTOR_MAT)
463 maxLevel = cv::buildOpticalFlowPyramid(_nextImg, nextPyr, winSize, maxLevel,
false);
465 else if(_nextImg.kind() == cv::_InputArray::STD_VECTOR_MAT)
467 _nextImg.getMatVector(nextPyr);
470 levels2 = int(nextPyr.size()) - 1;
471 CV_Assert(levels2 >= 0);
473 if (levels2 % 2 == 1 && nextPyr[0].channels() * 2 == nextPyr[1].channels() && nextPyr[1].depth() == derivDepth)
484 nextPyr[lvlStep2].locateROI(fullSize, ofs);
485 CV_Assert(ofs.x >= winSize.width && ofs.y >= winSize.height
486 && ofs.x + nextPyr[lvlStep2].cols + winSize.width <= fullSize.width
487 && ofs.y + nextPyr[lvlStep2].rows + winSize.height <= fullSize.height);
490 if(levels2 < maxLevel)
493 if( (criteria.type & cv::TermCriteria::COUNT) == 0 )
494 criteria.maxCount = 30;
497 if( (criteria.type & cv::TermCriteria::EPS) == 0 )
498 criteria.epsilon = 0.01;
501 criteria.epsilon *= criteria.epsilon;
504 for( level = maxLevel; level >= 0; level-- )
506 cv::Mat derivI = prevPyr[level * lvlStep1 + 1];
508 CV_Assert(prevPyr[level * lvlStep1].size() == nextPyr[level * lvlStep2].size());
509 CV_Assert(prevPyr[level * lvlStep1].type() == nextPyr[level * lvlStep2].type());
511 const cv::Mat & prevImg = prevPyr[level * lvlStep1];
512 const cv::Mat & prevDeriv = derivI;
513 const cv::Mat & nextImg = nextPyr[level * lvlStep2];
517 cv::Point2f halfWin((winSize.width-1)*0.5f, (winSize.height-1)*0.5f);
518 const cv::Mat& I = prevImg;
519 const cv::Mat& J = nextImg;
520 const cv::Mat& derivI = prevDeriv;
522 int j, cn = I.channels(), cn2 = cn*2;
523 cv::AutoBuffer<short> _buf(winSize.area()*(cn + cn2));
524 int derivDepth = cv::DataType<short>::depth;
526 cv::Mat IWinBuf(winSize, CV_MAKETYPE(derivDepth, cn), (
short*)_buf);
527 cv::Mat derivIWinBuf(winSize, CV_MAKETYPE(derivDepth, cn2), (
short*)_buf + winSize.area()*cn);
529 for(
int ptidx = 0; ptidx < npoints; ptidx++ )
531 cv::Point2f prevPt = prevPts[ptidx]*(float)(1./(1 << level));
533 if( level == maxLevel )
535 if( flags & cv::OPTFLOW_USE_INITIAL_FLOW )
536 nextPt = nextPts[ptidx]*(float)(1./(1 << level));
541 nextPt = nextPts[ptidx]*2.f;
542 nextPts[ptidx] = nextPt;
544 cv::Point2i iprevPt, inextPt;
546 iprevPt.x = cvFloor(prevPt.x);
547 iprevPt.y = cvFloor(prevPt.y);
549 if( iprevPt.x < -winSize.width || iprevPt.x >= derivI.cols ||
550 iprevPt.y < -winSize.height || iprevPt.y >= derivI.rows )
555 status[ptidx] =
false;
562 float a = prevPt.x - iprevPt.x;
563 float b = prevPt.y - iprevPt.y;
564 const int W_BITS = 14, W_BITS1 = 14;
565 const float FLT_SCALE = 1.f/(1 << 20);
566 int iw00 = cvRound((1.
f - a)*(1.
f - b)*(1 << W_BITS));
567 int iw01 = cvRound(a*(1.
f - b)*(1 << W_BITS));
568 int iw10 = cvRound((1.
f - a)*b*(1 << W_BITS));
569 int iw11 = (1 << W_BITS) - iw00 - iw01 - iw10;
571 int dstep = (int)(derivI.step/derivI.elemSize1());
572 int stepI = (int)(I.step/I.elemSize1());
573 int stepJ = (int)(J.step/J.elemSize1());
574 acctype iA11 = 0, iA12 = 0, iA22 = 0;
579 for( y = 0; y < winSize.height; y++ )
581 const uchar* src = I.ptr() + (y + iprevPt.y)*stepI + iprevPt.x*cn;
582 const short* dsrc = derivI.ptr<
short>() + (y + iprevPt.y)*dstep + iprevPt.x*cn2;
584 short* Iptr = IWinBuf.ptr<
short>(y);
585 short* dIptr = derivIWinBuf.ptr<
short>(y);
589 for( ; x < winSize.width*cn; x++, dsrc += 2, dIptr += 2 )
591 int ival =
CV_DESCALE(src[x]*iw00 + src[x+cn]*iw01 +
592 src[x+stepI]*iw10 + src[x+stepI+cn]*iw11, W_BITS1-5);
593 int ixval =
CV_DESCALE(dsrc[0]*iw00 + dsrc[cn2]*iw01 +
594 dsrc[dstep]*iw10 + dsrc[dstep+cn2]*iw11, W_BITS1);
595 int iyval =
CV_DESCALE(dsrc[1]*iw00 + dsrc[cn2+1]*iw01 + dsrc[dstep+1]*iw10 +
596 dsrc[dstep+cn2+1]*iw11, W_BITS1);
598 Iptr[x] = (short)ival;
599 dIptr[0] = (short)ixval;
600 dIptr[1] = (short)iyval;
608 A11 = iA11*FLT_SCALE;
609 A12 = iA12*FLT_SCALE;
610 A22 = iA22*FLT_SCALE;
612 float D = A11*A22 - A12*A12;
613 float minEig = (A22 + A11 -
std::sqrt((A11-A22)*(A11-A22) +
614 4.
f*A12*A12))/(2*winSize.width*winSize.height);
616 if( err && (flags & cv::OPTFLOW_LK_GET_MIN_EIGENVALS) != 0 )
617 err[ptidx] = (
float)minEig;
619 if( minEig < minEigThreshold || D < FLT_EPSILON )
621 if( level == 0 && status )
622 status[ptidx] =
false;
629 cv::Point2f prevDelta;
631 for( j = 0; j < criteria.maxCount; j++ )
633 inextPt.x = cvFloor(nextPt.x);
634 inextPt.y = cvFloor(nextPt.y);
636 if( inextPt.x < -winSize.width || inextPt.x >= J.cols ||
637 inextPt.y < -winSize.height || inextPt.y >= J.rows )
639 if( level == 0 && status )
640 status[ptidx] =
false;
644 a = nextPt.x - inextPt.x;
645 b = nextPt.y - inextPt.y;
646 iw00 = cvRound((1.
f - a)*(1.
f - b)*(1 << W_BITS));
647 iw01 = cvRound(a*(1.
f - b)*(1 << W_BITS));
648 iw10 = cvRound((1.
f - a)*b*(1 << W_BITS));
649 iw11 = (1 << W_BITS) - iw00 - iw01 - iw10;
650 acctype ib1 = 0, ib2 = 0;
653 for( y = 0; y < winSize.height; y++ )
655 const uchar* Jptr = J.ptr() + (y + inextPt.y)*stepJ + inextPt.x*cn;
656 const short* Iptr = IWinBuf.ptr<
short>(y);
657 const short* dIptr = derivIWinBuf.ptr<
short>(y);
661 for( ; x < winSize.width*cn; x++, dIptr += 2 )
663 int diff =
CV_DESCALE(Jptr[x]*iw00 + Jptr[x+cn]*iw01 +
664 Jptr[x+stepJ]*iw10 + Jptr[x+stepJ+cn]*iw11,
665 W_BITS1-5) - Iptr[x];
674 cv::Point2f delta( (
float)((A12*b2 - A22*b1) * D),
679 nextPts[ptidx] = nextPt + halfWin;
681 if( delta.ddot(delta) <= criteria.epsilon )
684 if( j > 0 &&
std::abs(delta.x + prevDelta.x) < 0.01 &&
685 std::abs(delta.y + prevDelta.y) < 0.01 )
687 nextPts[ptidx] -= delta*0.5f;
693 if( status[ptidx] && err && level == 0 && (flags & cv::OPTFLOW_LK_GET_MIN_EIGENVALS) == 0 )
695 cv::Point2f nextPoint = nextPts[ptidx] - halfWin;
696 cv::Point inextPoint;
698 inextPoint.x = cvFloor(nextPoint.x);
699 inextPoint.y = cvFloor(nextPoint.y);
701 if( inextPoint.x < -winSize.width || inextPoint.x >= J.cols ||
702 inextPoint.y < -winSize.height || inextPoint.y >= J.rows )
705 status[ptidx] =
false;
709 float aa = nextPoint.x - inextPoint.x;
710 float bb = nextPoint.y - inextPoint.y;
711 iw00 = cvRound((1.
f - aa)*(1.
f - bb)*(1 << W_BITS));
712 iw01 = cvRound(aa*(1.
f - bb)*(1 << W_BITS));
713 iw10 = cvRound((1.
f - aa)*bb*(1 << W_BITS));
714 iw11 = (1 << W_BITS) - iw00 - iw01 - iw10;
717 for( y = 0; y < winSize.height; y++ )
719 const uchar* Jptr = J.ptr() + (y + inextPoint.y)*stepJ + inextPoint.x*cn;
720 const short* Iptr = IWinBuf.ptr<
short>(y);
722 for( x = 0; x < winSize.width*cn; x++ )
724 int diff =
CV_DESCALE(Jptr[x]*iw00 + Jptr[x+cn]*iw01 +
725 Jptr[x+stepJ]*iw10 + Jptr[x+stepJ+cn]*iw11,
726 W_BITS1-5) - Iptr[x];
730 err[ptidx] = errval * 1.f/(32*winSize.width*cn*winSize.height);
739 const cv::Mat & leftImage,
740 const cv::Mat & rightImage,
743 UASSERT(!leftImage.empty() && !rightImage.empty());
744 UASSERT(leftImage.cols == rightImage.cols && leftImage.rows == rightImage.rows);
745 UASSERT((leftImage.type() == CV_8UC1 || leftImage.type() == CV_8UC3) && rightImage.type() == CV_8UC1);
748 if(leftImage.channels() == 3)
750 cv::cvtColor(leftImage, leftMono, CV_BGR2GRAY);
754 leftMono = leftImage;
764 float fx,
float baseline,
767 UASSERT(!disparity.empty() && (disparity.type() == CV_32FC1 || disparity.type() == CV_16SC1));
768 UASSERT(type == CV_32FC1 || type == CV_16UC1);
769 cv::Mat depth = cv::Mat::zeros(disparity.rows, disparity.cols, type);
770 int countOverMax = 0;
771 for (
int i = 0; i < disparity.rows; i++)
773 for (
int j = 0; j < disparity.cols; j++)
775 float disparity_value = disparity.type() == CV_16SC1?float(disparity.at<
short>(i,j))/16.0f:disparity.at<
float>(i,j);
776 if (disparity_value > 0.0
f)
779 float d = baseline * fx / disparity_value;
782 if(depth.type() == CV_32FC1)
784 depth.at<
float>(i,j) = d;
788 if(d*1000.0
f <= (
float)USHRT_MAX)
790 depth.at<
unsigned short>(i,j) = (
unsigned short)(d*1000.0f);
803 UWARN(
"Depth conversion error, %d depth values ignored because they are over the maximum depth allowed (65535 mm).", countOverMax);
809 const cv::Mat & leftImage,
810 const cv::Mat & rightImage,
811 const std::vector<cv::Point2f> & leftCorners,
819 UASSERT(!leftImage.empty() && !rightImage.empty() &&
820 leftImage.type() == CV_8UC1 && rightImage.type() == CV_8UC1 &&
821 leftImage.cols == rightImage.cols &&
822 leftImage.rows == rightImage.rows);
826 std::vector<unsigned char> status;
827 std::vector<float> err;
828 std::vector<cv::Point2f> rightCorners;
829 UDEBUG(
"cv::calcOpticalFlowPyrLK() begin");
830 cv::calcOpticalFlowPyrLK(
837 cv::Size(flowWinSize, flowWinSize), flowMaxLevel,
838 cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, flowIterations, flowEps),
839 cv::OPTFLOW_LK_GET_MIN_EIGENVALS, 1
e-4);
840 UDEBUG(
"cv::calcOpticalFlowPyrLK() end");
846 const cv::Size & disparitySize,
847 const std::vector<cv::Point2f> & leftCorners,
848 const std::vector<cv::Point2f> & rightCorners,
849 const std::vector<unsigned char> &
mask)
851 UASSERT(leftCorners.size() == rightCorners.size());
852 UASSERT(mask.size() == 0 || mask.size() == leftCorners.size());
853 cv::Mat disparity = cv::Mat::zeros(disparitySize, CV_32FC1);
854 for(
unsigned int i=0; i<leftCorners.size(); ++i)
856 if(mask.empty() || mask[i])
858 cv::Point2i dispPt(
int(leftCorners[i].y+0.5
f),
int(leftCorners[i].x+0.5
f));
859 UASSERT(dispPt.x >= 0 && dispPt.x < disparitySize.width);
860 UASSERT(dispPt.y >= 0 && dispPt.y < disparitySize.height);
861 disparity.at<
float>(dispPt.y, dispPt.x) = leftCorners[i].x - rightCorners[i].x;
868 const cv::Mat & leftImage,
869 const std::vector<cv::Point2f> & leftCorners,
870 const std::vector<cv::Point2f> & rightCorners,
871 const std::vector<unsigned char> &
mask,
872 float fx,
float baseline)
874 UASSERT(!leftImage.empty() && leftCorners.size() == rightCorners.size());
875 UASSERT(mask.size() == 0 || mask.size() == leftCorners.size());
876 cv::Mat depth = cv::Mat::zeros(leftImage.rows, leftImage.cols, CV_32FC1);
877 for(
unsigned int i=0; i<leftCorners.size(); ++i)
879 if(mask.size() == 0 || mask[i])
881 float disparity = leftCorners[i].x - rightCorners[i].x;
884 float d = baseline * fx / disparity;
885 depth.at<
float>(int(leftCorners[i].y+0.5
f), int(leftCorners[i].x+0.5
f)) = d;
894 UASSERT(depth32F.empty() || depth32F.type() == CV_32FC1);
896 if(!depth32F.empty())
898 depth16U = cv::Mat(depth32F.rows, depth32F.cols, CV_16UC1);
899 int countOverMax = 0;
900 for(
int i=0; i<depth32F.rows; ++i)
902 for(
int j=0; j<depth32F.cols; ++j)
904 float depth = (depth32F.at<
float>(i,j)*1000.0
f);
905 unsigned short depthMM = 0;
906 if(depth > 0 && depth <= (
float)USHRT_MAX)
908 depthMM = (
unsigned short)depth;
910 else if(depth > (
float)USHRT_MAX)
914 depth16U.at<
unsigned short>(i, j) = depthMM;
919 UWARN(
"Depth conversion error, %d depth values ignored because " 920 "they are over the maximum depth allowed (65535 mm). Is the depth " 921 "image really in meters? 32 bits images should be in meters, " 922 "and 16 bits should be in mm.", countOverMax);
930 UASSERT(depth16U.empty() || depth16U.type() == CV_16UC1);
932 if(!depth16U.empty())
934 depth32F = cv::Mat(depth16U.rows, depth16U.cols, CV_32FC1);
935 for(
int i=0; i<depth16U.rows; ++i)
937 for(
int j=0; j<depth16U.cols; ++j)
939 float depth = float(depth16U.at<
unsigned short>(i,j))/1000.0f;
940 depth32F.at<
float>(i, j) = depth;
948 const cv::Mat & depthImage,
951 float depthErrorRatio,
952 bool estWithNeighborsIfNull)
955 UASSERT(depthImage.type() == CV_16UC1 || depthImage.type() == CV_32FC1);
959 if(u == depthImage.cols && x<
float(depthImage.cols))
961 u = depthImage.cols - 1;
963 if(v == depthImage.rows && y<
float(depthImage.rows))
965 v = depthImage.rows - 1;
968 if(!(u >=0 && u<depthImage.cols && v >=0 && v<depthImage.rows))
970 UDEBUG(
"!(x >=0 && x<depthImage.cols && y >=0 && y<depthImage.rows) cond failed! returning bad point. (x=%f (u=%d), y=%f (v=%d), cols=%d, rows=%d)",
971 x,u,y,v,depthImage.cols, depthImage.rows);
975 bool isInMM = depthImage.type() == CV_16UC1;
985 int u_end =
std::min(u+1, depthImage.cols-1);
986 int v_end =
std::min(v+1, depthImage.rows-1);
991 if(depthImage.at<
unsigned short>(v,u) > 0 &&
994 depth = float(depthImage.at<
unsigned short>(v,u))*0.001f;
999 depth = depthImage.at<
float>(v,u);
1002 if((depth==0.0
f || !
uIsFinite(depth)) && estWithNeighborsIfNull)
1007 for(
int uu = u_start; uu <= u_end; ++uu)
1009 for(
int vv = v_start; vv <= v_end; ++vv)
1011 if((uu == u && vv!=v) || (uu != u && vv==v))
1016 if(depthImage.at<
unsigned short>(vv,uu) > 0 &&
1019 d = float(depthImage.at<
unsigned short>(vv,uu))*0.001f;
1024 d = depthImage.at<
float>(vv,uu);
1035 float depthError = depthErrorRatio * tmp;
1036 if(fabs(d - tmp/
float(count)) < depthError)
1049 depth = tmp/float(count);
1057 float sumWeights = 0.0f;
1058 float sumDepths = 0.0f;
1059 for(
int uu = u_start; uu <= u_end; ++uu)
1061 for(
int vv = v_start; vv <= v_end; ++vv)
1063 if(!(uu == u && vv == v))
1068 if(depthImage.at<
unsigned short>(vv,uu) > 0 &&
1071 d = float(depthImage.at<
unsigned short>(vv,uu))*0.001f;
1076 d = depthImage.at<
float>(vv,uu);
1079 float depthError = depthErrorRatio * depth;
1082 if(d != 0.0
f &&
uIsFinite(d) && fabs(d - depth) < depthError)
1084 if(uu == u || vv == v)
1103 depth = (depth+sumDepths)/sumWeights;
1113 cv::Rect
computeRoi(
const cv::Mat & image,
const std::string & roiRatios)
1118 cv::Rect
computeRoi(
const cv::Size & imageSize,
const std::string & roiRatios)
1120 std::list<std::string> strValues =
uSplit(roiRatios,
' ');
1121 if(strValues.size() != 4)
1123 UERROR(
"The number of values must be 4 (roi=\"%s\")", roiRatios.c_str());
1127 std::vector<float> values(4);
1129 for(std::list<std::string>::iterator iter = strValues.begin(); iter!=strValues.end(); ++iter)
1135 if(values[0] >= 0 && values[0] < 1 && values[0] < 1.0
f-values[1] &&
1136 values[1] >= 0 && values[1] < 1 && values[1] < 1.0
f-values[0] &&
1137 values[2] >= 0 && values[2] < 1 && values[2] < 1.0
f-values[3] &&
1138 values[3] >= 0 && values[3] < 1 && values[3] < 1.0
f-values[2])
1144 UERROR(
"The roi ratios are not valid (roi=\"%s\")", roiRatios.c_str());
1150 cv::Rect
computeRoi(
const cv::Mat & image,
const std::vector<float> & roiRatios)
1155 cv::Rect
computeRoi(
const cv::Size & imageSize,
const std::vector<float> & roiRatios)
1157 if(imageSize.height!=0 && imageSize.width!= 0 && roiRatios.size() == 4)
1159 float width = imageSize.width;
1160 float height = imageSize.height;
1161 cv::Rect roi(0, 0, width, height);
1162 UDEBUG(
"roi ratios = %f, %f, %f, %f", roiRatios[0],roiRatios[1],roiRatios[2],roiRatios[3]);
1163 UDEBUG(
"roi = %d, %d, %d, %d", roi.x, roi.y, roi.width, roi.height);
1166 if(roiRatios[0] > 0 && roiRatios[0] < 1.0
f - roiRatios[1])
1168 roi.x = width * roiRatios[0];
1172 if(roiRatios[1] > 0 && roiRatios[1] < 1.0
f - roiRatios[0])
1174 roi.width -= width * roiRatios[1];
1179 if(roiRatios[2] > 0 && roiRatios[2] < 1.0
f - roiRatios[3])
1181 roi.y = height * roiRatios[2];
1185 if(roiRatios[3] > 0 && roiRatios[3] < 1.0
f - roiRatios[2])
1187 roi.height -= height * roiRatios[3];
1189 roi.height -= roi.y;
1190 UDEBUG(
"roi = %d, %d, %d, %d", roi.x, roi.y, roi.width, roi.height);
1196 UERROR(
"Image is null or _roiRatios(=%d) != 4", roiRatios.size());
1201 cv::Mat
decimate(
const cv::Mat & image,
int decimation)
1209 if((image.type() == CV_32FC1 || image.type()==CV_16UC1))
1211 UASSERT_MSG(image.rows % decimation == 0 && image.cols % decimation == 0,
1212 uFormat(
"Decimation of depth images should be exact! (decimation=%d, size=%dx%d)",
1213 decimation, image.cols, image.rows).c_str());
1215 out = cv::Mat(image.rows/decimation, image.cols/decimation, image.type());
1216 if(image.type() == CV_32FC1)
1218 for(
int j=0; j<out.rows; ++j)
1220 for(
int i=0; i<out.cols; ++i)
1222 out.at<
float>(j, i) = image.at<
float>(j*decimation, i*decimation);
1228 for(
int j=0; j<out.rows; ++j)
1230 for(
int i=0; i<out.cols; ++i)
1232 out.at<
unsigned short>(j, i) = image.at<
unsigned short>(j*decimation, i*decimation);
1239 cv::resize(image, out, cv::Size(), 1.0
f/
float(decimation), 1.0
f/
float(decimation), cv::INTER_AREA);
1250 cv::Mat
interpolate(
const cv::Mat & image,
int factor,
float depthErrorRatio)
1258 if((image.type() == CV_32FC1 || image.type()==CV_16UC1))
1261 out = cv::Mat::zeros(image.rows*factor, image.cols*factor, image.type());
1262 for(
int j=0; j<out.rows; j+=factor)
1264 for(
int i=0; i<out.cols; i+=factor)
1272 if(image.type() == CV_32FC1)
1274 dTopLeft = image.at<
float>(j/factor-1, i/factor-1);
1275 dTopRight = image.at<
float>(j/factor-1, i/factor);
1276 dBottomLeft = image.at<
float>(j/factor, i/factor-1);
1277 dBottomRight = image.at<
float>(j/factor, i/factor);
1281 dTopLeft = image.at<
unsigned short>(j/factor-1, i/factor-1);
1282 dTopRight = image.at<
unsigned short>(j/factor-1, i/factor);
1283 dBottomLeft = image.at<
unsigned short>(j/factor, i/factor-1);
1284 dBottomRight = image.at<
unsigned short>(j/factor, i/factor);
1287 if(dTopLeft>0 && dTopRight>0 && dBottomLeft>0 && dBottomRight > 0)
1289 float depthError = depthErrorRatio*(dTopLeft+dTopRight+dBottomLeft+dBottomRight)/4.0
f;
1290 if(fabs(dTopLeft-dTopRight) <= depthError &&
1291 fabs(dTopLeft-dBottomLeft) <= depthError &&
1292 fabs(dTopLeft-dBottomRight) <= depthError)
1296 float slopeTop = (dTopRight-dTopLeft)/
float(factor);
1297 float slopeBottom = (dBottomRight-dBottomLeft)/
float(factor);
1298 if(image.type() == CV_32FC1)
1300 for(
int z=i-factor; z<=i; ++z)
1302 out.at<
float>(j-factor, z) = dTopLeft+(slopeTop*
float(z-(i-factor)));
1303 out.at<
float>(j, z) = dBottomLeft+(slopeBottom*
float(z-(i-factor)));
1308 for(
int z=i-factor; z<=i; ++z)
1310 out.at<
unsigned short>(j-factor, z) = (
unsigned short)(dTopLeft+(slopeTop*float(z-(i-factor))));
1311 out.at<
unsigned short>(j, z) = (
unsigned short)(dBottomLeft+(slopeBottom*float(z-(i-factor))));
1316 if(image.type() == CV_32FC1)
1318 for(
int z=i-factor; z<=i; ++z)
1320 float top = out.at<
float>(j-factor, z);
1321 float bottom = out.at<
float>(j, z);
1322 float slope = (bottom-top)/
float(factor);
1323 for(
int d=j-factor+1;
d<j; ++
d)
1325 out.at<
float>(
d, z) = top+(slope*
float(d-(j-factor)));
1331 for(
int z=i-factor; z<=i; ++z)
1333 float top = out.at<
unsigned short>(j-factor, z);
1334 float bottom = out.at<
unsigned short>(j, z);
1335 float slope = (bottom-top)/
float(factor);
1336 for(
int d=j-factor+1;
d<j; ++
d)
1338 out.at<
unsigned short>(
d, z) = (
unsigned short)(top+(slope*float(d-(j-factor))));
1350 cv::resize(image, out, cv::Size(),
float(factor),
float(factor));
1363 const cv::Mat & depth,
1364 const cv::Mat & depthK,
1365 const cv::Size & colorSize,
1366 const cv::Mat & colorK,
1371 UASSERT(depth.type() == CV_16UC1 || depth.type() == CV_32FC1);
1372 UASSERT(depthK.type() == CV_64FC1 && depthK.cols == 3 && depthK.cols == 3);
1373 UASSERT(colorK.type() == CV_64FC1 && colorK.cols == 3 && colorK.cols == 3);
1375 float fx = depthK.at<
double>(0,0);
1376 float fy = depthK.at<
double>(1,1);
1377 float cx = depthK.at<
double>(0,2);
1378 float cy = depthK.at<
double>(1,2);
1380 float rfx = colorK.at<
double>(0,0);
1381 float rfy = colorK.at<
double>(1,1);
1382 float rcx = colorK.at<
double>(0,2);
1383 float rcy = colorK.at<
double>(1,2);
1389 Eigen::Vector4f P4,P3;
1391 cv::Mat registered = cv::Mat::zeros(colorSize, depth.type());
1393 bool depthInMM = depth.type() == CV_16UC1;
1394 for(
int y=0; y<depth.rows; ++y)
1396 for(
int x=0; x<depth.cols; ++x)
1399 float dz = depthInMM?float(depth.at<
unsigned short>(y,x))*0.001f:depth.at<
float>(y,x);
1403 P4[0] = (x - cx) * dz / fx;
1404 P4[1] = (y - cy) * dz / fy;
1409 float invZ = 1.0f/z;
1410 int dx = (rfx*P3[0])*invZ + rcx;
1411 int dy = (rfy*P3[1])*invZ + rcy;
1417 unsigned short z16 = z * 1000;
1418 unsigned short &zReg = registered.at<
unsigned short>(dy, dx);
1419 if(zReg == 0 || z16 < zReg)
1426 float &zReg = registered.at<
float>(dy, dx);
1427 if(zReg == 0 || z < zReg)
1441 UASSERT(depth.type() == CV_16UC1 || depth.type() == CV_32FC1);
1443 cv::Mat output = depth.clone();
1444 bool isMM = depth.type() == CV_16UC1;
1445 for(
int y=0; y<depth.rows-2; ++y)
1447 for(
int x=0; x<depth.cols-2; ++x)
1449 float a, bRight, bDown;
1452 a = depth.at<
unsigned short>(y, x);
1453 bRight = depth.at<
unsigned short>(y, x+1);
1454 bDown = depth.at<
unsigned short>(y+1, x);
1458 a = depth.at<
float>(y, x);
1459 bRight = depth.at<
float>(y, x+1);
1460 bDown = depth.at<
float>(y+1, x);
1463 if(a > 0.0
f && (bRight == 0.0
f || bDown == 0.0
f))
1465 bool horizontalSet = bRight != 0.0f;
1466 bool verticalSet = bDown != 0.0f;
1468 for(
int h=1; h<=maximumHoleSize && (!horizontalSet || !verticalSet); ++h)
1473 if(x+1+h >= depth.cols)
1475 horizontalSet =
true;
1479 float c = isMM?depth.at<
unsigned short>(y, x+1+h):depth.at<
float>(y, x+1+h);
1487 float depthError = errorRatio*float(a+c)/2.0f;
1488 if(fabs(a-c) <= depthError)
1491 float slope = (c-a)/
float(h+1);
1494 for(
int z=x+1; z<x+1+h; ++z)
1496 unsigned short & value = output.at<
unsigned short>(y, z);
1499 value = (
unsigned short)(a+(slope*
float(z-x)));
1504 value = (value+(
unsigned short)(a+(slope*
float(z-x))))/2;
1510 for(
int z=x+1; z<x+1+h; ++z)
1512 float & value = output.at<
float>(y, z);
1515 value = a+(slope*float(z-x));
1520 value = (value+(a+(slope*float(z-x))))/2;
1525 horizontalSet =
true;
1534 if(y+1+h >= depth.rows)
1540 float c = isMM?depth.at<
unsigned short>(y+1+h, x):depth.at<
float>(y+1+h, x);
1548 float depthError = errorRatio*float(a+c)/2.0f;
1549 if(fabs(a-c) <= depthError)
1552 float slope = (c-a)/
float(h+1);
1555 for(
int z=y+1; z<y+1+h; ++z)
1557 unsigned short & value = output.at<
unsigned short>(z, x);
1560 value = (
unsigned short)(a+(slope*
float(z-y)));
1565 value = (value+(
unsigned short)(a+(slope*
float(z-y))))/2;
1571 for(
int z=y+1; z<y+1+h; ++z)
1573 float & value = output.at<
float>(z, x);
1576 value = (a+(slope*float(z-y)));
1581 value = (value+(a+(slope*float(z-y))))/2;
1600 UASSERT(registeredDepth.type() == CV_16UC1);
1601 int margin = fillDoubleHoles?2:1;
1602 for(
int x=1; x<registeredDepth.cols-margin; ++x)
1604 for(
int y=1; y<registeredDepth.rows-margin; ++y)
1606 unsigned short & b = registeredDepth.at<
unsigned short>(y, x);
1610 const unsigned short & a = registeredDepth.at<
unsigned short>(y-1, x);
1611 unsigned short & c = registeredDepth.at<
unsigned short>(y+1, x);
1614 unsigned short error = 0.01*((a+c)/2);
1615 if(((b == 0 && a && c) || (b > a+error && b > c+error)) &&
1616 (a>c?a-c<=error:c-a<=error))
1626 if(!
set && fillDoubleHoles)
1628 const unsigned short &
d = registeredDepth.at<
unsigned short>(y+2, x);
1629 if(a && d && (b==0 || c==0))
1631 unsigned short error = 0.01*((a+d)/2);
1632 if(((b == 0 && a && d) || (b > a+error && b > d+error)) &&
1633 ((c == 0 && a && d) || (c > a+error && c > d+error)) &&
1634 (a>d?a-d<=error:d-a<=error))
1638 unsigned short tmp = (a-d)/4;
1644 unsigned short tmp = (d-a)/4;
1657 if(!
set && horizontal)
1659 const unsigned short & a = registeredDepth.at<
unsigned short>(y, x-1);
1660 unsigned short & c = registeredDepth.at<
unsigned short>(y, x+1);
1663 unsigned short error = 0.01*((a+c)/2);
1664 if(((b == 0 && a && c) || (b > a+error && b > c+error)) &&
1665 (a>c?a-c<=error:c-a<=error))
1671 if(!
set && fillDoubleHoles)
1673 const unsigned short &
d = registeredDepth.at<
unsigned short>(y, x+2);
1674 if(a && d && (b==0 || c==0))
1676 unsigned short error = 0.01*((a+d)/2);
1677 if(((b == 0 && a && d) || (b > a+error && b > d+error)) &&
1678 ((c == 0 && a && d) || (c > a+error && c > d+error)) &&
1679 (a>d?a-d<=error:d-a<=error))
1683 unsigned short tmp = (a-d)/4;
1689 unsigned short tmp = (d-a)/4;
1705 Array3D (
const size_t width,
const size_t height,
const size_t depth)
1710 v_ = std::vector<Eigen::Vector2f> (width*height*depth, Eigen::Vector2f (0.0
f, 0.0
f));
1713 inline Eigen::Vector2f&
1717 inline const Eigen::Vector2f&
1722 resize (
const size_t width,
const size_t height,
const size_t depth)
1735 const size_t x_index =
clamp (0,
x_dim_ - 1, static_cast<size_t> (x));
1736 const size_t xx_index =
clamp (0,
x_dim_ - 1, x_index + 1);
1738 const size_t y_index =
clamp (0,
y_dim_ - 1, static_cast<size_t> (y));
1739 const size_t yy_index =
clamp (0,
y_dim_ - 1, y_index + 1);
1741 const size_t z_index =
clamp (0,
z_dim_ - 1, static_cast<size_t> (z));
1742 const size_t zz_index =
clamp (0,
z_dim_ - 1, z_index + 1);
1744 const float x_alpha = x -
static_cast<float> (x_index);
1745 const float y_alpha = y -
static_cast<float> (y_index);
1746 const float z_alpha = z -
static_cast<float> (z_index);
1749 (1.0
f-x_alpha) * (1.0f-y_alpha) * (1.0
f-z_alpha) * (*this)(x_index, y_index, z_index) +
1750 x_alpha * (1.0
f-y_alpha) * (1.0f-z_alpha) * (*
this)(xx_index, y_index, z_index) +
1751 (1.0
f-x_alpha) * y_alpha * (1.0f-z_alpha) * (*
this)(x_index, yy_index, z_index) +
1752 x_alpha * y_alpha * (1.0
f-z_alpha) * (*this)(xx_index, yy_index, z_index) +
1753 (1.0
f-x_alpha) * (1.0f-y_alpha) * z_alpha * (*
this)(x_index, y_index, zz_index) +
1754 x_alpha * (1.0
f-y_alpha) * z_alpha * (*this)(xx_index, y_index, zz_index) +
1755 (1.0
f-x_alpha) * y_alpha * z_alpha * (*this)(x_index, yy_index, zz_index) +
1756 x_alpha * y_alpha * z_alpha * (*
this)(xx_index, yy_index, zz_index);
1759 static inline size_t 1761 const size_t max_value,
1764 if (x >= min_value && x <= max_value)
1768 else if (x < min_value)
1790 inline std::vector<Eigen::Vector2f >::iterator
1792 {
return v_.begin (); }
1794 inline std::vector<Eigen::Vector2f >::iterator
1796 {
return v_.end (); }
1798 inline std::vector<Eigen::Vector2f >::const_iterator
1800 {
return v_.begin (); }
1802 inline std::vector<Eigen::Vector2f >::const_iterator
1804 {
return v_.end (); }
1807 std::vector<Eigen::Vector2f >
v_;
1816 UASSERT(!depth.empty() && (depth.type() == CV_32FC1 || depth.type() == CV_16UC1));
1817 UDEBUG(
"Begin: depth float=%d %dx%d sigmaS=%f sigmaR=%f earlDivision=%d",
1818 depth.type()==CV_32FC1?1:0, depth.cols, depth.rows, sigmaS, sigmaR, earlyDivision?1:0);
1820 cv::Mat output = cv::Mat::zeros(depth.size(), CV_32FC1);
1824 bool found_finite =
false;
1825 for (
int x = 0; x < depth.cols; ++x)
1826 for (
int y = 0; y < depth.rows; ++y)
1828 float z = depth.type()==CV_32FC1?depth.at<
float>(y, x):
float(depth.at<
unsigned short>(y, x))/1000.0
f;
1835 found_finite =
true;
1840 UWARN(
"Given an empty depth image. Doing nothing.");
1843 UDEBUG(
"base_min=%f base_max=%f", base_min, base_max);
1845 const float base_delta = base_max - base_min;
1847 const size_t padding_xy = 2;
1848 const size_t padding_z = 2;
1850 const size_t small_width =
static_cast<size_t> (
static_cast<float> (depth.cols - 1) / sigmaS) + 1 + 2 * padding_xy;
1851 const size_t small_height =
static_cast<size_t> (
static_cast<float> (depth.rows - 1) / sigmaS) + 1 + 2 * padding_xy;
1852 const size_t small_depth =
static_cast<size_t> (base_delta / sigmaR) + 1 + 2 * padding_z;
1854 UDEBUG(
"small_width=%d small_height=%d small_depth=%d", (
int)small_width, (
int)small_height, (
int)small_depth);
1855 Array3D data (small_width, small_height, small_depth);
1856 for (
int x = 0; x < depth.cols; ++x)
1858 const size_t small_x =
static_cast<size_t> (
static_cast<float> (x) / sigmaS + 0.5
f) + padding_xy;
1859 for (
int y = 0; y < depth.rows; ++y)
1861 float v = depth.type()==CV_32FC1?depth.at<
float>(y,x):
float(depth.at<
unsigned short>(y,x))/1000.0
f;
1864 float z = v - base_min;
1866 const size_t small_y =
static_cast<size_t> (
static_cast<float> (y) / sigmaS + 0.5
f) + padding_xy;
1867 const size_t small_z =
static_cast<size_t> (
static_cast<float> (z) / sigmaR + 0.5
f) + padding_z;
1869 Eigen::Vector2f&
d = data (small_x, small_y, small_z);
1876 std::vector<long int> offset (3);
1877 offset[0] = &(data (1,0,0)) - &(data (0,0,0));
1878 offset[1] = &(data (0,1,0)) - &(data (0,0,0));
1879 offset[2] = &(data (0,0,1)) - &(data (0,0,0));
1881 Array3D buffer (small_width, small_height, small_depth);
1883 for (
size_t dim = 0; dim < 3; ++dim)
1885 const long int off = offset[dim];
1886 for (
size_t n_iter = 0; n_iter < 2; ++n_iter)
1888 std::swap (buffer, data);
1889 for(
size_t x = 1; x < small_width - 1; ++x)
1890 for(
size_t y = 1; y < small_height - 1; ++y)
1892 Eigen::Vector2f* d_ptr = &(data (x,y,1));
1893 Eigen::Vector2f* b_ptr = &(buffer (x,y,1));
1895 for(
size_t z = 1; z < small_depth - 1; ++z, ++d_ptr, ++b_ptr)
1896 *d_ptr = (*(b_ptr - off) + *(b_ptr + off) + 2.0 * (*b_ptr)) / 4.0;
1903 for (std::vector<Eigen::Vector2f>::iterator
d = data.
begin ();
d != data.
end (); ++
d)
1904 *
d /= ((*
d)[0] != 0) ? (*
d)[1] : 1;
1907 for (
int x = 0; x < depth.cols; ++x)
1908 for (
int y = 0; y < depth.rows; ++y)
1910 float z = depth.type()==CV_32FC1?depth.at<
float>(y,x):
float(depth.at<
unsigned short>(y,x))/1000.0
f;
1915 static_cast<float> (y) / sigmaS + padding_xy,
1916 z / sigmaR + padding_z);
1917 float v = earlyDivision ? D[0] : D[0] / D[1];
1918 if(v < base_min || v >= base_max)
1922 if(depth.type()==CV_16UC1 && v>65.5350f)
1926 output.at<
float>(y,x) = v;
1942 cv::Mat
brightnessAndContrastAuto(
const cv::Mat &src,
const cv::Mat &
mask,
float clipLowHistPercent,
float clipHighHistPercent,
float * alphaOut,
float * betaOut)
1945 CV_Assert(clipLowHistPercent >= 0 && clipHighHistPercent>=0);
1946 CV_Assert((src.type() == CV_8UC1) || (src.type() == CV_8UC3) || (src.type() == CV_8UC4));
1950 double minGray = 0, maxGray = 0;
1954 if (src.type() == CV_8UC1) gray = src;
1955 else if (src.type() == CV_8UC3)
cvtColor(src, gray, CV_BGR2GRAY);
1956 else if (src.type() == CV_8UC4)
cvtColor(src, gray, CV_BGRA2GRAY);
1957 if (clipLowHistPercent == 0 && clipHighHistPercent == 0)
1960 cv::minMaxLoc(gray, &minGray, &maxGray, 0, 0, mask);
1966 float range[] = { 0, 256 };
1967 const float* histRange = { range };
1968 bool uniform =
true;
1969 bool accumulate =
false;
1970 calcHist(&gray, 1, 0, mask, hist, 1, &histSize, &histRange, uniform, accumulate);
1973 std::vector<float> accumulator(histSize);
1974 accumulator[0] = hist.at<
float>(0);
1975 for (
int i = 1; i < histSize; i++)
1977 accumulator[i] = accumulator[i - 1] + hist.at<
float>(i);
1981 float max = accumulator.back();
1982 clipLowHistPercent *= (max / 100.0);
1983 clipHighHistPercent *= (max / 100.0);
1986 while (accumulator[minGray] < clipLowHistPercent)
1990 maxGray = histSize - 1;
1991 while (accumulator[maxGray] >= (max - clipHighHistPercent))
1996 float inputRange = maxGray - minGray;
1998 alpha = (histSize - 1) / inputRange;
1999 beta = -minGray * alpha;
2001 UINFO(
"minGray=%f maxGray=%f alpha=%f beta=%f", minGray, maxGray, alpha, beta);
2006 src.convertTo(dst, -1, alpha, beta);
2009 if (dst.type() == CV_8UC4)
2011 int from_to[] = { 3, 3};
2012 cv::mixChannels(&src, 4, &dst,1, from_to, 1);
2031 #if CV_MAJOR_VERSION >= 3 2032 cv::createMergeMertens()->process(images, fusion);
2034 UASSERT(fusion.channels() == 3);
2035 fusion.convertTo(rgb8, CV_8UC3, 255.0);
2038 UWARN(
"Exposure fusion is only available when rtabmap is built with OpenCV3.");
2041 fusion = images[0].clone();
2047 void HSVtoRGB(
float *r,
float *g,
float *b,
float h,
float s,
float v )
2060 q = v * ( 1 - s * f );
2061 t = v * ( 1 - s * ( 1 - f ) );
cv::Mat RTABMAP_EXP disparityFromStereoImages(const cv::Mat &leftImage, const cv::Mat &rightImage, const ParametersMap ¶meters=ParametersMap())
GLM_FUNC_DECL genIType mask(genIType const &count)
T uVariance(const T *v, unsigned int size, T meanV)
cv::Mat RTABMAP_EXP depthFromStereoCorrespondences(const cv::Mat &leftImage, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask, float fx, float baseline)
std::vector< Eigen::Vector2f >::const_iterator end() const
std::vector< Eigen::Vector2f >::iterator end()
T uMean(const T *v, unsigned int size)
cv::Mat RTABMAP_EXP cvtDepthToFloat(const cv::Mat &depth16U)
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
static StereoDense * create(const ParametersMap ¶meters)
bool uIsInBounds(const T &value, const T &low, const T &high)
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
Eigen::Vector2f trilinear_interpolation(const float x, const float y, const float z)
cv::Mat RTABMAP_EXP depthFromDisparity(const cv::Mat &disparity, float fx, float baseline, int type=CV_32FC1)
GLM_FUNC_DECL genType e()
float UTILITE_EXP uStr2Float(const std::string &str)
std::map< std::string, std::string > ParametersMap
cv::Mat RTABMAP_EXP fastBilateralFiltering(const cv::Mat &depth, float sigmaS=15.0f, float sigmaR=0.05f, bool earlyDivision=false)
Basic mathematics functions.
Some conversion functions.
cv::Mat RTABMAP_EXP registerDepth(const cv::Mat &depth, const cv::Mat &depthK, const cv::Size &colorSize, const cv::Mat &colorK, const rtabmap::Transform &transform)
cv::Mat RTABMAP_EXP depthFromStereoImages(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, float fx, float baseline, int flowWinSize=9, int flowMaxLevel=4, int flowIterations=20, double flowEps=0.02)
std::vector< Eigen::Vector2f > v_
std::vector< Eigen::Vector2f >::const_iterator begin() const
GLM_FUNC_DECL genType step(genType const &edge, genType const &x)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
cv::Mat RTABMAP_EXP interpolate(const cv::Mat &image, int factor, float depthErrorRatio=0.02f)
float RTABMAP_EXP ssd(const cv::Mat &windowLeft, const cv::Mat &windowRight)
Array3D(const size_t width, const size_t height, const size_t depth)
bool uIsFinite(const T &value)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
virtual cv::Mat computeDisparity(const cv::Mat &leftImage, const cv::Mat &rightImage) const =0
GLM_FUNC_DECL genType floor(genType const &x)
#define UASSERT_MSG(condition, msg_str)
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
GLM_FUNC_DECL vecType proj(vecType const &x, vecType const &Normal)
cv::Mat RTABMAP_EXP decimate(const cv::Mat &image, int d)
cv::Mat RTABMAP_EXP disparityFromStereoCorrespondences(const cv::Size &disparitySize, const std::vector< cv::Point2f > &leftCorners, const std::vector< cv::Point2f > &rightCorners, const std::vector< unsigned char > &mask)
GLM_FUNC_DECL genType abs(genType const &x)
cv::Rect RTABMAP_EXP computeRoi(const cv::Mat &image, const std::string &roiRatios)
void RTABMAP_EXP fillRegisteredDepthHoles(cv::Mat &depthRegistered, bool vertical, bool horizontal, bool fillDoubleHoles=false)
std::vector< Eigen::Vector2f >::iterator begin()
cv::Mat RTABMAP_EXP exposureFusion(const std::vector< cv::Mat > &images)
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
cv::Mat RTABMAP_EXP fillDepthHoles(const cv::Mat &depth, int maximumHoleSize=1, float errorRatio=0.02f)
void resize(const size_t width, const size_t height, const size_t depth)
ULogger class and convenient macros.
static size_t clamp(const size_t min_value, const size_t max_value, const size_t x)
float RTABMAP_EXP sad(const cv::Mat &windowLeft, const cv::Mat &windowRight)
cv::Mat RTABMAP_EXP cvtDepthFromFloat(const cv::Mat &depth32F)
cv::Mat RTABMAP_EXP brightnessAndContrastAuto(const cv::Mat &src, const cv::Mat &mask, float clipLowHistPercent=0, float clipHighHistPercent=0, float *alphaOut=0, float *betaOut=0)
Automatic brightness and contrast optimization with optional histogram clipping.
float RTABMAP_EXP getDepth(const cv::Mat &depthImage, float x, float y, bool smoothing, float depthErrorRatio=0.02f, bool estWithNeighborsIfNull=false)
GLM_FUNC_DECL genType::value_type length(genType const &x)
void RTABMAP_EXP HSVtoRGB(float *r, float *g, float *b, float h, float s, float v)
std::string UTILITE_EXP uFormat(const char *fmt,...)
std::vector< cv::Point2f > RTABMAP_EXP calcStereoCorrespondences(const cv::Mat &leftImage, const cv::Mat &rightImage, const std::vector< cv::Point2f > &leftCorners, std::vector< unsigned char > &status, cv::Size winSize=cv::Size(6, 3), int maxLevel=3, int iterations=5, float minDisparity=0.0f, float maxDisparity=64.0f, bool ssdApproach=true)
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
Eigen::Vector2f & operator()(const size_t x, const size_t y, const size_t z)
void RTABMAP_EXP calcOpticalFlowPyrLKStereo(cv::InputArray _prevImg, cv::InputArray _nextImg, cv::InputArray _prevPts, cv::InputOutputArray _nextPts, cv::OutputArray _status, cv::OutputArray _err, cv::Size winSize=cv::Size(15, 3), int maxLevel=3, cv::TermCriteria criteria=cv::TermCriteria(cv::TermCriteria::COUNT+cv::TermCriteria::EPS, 30, 0.01), int flags=0, double minEigThreshold=1e-4)