DepthFromStereo.cpp
Go to the documentation of this file.
1 /*
2  * This file is part of ArmarX.
3  *
4  * Copyright (C) 2011-2016, High Performance Humanoid Technologies (H2T), Karlsruhe Institute of Technology (KIT), all rights reserved.
5  *
6  * ArmarX is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License version 2 as
8  * published by the Free Software Foundation.
9  *
10  * ArmarX is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program. If not, see <http://www.gnu.org/licenses/>.
17  *
18  * @package
19  * @author
20  * @date
21  * @copyright http://www.gnu.org/licenses/gpl-2.0.txt
22  * GNU General Public License
23  */
24 #include "DepthFromStereo.h"
25 
26 // OpenCV
27 #include <opencv2/opencv.hpp>
28 
29 
30 // IVT
31 #include <cmath>
32 #include <limits>
33 
34 #include <opencv2/calib3d.hpp>
35 
36 #include <Calibration/Calibration.h>
37 #include <Calibration/Rectification.h>
38 #include <Calibration/StereoCalibration.h>
39 #include <Image/ByteImage.h>
40 #include <Image/ImageProcessor.h>
41 #include <Image/IplImageAdaptor.h>
42 #include <Image/StereoMatcher.h>
43 #include <Math/Math3d.h>
44 #include <Threading/Threading.h>
45 
47 {
48 
49  static void
50  doStereoSGBM(int minDisparity,
51  int numDisparities,
52  int nSADWindowSize,
53  int P1,
54  int P2,
55  int disp12MaxDiff,
56  cv::Mat leftInput,
57  cv::Mat rightInput,
58  cv::Mat output)
59  {
60  int preFilterCap = 0;
61  int uniquenessRatio = 0;
62  int speckleWindowSize = 0;
63  int speckleRange = 0;
64 #if CV_MAJOR_VERSION == 2
65  bool fullDP = true;
66  cv::StereoSGBM stereoSGBM(minDisparity,
67  numDisparities,
68  nSADWindowSize,
69  P1,
70  P2,
71  disp12MaxDiff,
72  preFilterCap,
73  uniquenessRatio,
74  speckleWindowSize,
75  speckleRange,
76  fullDP);
77  stereoSGBM(leftInput, rightInput, output);
78 #else
79  cv::Ptr<cv::StereoSGBM> stereoSGBM = cv::StereoSGBM::create(minDisparity,
80  numDisparities,
81  nSADWindowSize,
82  P1,
83  P2,
84  disp12MaxDiff,
85  preFilterCap,
86  uniquenessRatio,
87  speckleWindowSize,
88  speckleRange,
89  cv::StereoSGBM::MODE_SGBM);
90  stereoSGBM->compute(leftInput, rightInput, output);
91 #endif
92  }
93 
94  void
95  GetPointsFromDisparity(const CByteImage* pImageLeftColor,
96  const CByteImage* pImageRightColor,
97  const CByteImage* pImageLeftGrey,
98  const CByteImage* pImageRightGrey,
99  const int nDisparityPointDistance,
100  pcl::PointCloud<pcl::PointXYZRGBA>& aPointsFromDisparity,
101  CByteImage* pDisparityImage,
102  const int imageWidth,
103  const int imageHeight,
104  CStereoCalibration* pStereoCalibration,
105  bool imagesAreUndistorted,
106  const bool smoothDisparities)
107  {
108  // rectify images
109  CByteImage *pRectifiedImageLeftGrey, *pRectifiedImageRightGrey,
110  *pRectifiedImageLeftGreyHalfsize, *pRectifiedImageRightGreyHalfsize,
111  *pRectifiedImageLeftGreyQuartersize, *pRectifiedImageRightGreyQuartersize;
112  IplImage *pRectifiedIplImageLeft, *pRectifiedIplImageRight, *pRectifiedIplImageLeftHalfsize,
113  *pRectifiedIplImageRightHalfsize, *pRectifiedIplImageLeftQuartersize,
114  *pRectifiedIplImageRightQuartersize;
115  CByteImage* pRectifiedImageLeftColorGaussFiltered;
116  cv::Mat mDispImg, mDispImgHalfsize, mDispImgQuartersize;
117  bool bGreyImagesReady = false;
118  bool bGreyImagesHalfsizeReady = false;
119  bool bGreyImagesQuartersizeReady = false;
120  const int nPenaltyDispDiffOneFactor = 8;
121  const int nPenaltyDispDiffBiggerOneFactor = 32;
122 
123  CStereoMatcher* pStereoMatcher = new CStereoMatcher();
124  CStereoCalibration* pStereoCalibrationCopy = new CStereoCalibration(*pStereoCalibration);
125  pStereoMatcher->InitCameraParameters(pStereoCalibrationCopy, false);
126 
127  const int nDispMin = pStereoMatcher->GetDisparityEstimate(8000);
128  const int nDispMax = pStereoMatcher->GetDisparityEstimate(400);
129 
130  const int imageOverlapCutoffLeft = 0; // 110
131  const int imageOverlapCutoffRight = 0; // 5
132  const int imageOverlapCutoffTop = 0; // 5
133  const int imageOverlapCutoffBottom = 0; // 5
134 
135  const bool fillHoles = false;
136 
137 
138 #pragma omp parallel sections
139  {
140 #pragma omp section
141  {
142  const CByteImage* ppOriginalImages[2];
143  ppOriginalImages[0] = pImageLeftGrey;
144  ppOriginalImages[1] = pImageRightGrey;
145  pRectifiedImageLeftGrey =
146  new CByteImage(imageWidth, imageHeight, CByteImage::eGrayScale);
147  pRectifiedImageRightGrey =
148  new CByteImage(imageWidth, imageHeight, CByteImage::eGrayScale);
149  CByteImage* ppRectifiedImages[2];
150  ppRectifiedImages[0] = pRectifiedImageLeftGrey;
151  ppRectifiedImages[1] = pRectifiedImageRightGrey;
152 
153  CRectification* pRectification = new CRectification(true, !imagesAreUndistorted);
154  pRectification->Init(pStereoCalibration);
155  pRectification->Rectify(ppOriginalImages, ppRectifiedImages);
156 
157  pRectifiedIplImageLeft = IplImageAdaptor::Adapt(pRectifiedImageLeftGrey);
158  pRectifiedIplImageRight = IplImageAdaptor::Adapt(pRectifiedImageRightGrey);
159  bGreyImagesReady = true;
160 
161  // half size
162  pRectifiedImageLeftGreyHalfsize =
163  new CByteImage(imageWidth / 2, imageHeight / 2, CByteImage::eGrayScale);
164  pRectifiedImageRightGreyHalfsize =
165  new CByteImage(imageWidth / 2, imageHeight / 2, CByteImage::eGrayScale);
166  ::ImageProcessor::Resize(pRectifiedImageLeftGrey, pRectifiedImageLeftGreyHalfsize);
167  ::ImageProcessor::Resize(pRectifiedImageRightGrey,
168  pRectifiedImageRightGreyHalfsize);
169 
170  pRectifiedIplImageLeftHalfsize =
171  IplImageAdaptor::Adapt(pRectifiedImageLeftGreyHalfsize);
172  pRectifiedIplImageRightHalfsize =
173  IplImageAdaptor::Adapt(pRectifiedImageRightGreyHalfsize);
174  bGreyImagesHalfsizeReady = true;
175 
176  // quarter size
177  pRectifiedImageLeftGreyQuartersize =
178  new CByteImage(imageWidth / 4, imageHeight / 4, CByteImage::eGrayScale);
179  pRectifiedImageRightGreyQuartersize =
180  new CByteImage(imageWidth / 4, imageHeight / 4, CByteImage::eGrayScale);
181  ::ImageProcessor::Resize(pRectifiedImageLeftGrey,
182  pRectifiedImageLeftGreyQuartersize);
183  ::ImageProcessor::Resize(pRectifiedImageRightGrey,
184  pRectifiedImageRightGreyQuartersize);
185 
186  pRectifiedIplImageLeftQuartersize =
187  IplImageAdaptor::Adapt(pRectifiedImageLeftGreyQuartersize);
188  pRectifiedIplImageRightQuartersize =
189  IplImageAdaptor::Adapt(pRectifiedImageRightGreyQuartersize);
190  bGreyImagesQuartersizeReady = true;
191 
192  delete pRectification;
193  }
194 
195 #pragma omp section
196  {
197  const CByteImage* ppOriginalImages[2];
198  ppOriginalImages[0] = pImageLeftColor;
199  ppOriginalImages[1] = pImageRightColor;
200  CByteImage* pRectifiedImageLeftColor =
201  new CByteImage(imageWidth, imageHeight, CByteImage::eRGB24);
202  CByteImage* pRectifiedImageRightColor =
203  new CByteImage(imageWidth, imageHeight, CByteImage::eRGB24);
204  CByteImage* ppRectifiedImages[2];
205  ppRectifiedImages[0] = pRectifiedImageLeftColor;
206  ppRectifiedImages[1] = pRectifiedImageRightColor;
207 
208  CRectification* pRectification = new CRectification(true, !imagesAreUndistorted);
209  pRectification->Init(pStereoCalibration);
210  pRectification->Rectify(ppOriginalImages, ppRectifiedImages);
211 
212  pRectifiedImageLeftColorGaussFiltered =
213  new CByteImage(imageWidth, imageHeight, CByteImage::eRGB24);
214  ::ImageProcessor::GaussianSmooth3x3(pRectifiedImageLeftColor,
215  pRectifiedImageLeftColorGaussFiltered);
216 
217  delete pRectifiedImageLeftColor;
218  delete pRectifiedImageRightColor;
219  delete pRectification;
220  }
221 
222 
223  // get disparity using semi-global block matching
224 
225 #pragma omp section
226  {
227  while (!bGreyImagesReady)
228  {
229  Threading::YieldThread();
230  }
231 
232  // StereoSGBM::StereoSGBM(int minDisparity, int numDisparities, int SADWindowSize, int P1=0, int P2=0, int disp12MaxDiff=0,
233  // int preFilterCap=0, int uniquenessRatio=0, int speckleWindowSize=0, int speckleRange=0, bool fullDP=false)
234  //
235  // minDisparity – Minimum possible disparity value. Normally, it is zero but sometimes rectification algorithms can shift images, so this parameter needs to be adjusted accordingly.
236  // numDisparities – Maximum disparity minus minimum disparity. The value is always greater than zero. In the current implementation, this parameter must be divisible by 16.
237  // SADWindowSize – Matched block size. It must be an odd number >=1 . Normally, it should be somewhere in the 3..11 range.
238  // P1 – The first parameter controlling the disparity smoothness. See below.
239  // P2 – The second parameter controlling the disparity smoothness. The larger the values are, the smoother the disparity is. P1 is the penalty on the disparity change by plus or minus 1 between neighbor pixels. P2 is the penalty on the disparity change by more than 1 between neighbor pixels. The algorithm requires P2 > P1 . See stereo_match.cpp sample where some reasonably good P1 and P2 values are shown (like 8*number_of_image_channels*SADWindowSize*SADWindowSize and 32*number_of_image_channels*SADWindowSize*SADWindowSize , respectively).
240  // disp12MaxDiff – Maximum allowed difference (in integer pixel units) in the left-right disparity check. Set it to a non-positive value to disable the check.
241  // preFilterCap – Truncation value for the prefiltered image pixels. The algorithm first computes x-derivative at each pixel and clips its value by [-preFilterCap, preFilterCap] interval. The result values are passed to the Birchfield-Tomasi pixel cost function.
242  // uniquenessRatio – Margin in percentage by which the best (minimum) computed cost function value should “win” the second best value to consider the found match correct. Normally, a value within the 5-15 range is good enough.
243  // speckleWindowSize – Maximum size of smooth disparity regions to consider their noise speckles and invalidate. Set it to 0 to disable speckle filtering. Otherwise, set it somewhere in the 50-200 range.
244  // speckleRange – Maximum disparity variation within each connected component. If you do speckle filtering, set the parameter to a positive value, multiple of 16. Normally, 16 or 32 is good enough.
245  // fullDP – Set it to true to run the full-scale two-pass dynamic programming algorithm. It will consume O(W*H*numDisparities) bytes, which is large for 640x480 stereo and huge for HD-size pictures. By default, it is set to false.
246  const cv::Mat mLeftImg = cv::cvarrToMat(pRectifiedIplImageLeft);
247  const cv::Mat mRightImg = cv::cvarrToMat(pRectifiedIplImageRight);
248  const int nSADWindowSize = 7; // 11
249  const int nPenaltyDispDiffOne =
250  nPenaltyDispDiffOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 8
251  const int nPenaltyDispDiffBiggerOne =
252  nPenaltyDispDiffBiggerOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 32
253 
254  doStereoSGBM(1,
255  8 * 16,
256  nSADWindowSize,
257  nPenaltyDispDiffOne,
258  nPenaltyDispDiffBiggerOne,
259  4,
260  mLeftImg,
261  mRightImg,
262  mDispImg);
263  }
264 
265 
266 #pragma omp section
267  {
268  while (!bGreyImagesHalfsizeReady)
269  {
270  Threading::YieldThread();
271  }
272 
273  const cv::Mat mLeftImg = cv::cvarrToMat(pRectifiedIplImageLeftHalfsize);
274  const cv::Mat mRightImg = cv::cvarrToMat(pRectifiedIplImageRightHalfsize);
275  const int nSADWindowSize = 7;
276  const int nPenaltyDispDiffOne =
277  nPenaltyDispDiffOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 8
278  const int nPenaltyDispDiffBiggerOne =
279  nPenaltyDispDiffBiggerOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 32
280  doStereoSGBM(1,
281  4 * 16,
282  nSADWindowSize,
283  nPenaltyDispDiffOne,
284  nPenaltyDispDiffBiggerOne,
285  4,
286  mLeftImg,
287  mRightImg,
288  mDispImgHalfsize);
289  }
290 
291 
292 #pragma omp section
293  {
294  while (!bGreyImagesQuartersizeReady)
295  {
296  Threading::YieldThread();
297  }
298 
299  const cv::Mat mLeftImg = cv::cvarrToMat(pRectifiedIplImageLeftQuartersize);
300  const cv::Mat mRightImg = cv::cvarrToMat(pRectifiedIplImageRightQuartersize);
301  const int nSADWindowSize = 7;
302  const int nPenaltyDispDiffOne =
303  nPenaltyDispDiffOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 8
304  const int nPenaltyDispDiffBiggerOne =
305  nPenaltyDispDiffBiggerOneFactor * 3 * nSADWindowSize * nSADWindowSize; // 32
306 
307  doStereoSGBM(1,
308  4 * 16,
309  nSADWindowSize,
310  nPenaltyDispDiffOne,
311  nPenaltyDispDiffBiggerOne,
312  4,
313  mLeftImg,
314  mRightImg,
315  mDispImgQuartersize);
316  }
317  }
318 
319 
320  // combine disparities
321  float* pDisparities = new float[imageWidth * imageHeight];
322 #pragma omp parallel for schedule(static, 80)
323  for (int i = 0; i < imageHeight; i++)
324  {
325  for (int j = 0; j < imageWidth; j++)
326  {
327  int nDispFullsize = mDispImg.at<short>(i, j) / 16;
328  int nDispHalfsize = 2 * mDispImgHalfsize.at<short>(i / 2, j / 2) / 16;
329  int nDispQuartersize = 4 * mDispImgQuartersize.at<short>(i / 4, j / 4) / 16;
330 
331  int nDisp = 0;
332  float fDisp = 0;
333  int nNumValidDisparities = 0;
334 
335  if ((nDispFullsize > nDispMin) && (nDispFullsize < nDispMax))
336  {
337  nDisp += nDispFullsize;
338  nNumValidDisparities++;
339  }
340 
341  if ((nDispHalfsize > nDispMin) && (nDispHalfsize < nDispMax))
342  {
343  nDisp += nDispHalfsize;
344  nNumValidDisparities++;
345  }
346 
347  if ((nDispQuartersize > nDispMin) && (nDispQuartersize < nDispMax))
348  {
349  nDisp += nDispQuartersize;
350  nNumValidDisparities++;
351  }
352 
353  if (nNumValidDisparities > 0)
354  {
355  fDisp = (float)nDisp / (float)nNumValidDisparities;
356  }
357 
358  pDisparities[i * imageWidth + j] = fDisp;
359  }
360  }
361 
362 
363  // fill holes
364  if (fillHoles)
365  {
366  std::vector<int> pDisparitiesCopy(imageWidth * imageHeight);
367 
368  for (int i = 0; i < imageHeight * imageWidth; i++)
369  {
370  pDisparitiesCopy[i] = pDisparities[i];
371  }
372 
373  const int nMargin = 10;
374  const int nHoleFillingAveragingRadius = 5;
375 
376  for (int i = nMargin; i < imageHeight - nMargin; i++)
377  {
378  for (int j = nMargin; j < imageWidth - nMargin; j++)
379  {
380  if (pDisparitiesCopy[i * imageWidth + j] == 0)
381  {
382  int nSum = 0;
383  int nNumValidDisparities = 0;
384 
385  for (int k = -nHoleFillingAveragingRadius; k <= nHoleFillingAveragingRadius;
386  k++)
387  {
388  for (int l = -nHoleFillingAveragingRadius;
389  l <= nHoleFillingAveragingRadius;
390  l++)
391  {
392  if (pDisparitiesCopy[(i + k) * imageWidth + (j + l)] > 0)
393  {
394  nSum += pDisparitiesCopy[(i + k) * imageWidth + (j + l)];
395  nNumValidDisparities++;
396  }
397  }
398  }
399 
400  if (nNumValidDisparities > 0)
401  {
402  pDisparities[i * imageWidth + j] = nSum / nNumValidDisparities;
403  }
404  }
405  }
406  }
407  }
408 
409 
410  // get smoothed disparity
411  float* pSmoothedDisparity = pDisparities;
412 
413  if (smoothDisparities)
414  {
415  pSmoothedDisparity = new float[imageWidth * imageHeight];
416  float* pSmoothedDisparity1 = new float[imageWidth * imageHeight];
417  float* pSmoothedDisparity2 = new float[imageWidth * imageHeight];
418  float* pSmoothedDisparity3 = new float[imageWidth * imageHeight];
419  float* pSmoothedDisparity4 = new float[imageWidth * imageHeight];
420 
421 #pragma omp parallel sections
422  {
423 #pragma omp section
424  {
426  pDisparities, pSmoothedDisparity1, imageWidth, imageHeight, 1);
427  }
428 
429 #pragma omp section
430  {
432  pDisparities, pSmoothedDisparity2, imageWidth, imageHeight, 2);
433  }
434 
435 #pragma omp section
436  {
437  //CalculateSmoothedDisparityImage(pDisparities, pSmoothedDisparity3, imageWidth, imageHeight, 3);
438  }
439 
440 #pragma omp section
441  {
442  //CalculateSmoothedDisparityImage(pDisparities, pSmoothedDisparity4, imageWidth, imageHeight, 4);
443  }
444  }
445 
446  for (int i = 0; i < imageWidth * imageHeight; i++)
447  {
448  pSmoothedDisparity[i] =
449  0.8f * pDisparities[i] + 0.15f * pSmoothedDisparity1[i] +
450  0.05f *
451  pSmoothedDisparity2
452  [i]; // + 0.0f * pSmoothedDisparity3[i] + 0.0f * pSmoothedDisparity4[i];
453  }
454 
455  delete[] pSmoothedDisparity1;
456  delete[] pSmoothedDisparity2;
457  delete[] pSmoothedDisparity3;
458  delete[] pSmoothedDisparity4;
459  }
460 
461 
462  // cut of the edges to avoid noise points
463  for (int i = 0; i < imageHeight; i++)
464  {
465  for (int j = 0; j < imageWidth; j++)
466  {
467  if (i < imageOverlapCutoffTop || i >= imageHeight - imageOverlapCutoffBottom ||
468  j < imageOverlapCutoffLeft || j > imageWidth - imageOverlapCutoffRight)
469  {
470  pSmoothedDisparity[i * imageWidth + j] = 0;
471  }
472  }
473  }
474 
475 
476  // visualize
477  if (pDisparityImage)
478  {
479  CByteImage* pRectifiedDisparityImage =
480  new CByteImage(imageWidth, imageHeight, CByteImage::eGrayScale);
481 
482  for (int i = 0; i < imageHeight; i++)
483  {
484  for (int j = 0; j < imageWidth; j++)
485  {
486  int nDisp = pSmoothedDisparity[i * imageWidth + j];
487  pRectifiedDisparityImage->pixels[i * imageWidth + j] =
488  (nDisp > 255) ? 255 : nDisp;
489  }
490  }
491 
492  // get unrectified disparity image
493  ::ImageProcessor::Zero(pDisparityImage);
494  Vec2d vRectPos, vUnRectPos;
495  Mat3d mRectificationHomography = pStereoCalibration->rectificationHomographyLeft;
496 
497  for (int i = 0; i < imageHeight; i++)
498  {
499  for (int j = 0; j < imageWidth; j++)
500  {
501  vRectPos.x = j;
502  vRectPos.y = i;
503  Math2d::ApplyHomography(mRectificationHomography, vRectPos, vUnRectPos);
504 
505  if (0 <= vUnRectPos.y && vUnRectPos.y < imageHeight && 0 <= vUnRectPos.x &&
506  vUnRectPos.x < imageWidth)
507  {
508  pDisparityImage
509  ->pixels[(int)vUnRectPos.y * imageWidth + (int)vUnRectPos.x] =
510  pRectifiedDisparityImage->pixels[i * imageWidth + j];
511  }
512  }
513  }
514 
515  FillHolesGray(pDisparityImage, pRectifiedDisparityImage, imageWidth, imageHeight, 1);
516  FillHolesGray(pRectifiedDisparityImage, pDisparityImage, imageWidth, imageHeight, 1);
517  delete pRectifiedDisparityImage;
518  }
519 
520 
521  Vec2d vImgPointLeft, vImgPointRight;
522  Vec3d vPoint3D;
523  const float fDispMin = nDispMin;
524  const float fDispMax = nDispMax;
525  aPointsFromDisparity.width = ceil((float)imageWidth / (float)nDisparityPointDistance);
526  aPointsFromDisparity.height = ceil((float)imageHeight / (float)nDisparityPointDistance);
527  aPointsFromDisparity.resize(aPointsFromDisparity.width * aPointsFromDisparity.height);
528 
529  int index = 0;
530 
531  for (int i = 0; i < imageHeight; i += nDisparityPointDistance)
532  {
533  for (int j = 0; j < imageWidth; j += nDisparityPointDistance, index++)
534  {
535 
536  float fDisp = pSmoothedDisparity[i * imageWidth + j];
537 
538  if ((fDisp > fDispMin) && (fDisp < fDispMax))
539  {
540  vImgPointLeft.x = j;
541  vImgPointLeft.y = i;
542  vImgPointRight.x = j - fDisp;
543  vImgPointRight.y = i;
544 
545  pStereoCalibration->Calculate3DPoint(
546  vImgPointLeft, vImgPointRight, vPoint3D, true, false);
547 
548  // create point descriptor
549  aPointsFromDisparity.points[index].x = vPoint3D.x;
550  aPointsFromDisparity.points[index].y = vPoint3D.y;
551  aPointsFromDisparity.points[index].z = vPoint3D.z;
552  aPointsFromDisparity.points[index].r =
553  pRectifiedImageLeftColorGaussFiltered->pixels[3 * (i * imageWidth + j)];
554  aPointsFromDisparity.points[index].g =
555  pRectifiedImageLeftColorGaussFiltered->pixels[3 * (i * imageWidth + j) + 1];
556  aPointsFromDisparity.points[index].b =
557  pRectifiedImageLeftColorGaussFiltered->pixels[3 * (i * imageWidth + j) + 2];
558  aPointsFromDisparity.points[index].a = 1.0f;
559  }
560  // else if (false)
561  // {
562  // aPointsFromDisparity.points[index].x = std::numeric_limits<float>::quiet_NaN();
563  // aPointsFromDisparity.points[index].y = std::numeric_limits<float>::quiet_NaN();
564  // aPointsFromDisparity.points[index].z = std::numeric_limits<float>::quiet_NaN();
565  // aPointsFromDisparity.points[index].r = std::numeric_limits<float>::quiet_NaN();
566  // aPointsFromDisparity.points[index].g = std::numeric_limits<float>::quiet_NaN();
567  // aPointsFromDisparity.points[index].b = std::numeric_limits<float>::quiet_NaN();
568  // aPointsFromDisparity.points[index].a = std::numeric_limits<float>::quiet_NaN();
569  // }
570  else
571  {
572  aPointsFromDisparity.points[index].x = 0;
573  aPointsFromDisparity.points[index].y = 0;
574  aPointsFromDisparity.points[index].z = 0;
575  aPointsFromDisparity.points[index].r = 0;
576  aPointsFromDisparity.points[index].g = 0;
577  aPointsFromDisparity.points[index].b = 0;
578  aPointsFromDisparity.points[index].a = 0;
579  }
580  }
581  }
582 
583  delete pRectifiedImageLeftGrey;
584  delete pRectifiedImageRightGrey;
585  delete pRectifiedImageLeftGreyHalfsize;
586  delete pRectifiedImageRightGreyHalfsize;
587  delete pRectifiedImageLeftGreyQuartersize;
588  delete pRectifiedImageRightGreyQuartersize;
589  delete pRectifiedImageLeftColorGaussFiltered;
590  delete pStereoMatcher;
591  delete pStereoCalibrationCopy;
592  cvReleaseImageHeader(&pRectifiedIplImageLeft);
593  cvReleaseImageHeader(&pRectifiedIplImageRight);
594 
595  if (pSmoothedDisparity != pDisparities)
596  {
597  delete[] pSmoothedDisparity;
598  }
599 
600  delete[] pDisparities;
601  }
602 
603  void
604  FillHolesGray(const CByteImage* pInputImage,
605  CByteImage* pOutputImage,
606  const int imageWidth,
607  const int imageHeight,
608  const int nRadius)
609  {
610 
611  for (int i = 0; i < imageWidth * imageHeight; i++)
612  {
613  pOutputImage->pixels[i] = pInputImage->pixels[i];
614  }
615 
616  for (int i = nRadius; i < imageHeight - nRadius; i++)
617  {
618  for (int j = nRadius; j < imageWidth - nRadius; j++)
619  {
620  int nIndex = i * imageWidth + j;
621 
622  if (pInputImage->pixels[nIndex] == 0)
623  {
624  int nSum = 0;
625  int nNumPixels = 0;
626 
627  for (int l = -nRadius; l <= nRadius; l++)
628  {
629  for (int k = -nRadius; k <= nRadius; k++)
630  {
631  int nTempIndex = nIndex + l * imageWidth + k;
632 
633  if (pInputImage->pixels[nTempIndex] != 0)
634  {
635  nSum += pInputImage->pixels[nTempIndex];
636  nNumPixels++;
637  }
638  }
639  }
640 
641  if (nNumPixels > 0)
642  {
643  pOutputImage->pixels[nIndex] = nSum / nNumPixels;
644  }
645  }
646  }
647  }
648  }
649 
650  void
651  CalculateSmoothedDisparityImage(float* pInputDisparity,
652  float* pSmoothedDisparity,
653  const int imageWidth,
654  const int imageHeight,
655  const int nRadius)
656  {
657 
658  for (int i = 0; i < imageWidth * imageHeight; i++)
659  {
660  pSmoothedDisparity[i] = pInputDisparity[i];
661  }
662 
663  for (int i = nRadius; i < imageHeight - nRadius; i++)
664  {
665  for (int j = nRadius; j < imageWidth - nRadius; j++)
666  {
667  int nIndex = i * imageWidth + j;
668 
669  if (pInputDisparity[nIndex] != 0)
670  {
671  float fSum = 0;
672  int nNumPixels = 0;
673 
674  for (int l = -nRadius; l <= nRadius; l++)
675  {
676  for (int k = -nRadius; k <= nRadius; k++)
677  {
678  int nTempIndex = nIndex + l * imageWidth + k;
679 
680  if (pInputDisparity[nTempIndex] != 0)
681  {
682  fSum += pInputDisparity[nTempIndex];
683  nNumPixels++;
684  }
685  }
686  }
687 
688  pSmoothedDisparity[nIndex] = fSum / (float)nNumPixels;
689  }
690  }
691  }
692  }
693 
694 } // namespace visionx::depthfromstereo
GfxTL::Vec3d
VectorXD< 3, double > Vec3d
Definition: VectorXD.h:737
visionx::depthfromstereo::FillHolesGray
void FillHolesGray(const CByteImage *pInputImage, CByteImage *pOutputImage, const int imageWidth, const int imageHeight, const int nRadius)
Definition: DepthFromStereo.cpp:604
index
uint8_t index
Definition: EtherCATFrame.h:59
visionx::depthfromstereo::CalculateSmoothedDisparityImage
void CalculateSmoothedDisparityImage(float *pInputDisparity, float *pSmoothedDisparity, const int imageWidth, const int imageHeight, const int nRadius)
Definition: DepthFromStereo.cpp:651
visionx::depthfromstereo::GetPointsFromDisparity
void GetPointsFromDisparity(const CByteImage *pImageLeftColor, const CByteImage *pImageRightColor, const CByteImage *pImageLeftGrey, const CByteImage *pImageRightGrey, const int nDisparityPointDistance, pcl::PointCloud< pcl::PointXYZRGBA > &aPointsFromDisparity, CByteImage *pDisparityImage, const int imageWidth, const int imageHeight, CStereoCalibration *pStereoCalibration, bool imagesAreUndistorted, const bool smoothDisparities)
Definition: DepthFromStereo.cpp:95
GfxTL::Vec2d
VectorXD< 2, double > Vec2d
Definition: VectorXD.h:736
float
#define float
Definition: 16_Level.h:22
DepthFromStereo.h
visionx::depthfromstereo
Definition: DepthFromStereo.cpp:46