Main MRPT website > C++ reference for MRPT 1.9.9
CObservation3DRangeScan.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2017, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 
10 #include "obs-precomp.h" // Precompiled headers
11 
13 #include <mrpt/poses/CPosePDF.h>
14 #include <mrpt/utils/CStream.h>
16 
17 #include <mrpt/math/CMatrix.h>
19 #include <mrpt/math/ops_containers.h> // norm(), etc.
22 #include <mrpt/utils/CTimeLogger.h>
24 #include <mrpt/system/filesystem.h>
26 
27 #include <limits>
28 
29 using namespace std;
30 using namespace mrpt::obs;
31 using namespace mrpt::utils;
32 using namespace mrpt::poses;
33 using namespace mrpt::math;
34 
35 // This must be added to any CSerializable class implementation file.
37 
38 // Static LUT:
39 static CObservation3DRangeScan::TCached3DProjTables lut_3dproj;
41 {
42  return lut_3dproj;
43 }
44 
45 static bool EXTERNALS_AS_TEXT_value = false;
46 void CObservation3DRangeScan::EXTERNALS_AS_TEXT(bool value)
47 {
49 }
50 bool CObservation3DRangeScan::EXTERNALS_AS_TEXT()
51 {
53 }
54 
55 
56 // Whether to use a memory pool for 3D points:
57 #define COBS3DRANGE_USE_MEMPOOL
58 
59 // Do performance time logging?
60 //#define PROJ3D_PERFLOG
61 
62 // Data types for memory pooling CObservation3DRangeScan:
63 #ifdef COBS3DRANGE_USE_MEMPOOL
64 
66 
67 // Memory pool for XYZ points ----------------
69 {
70  /** Width*Height, that is, the number of 3D points */
71  size_t WH;
72  inline bool isSuitable(
74  {
75  return WH >= req.WH;
76  }
77 };
79 {
80  std::vector<float> pts_x, pts_y, pts_z;
81  /** for each point, the corresponding (x,y) pixel coordinates */
82  std::vector<uint16_t> idxs_x, idxs_y;
83 };
88 
89 // Memory pool for the rangeImage matrix ----------------
91 {
92  /** Size of matrix */
93  int H, W;
94  inline bool isSuitable(
96  {
97  return H == req.H && W == req.W;
98  }
99 };
101 {
103 };
108 
110 {
111  if (!obs.points3D_x.empty())
112  {
113  // Before dying, donate my memory to the pool for the joy of future
114  // class-brothers...
116  if (pool)
117  {
119  mem_params.WH = obs.points3D_x.capacity();
120  if (obs.points3D_y.capacity() != mem_params.WH)
121  obs.points3D_y.resize(mem_params.WH);
122  if (obs.points3D_z.capacity() != mem_params.WH)
123  obs.points3D_z.resize(mem_params.WH);
124  if (obs.points3D_idxs_x.capacity() != mem_params.WH)
125  obs.points3D_idxs_x.resize(mem_params.WH);
126  if (obs.points3D_idxs_y.capacity() != mem_params.WH)
127  obs.points3D_idxs_y.resize(mem_params.WH);
128 
131  obs.points3D_x.swap(mem_block->pts_x);
132  obs.points3D_y.swap(mem_block->pts_y);
133  obs.points3D_z.swap(mem_block->pts_z);
134  obs.points3D_idxs_x.swap(mem_block->idxs_x);
135  obs.points3D_idxs_y.swap(mem_block->idxs_y);
136 
137  pool->dump_to_pool(mem_params, mem_block);
138  }
139  }
140 }
142 {
143  if (obs.rangeImage.cols() > 1 && obs.rangeImage.rows() > 1)
144  {
145  // Before dying, donate my memory to the pool for the joy of future
146  // class-brothers...
148  if (pool)
149  {
151  mem_params.H = obs.rangeImage.rows();
152  mem_params.W = obs.rangeImage.cols();
153 
156  obs.rangeImage.swap(mem_block->rangeImage);
157 
158  pool->dump_to_pool(mem_params, mem_block);
159  }
160  }
161 }
162 
163 #endif
164 
165 /*---------------------------------------------------------------
166  Constructor
167  ---------------------------------------------------------------*/
168 CObservation3DRangeScan::CObservation3DRangeScan()
169  : m_points3D_external_stored(false),
170  m_rangeImage_external_stored(false),
171  hasPoints3D(false),
172  hasRangeImage(false),
173  range_is_depth(true),
174  hasIntensityImage(false),
175  intensityImageChannel(CH_VISIBLE),
176  hasConfidenceImage(false),
177  pixelLabels(), // Start without label info
178  cameraParams(),
179  cameraParamsIntensity(),
180  relativePoseIntensityWRTDepth(
181  0, 0, 0, DEG2RAD(-90), DEG2RAD(0), DEG2RAD(-90)),
182  maxRange(5.0f),
183  sensorPose(),
184  stdError(0.01f)
185 {
186 }
187 
188 /*---------------------------------------------------------------
189  Destructor
190  ---------------------------------------------------------------*/
191 
193 {
194 #ifdef COBS3DRANGE_USE_MEMPOOL
197 #endif
198 }
199 
200 /*---------------------------------------------------------------
201  Implements the writing to a CStream capability of CSerializable objects
202  ---------------------------------------------------------------*/
204  mrpt::utils::CStream& out, int* version) const
205 {
206  if (version)
207  *version = 8;
208  else
209  {
210  // The data
211  out << maxRange << sensorPose;
212 
213  out << hasPoints3D;
214  if (hasPoints3D)
215  {
216  ASSERT_(
217  points3D_x.size() == points3D_y.size() &&
218  points3D_x.size() == points3D_z.size() &&
219  points3D_idxs_x.size() == points3D_x.size() &&
220  points3D_idxs_y.size() == points3D_x.size())
221  uint32_t N = points3D_x.size();
222  out << N;
223  if (N)
224  {
229  &points3D_idxs_x[0], N); // New in v8
231  &points3D_idxs_y[0], N); // New in v8
232  }
233  }
234 
235  out << hasRangeImage;
236  if (hasRangeImage) out << rangeImage;
237  out << hasIntensityImage;
238  if (hasIntensityImage) out << intensityImage;
239  out << hasConfidenceImage;
241 
242  out << cameraParams; // New in v2
243  out << cameraParamsIntensity; // New in v4
244  out << relativePoseIntensityWRTDepth; // New in v4
245 
246  out << stdError;
247  out << timestamp;
248  out << sensorLabel;
249 
250  // New in v3:
253 
254  // New in v5:
255  out << range_is_depth;
256 
257  // New in v6:
258  out << static_cast<int8_t>(intensityImageChannel);
259 
260  // New in v7:
261  out << hasPixelLabels();
262  if (hasPixelLabels())
263  {
264  pixelLabels->writeToStream(out);
265  }
266  }
267 }
268 
269 /*---------------------------------------------------------------
270  Implements the reading from a CStream capability of CSerializable objects
271  ---------------------------------------------------------------*/
273  mrpt::utils::CStream& in, int version)
274 {
275  switch (version)
276  {
277  case 0:
278  case 1:
279  case 2:
280  case 3:
281  case 4:
282  case 5:
283  case 6:
284  case 7:
285  case 8:
286  {
287  uint32_t N;
288 
289  in >> maxRange >> sensorPose;
290 
291  if (version > 0)
292  in >> hasPoints3D;
293  else
294  hasPoints3D = true;
295 
296  if (hasPoints3D)
297  {
298  in >> N;
300 
301  if (N)
302  {
303  in.ReadBufferFixEndianness(&points3D_x[0], N);
304  in.ReadBufferFixEndianness(&points3D_y[0], N);
305  in.ReadBufferFixEndianness(&points3D_z[0], N);
306 
307  if (version == 0)
308  {
309  vector<char> validRange(N); // for v0.
310  in.ReadBuffer(
311  &validRange[0], sizeof(validRange[0]) * N);
312  }
313  if (version >= 8)
314  {
315  in.ReadBufferFixEndianness(&points3D_idxs_x[0], N);
316  in.ReadBufferFixEndianness(&points3D_idxs_y[0], N);
317  }
318  }
319  }
320  else
321  {
322  this->resizePoints3DVectors(0);
323  }
324 
325  if (version >= 1)
326  {
327  in >> hasRangeImage;
328  if (hasRangeImage)
329  {
330 #ifdef COBS3DRANGE_USE_MEMPOOL
331  // We should call "rangeImage_setSize()" to exploit the
332  // mempool:
333  this->rangeImage_setSize(480, 640);
334 #endif
335  in >> rangeImage;
336  }
337 
340 
343 
344  if (version >= 2)
345  {
346  in >> cameraParams;
347 
348  if (version >= 4)
349  {
352  }
353  else
354  {
357  }
358  }
359  }
360 
361  in >> stdError;
362  in >> timestamp;
363  in >> sensorLabel;
364 
365  if (version >= 3)
366  {
367  // New in v3:
371  }
372  else
373  {
376  }
377 
378  if (version >= 5)
379  {
380  in >> range_is_depth;
381  }
382  else
383  {
384  range_is_depth = true;
385  }
386 
387  if (version >= 6)
388  {
389  int8_t i;
390  in >> i;
391  intensityImageChannel = static_cast<TIntensityChannelID>(i);
392  }
393  else
394  {
396  }
397 
398  pixelLabels.reset(); // Remove existing data first (_unique() is to
399  // leave alive any user copies of the shared
400  // pointer).
401  if (version >= 7)
402  {
403  bool do_have_labels;
404  in >> do_have_labels;
405 
406  if (do_have_labels)
407  pixelLabels.reset(
409  }
410  }
411  break;
412  default:
414  };
415 }
416 
418 {
420 
421  std::swap(hasPoints3D, o.hasPoints3D);
422  points3D_x.swap(o.points3D_x);
423  points3D_y.swap(o.points3D_y);
424  points3D_z.swap(o.points3D_z);
429 
430  std::swap(hasRangeImage, o.hasRangeImage);
431  rangeImage.swap(o.rangeImage);
434 
435  std::swap(hasIntensityImage, o.hasIntensityImage);
438 
441 
442  std::swap(pixelLabels, o.pixelLabels);
443 
445 
446  std::swap(cameraParams, o.cameraParams);
448 
449  std::swap(maxRange, o.maxRange);
450  std::swap(sensorPose, o.sensorPose);
451  std::swap(stdError, o.stdError);
452 }
453 
455 {
457  {
458  const string fil = points3D_getExternalStorageFileAbsolutePath();
460  "txt", mrpt::system::extractFileExtension(fil, true)))
461  {
462  CMatrixFloat M;
463  M.loadFromTextFile(fil);
464  ASSERT_EQUAL_(M.rows(), 3);
465 
466  M.extractRow(0, const_cast<std::vector<float>&>(points3D_x));
467  M.extractRow(1, const_cast<std::vector<float>&>(points3D_y));
468  M.extractRow(2, const_cast<std::vector<float>&>(points3D_z));
469  }
470  else
471  {
473  f >> const_cast<std::vector<float>&>(points3D_x) >>
474  const_cast<std::vector<float>&>(points3D_y) >>
475  const_cast<std::vector<float>&>(points3D_z);
476  }
477  }
478 
480  {
483  "txt", mrpt::system::extractFileExtension(fil, true)))
484  {
485  const_cast<CMatrix&>(rangeImage).loadFromTextFile(fil);
486  }
487  else
488  {
490  f >> const_cast<CMatrix&>(rangeImage);
491  }
492  }
493 }
494 
496 {
498  {
502  }
503 
505 
508 }
509 
511  std::string& out_path) const
512 {
514  if (m_rangeImage_external_file[0] == '/' ||
515  (m_rangeImage_external_file[1] == ':' &&
516  m_rangeImage_external_file[2] == '\\'))
517  {
518  out_path = m_rangeImage_external_file;
519  }
520  else
521  {
522  out_path = CImage::getImagesPathBase();
523  size_t N = CImage::getImagesPathBase().size() - 1;
524  if (CImage::getImagesPathBase()[N] != '/' &&
525  CImage::getImagesPathBase()[N] != '\\')
526  out_path += "/";
527  out_path += m_rangeImage_external_file;
528  }
529 }
531  std::string& out_path) const
532 {
533  ASSERT_(m_points3D_external_file.size() > 2);
534  if (m_points3D_external_file[0] == '/' ||
535  (m_points3D_external_file[1] == ':' &&
536  m_points3D_external_file[2] == '\\'))
537  {
538  out_path = m_points3D_external_file;
539  }
540  else
541  {
542  out_path = CImage::getImagesPathBase();
543  size_t N = CImage::getImagesPathBase().size() - 1;
544  if (CImage::getImagesPathBase()[N] != '/' &&
545  CImage::getImagesPathBase()[N] != '\\')
546  out_path += "/";
547  out_path += m_points3D_external_file;
548  }
549 }
550 
552  const std::string& fileName_, const std::string& use_this_base_dir)
553 {
555  ASSERT_(
556  points3D_x.size() == points3D_y.size() &&
557  points3D_x.size() == points3D_z.size())
558 
561  mrpt::system::fileNameChangeExtension(fileName_, "txt");
562  else
564  mrpt::system::fileNameChangeExtension(fileName_, "bin");
565 
566  // Use "use_this_base_dir" in "*_getExternalStorageFileAbsolutePath()"
567  // instead of CImage::getImagesPathBase()
568  const string savedDir = CImage::getImagesPathBase();
569  CImage::setImagesPathBase(use_this_base_dir);
570  const string real_absolute_file_path =
572  CImage::setImagesPathBase(savedDir);
573 
575  {
576  const size_t nPts = points3D_x.size();
577 
578  CMatrixFloat M(3, nPts);
579  M.insertRow(0, points3D_x);
580  M.insertRow(1, points3D_y);
581  M.insertRow(2, points3D_z);
582 
583  M.saveToTextFile(real_absolute_file_path, MATRIX_FORMAT_FIXED);
584  }
585  else
586  {
587  mrpt::utils::CFileGZOutputStream f(real_absolute_file_path);
588  f << points3D_x << points3D_y << points3D_z;
589  }
590 
592 
593  // Really dealloc memory, clear() is not enough:
599 }
601  const std::string& fileName_, const std::string& use_this_base_dir)
602 {
606  mrpt::system::fileNameChangeExtension(fileName_, "txt");
607  else
609  mrpt::system::fileNameChangeExtension(fileName_, "bin");
610 
611  // Use "use_this_base_dir" in "*_getExternalStorageFileAbsolutePath()"
612  // instead of CImage::getImagesPathBase()
613  const string savedDir = CImage::getImagesPathBase();
614  CImage::setImagesPathBase(use_this_base_dir);
615  const string real_absolute_file_path =
617  CImage::setImagesPathBase(savedDir);
618 
620  {
621  rangeImage.saveToTextFile(real_absolute_file_path, MATRIX_FORMAT_FIXED);
622  }
623  else
624  {
625  mrpt::utils::CFileGZOutputStream f(real_absolute_file_path);
626  f << rangeImage;
627  }
628 
630  rangeImage.setSize(0, 0);
631 }
632 
633 // ============== Auxiliary function for "recoverCameraCalibrationParameters"
634 // =========================
635 
636 #define CALIB_DECIMAT 15
637 
638 namespace mrpt
639 {
640 namespace obs
641 {
642 namespace detail
643 {
645 {
647  const double z_offset;
648  TLevMarData(const CObservation3DRangeScan& obs_, const double z_offset_)
649  : obs(obs_), z_offset(z_offset_)
650  {
651  }
652 };
653 
654 void cam2vec(const TCamera& camPar, CVectorDouble& x)
655 {
656  if (x.size() < 4 + 4) x.resize(4 + 4);
657 
658  x[0] = camPar.fx();
659  x[1] = camPar.fy();
660  x[2] = camPar.cx();
661  x[3] = camPar.cy();
662 
663  for (size_t i = 0; i < 4; i++) x[4 + i] = camPar.dist[i];
664 }
665 void vec2cam(const CVectorDouble& x, TCamera& camPar)
666 {
667  camPar.intrinsicParams(0, 0) = x[0]; // fx
668  camPar.intrinsicParams(1, 1) = x[1]; // fy
669  camPar.intrinsicParams(0, 2) = x[2]; // cx
670  camPar.intrinsicParams(1, 2) = x[3]; // cy
671 
672  for (size_t i = 0; i < 4; i++) camPar.dist[i] = x[4 + i];
673 }
675  const CVectorDouble& par, const TLevMarData& d, CVectorDouble& err)
676 {
677  const CObservation3DRangeScan& obs = d.obs;
678 
679  TCamera params;
680  vec2cam(par, params);
681 
682  const size_t nC = obs.rangeImage.getColCount();
683  const size_t nR = obs.rangeImage.getRowCount();
684 
685  err = CVectorDouble(); // .resize( nC*nR/square(CALIB_DECIMAT) );
686 
687  for (size_t r = 0; r < nR; r += CALIB_DECIMAT)
688  {
689  for (size_t c = 0; c < nC; c += CALIB_DECIMAT)
690  {
691  const size_t idx = nC * r + c;
692 
693  TPoint3D p(
694  obs.points3D_x[idx] + d.z_offset, obs.points3D_y[idx],
695  obs.points3D_z[idx]);
696  TPoint3D P(-p.y, -p.z, p.x);
697  TPixelCoordf pixel;
698  { // mrpt-obs shouldn't depend on mrpt-vision just for this!
699  // pinhole::projectPoint_with_distortion(p_wrt_cam,cam,pixel);
700 
701  // Pinhole model:
702  const double x = P.x / P.z;
703  const double y = P.y / P.z;
704 
705  // Radial distortion:
706  const double r2 = square(x) + square(y);
707  const double r4 = square(r2);
708 
709  pixel.x =
710  params.cx() +
711  params.fx() *
712  (x * (1 + params.dist[0] * r2 + params.dist[1] * r4 +
713  2 * params.dist[2] * x * y +
714  params.dist[3] * (r2 + 2 * square(x))));
715  pixel.y =
716  params.cy() +
717  params.fy() *
718  (y * (1 + params.dist[0] * r2 + params.dist[1] * r4 +
719  2 * params.dist[3] * x * y +
720  params.dist[2] * (r2 + 2 * square(y))));
721  }
722 
723  // In theory, it should be (r,c):
724  err.push_back(c - pixel.x);
725  err.push_back(r - pixel.y);
726  }
727  }
728 } // end error_func
729 }
730 }
731 }
732 
733 /** A Levenberg-Marquart-based optimizer to recover the calibration parameters
734  * of a 3D camera given a range (depth) image and the corresponding 3D point
735  * cloud.
736  * \param camera_offset The offset (in meters) in the +X direction of the point
737  * cloud. It's 1cm for SwissRanger SR4000.
738  * \return The final average reprojection error per pixel (typ <0.05 px)
739  */
741  const CObservation3DRangeScan& obs, mrpt::utils::TCamera& out_camParams,
742  const double camera_offset)
743 {
744  MRPT_START
745 
746  ASSERT_(obs.hasRangeImage && obs.hasPoints3D)
747  ASSERT_(
748  obs.points3D_x.size() == obs.points3D_y.size() &&
749  obs.points3D_x.size() == obs.points3D_z.size())
750 
752  TMyLevMar;
753  TMyLevMar::TResultInfo info;
754 
755  const size_t nR = obs.rangeImage.getRowCount();
756  const size_t nC = obs.rangeImage.getColCount();
757 
758  TCamera camInit;
759  camInit.ncols = nC;
760  camInit.nrows = nR;
761  camInit.intrinsicParams(0, 0) = 250;
762  camInit.intrinsicParams(1, 1) = 250;
763  camInit.intrinsicParams(0, 2) = nC >> 1;
764  camInit.intrinsicParams(1, 2) = nR >> 1;
765 
766  CVectorDouble initial_x;
767  detail::cam2vec(camInit, initial_x);
768 
769  initial_x.resize(8);
770  CVectorDouble increments_x(initial_x.size());
771  increments_x.assign(1e-4);
772 
773  CVectorDouble optimal_x;
774 
775  TMyLevMar lm;
776  lm.execute(
777  optimal_x, initial_x, &mrpt::obs::detail::cost_func, increments_x,
778  detail::TLevMarData(obs, camera_offset), info,
779  mrpt::utils::LVL_INFO, /* verbose */
780  1000, /* max iter */
781  1e-3, 1e-9, 1e-9, false);
782 
783  const double avr_px_err =
784  sqrt(info.final_sqr_err / (nC * nR / square(CALIB_DECIMAT)));
785 
786  out_camParams.ncols = nC;
787  out_camParams.nrows = nR;
788  out_camParams.focalLengthMeters = camera_offset;
789  detail::vec2cam(optimal_x, out_camParams);
790 
791  return avr_px_err;
792 
793  MRPT_END
794 }
795 
797  CObservation3DRangeScan& obs, const unsigned int& r1,
798  const unsigned int& r2, const unsigned int& c1, const unsigned int& c2)
799 {
800  unsigned int cols = cameraParams.ncols;
801  unsigned int rows = cameraParams.nrows;
802 
803  ASSERT_((r1 < r2) && (c1 < c2))
804  ASSERT_((r2 < rows) && (c2 < cols))
805 
806  // Maybe we needed to copy more base obs atributes
807 
808  // Copy zone of range image
810  if (hasRangeImage)
811  rangeImage.extractSubmatrix(r1, r2, c1, c2, obs.rangeImage);
812 
813  // Copy zone of intensity image
816  if (hasIntensityImage)
818  obs.intensityImage, c1, r1, c2 - c1, r2 - r1);
819 
820  // Copy zone of confidence image
822  if (hasConfidenceImage)
824  obs.confidenceImage, c1, r1, c2 - c1, r2 - r1);
825 
826  // Zone labels: It's too complex, just document that pixel labels are NOT
827  // extracted.
828 
829  // Copy zone of scanned points
830  obs.hasPoints3D = hasPoints3D;
831  if (hasPoints3D)
832  {
833  // Erase a possible previous content
834  if (obs.points3D_x.size() > 0)
835  {
836  obs.points3D_x.clear();
837  obs.points3D_y.clear();
838  obs.points3D_z.clear();
839  }
840 
841  for (unsigned int i = r1; i < r2; i++)
842  for (unsigned int j = c1; j < c2; j++)
843  {
844  obs.points3D_x.push_back(points3D_x.at(cols * i + j));
845  obs.points3D_y.push_back(points3D_y.at(cols * i + j));
846  obs.points3D_z.push_back(points3D_z.at(cols * i + j));
847  }
848  }
849 
850  obs.maxRange = maxRange;
851  obs.sensorPose = sensorPose;
852  obs.stdError = stdError;
853 
855 }
856 
857 /** Use this method instead of resizing all three \a points3D_x, \a points3D_y &
858  * \a points3D_z to allow the usage of the internal memory pool. */
860 {
861 #ifdef COBS3DRANGE_USE_MEMPOOL
862  // If WH=0 this is a clear:
863  if (!WH)
864  {
870  return;
871  }
872 
873  if (WH <= points3D_x.size()) // reduce size, don't realloc
874  {
875  points3D_x.resize(WH);
876  points3D_y.resize(WH);
877  points3D_z.resize(WH);
878  points3D_idxs_x.resize(WH);
879  points3D_idxs_y.resize(WH);
880  return;
881  }
882 
883  // Request memory for the X,Y,Z buffers from the memory pool:
885  if (pool)
886  {
888  mem_params.WH = WH;
889 
891  pool->request_memory(mem_params);
892 
893  if (mem_block)
894  { // Take the memory via swaps:
895  points3D_x.swap(mem_block->pts_x);
896  points3D_y.swap(mem_block->pts_y);
897  points3D_z.swap(mem_block->pts_z);
898  points3D_idxs_x.swap(mem_block->idxs_x);
899  points3D_idxs_y.swap(mem_block->idxs_y);
900  delete mem_block;
901  }
902  }
903 #endif
904 
905  // Either if there was no pool memory or we got it, make sure the size of
906  // vectors is OK:
907  points3D_x.resize(WH);
908  points3D_y.resize(WH);
909  points3D_z.resize(WH);
910  points3D_idxs_x.resize(WH);
911  points3D_idxs_y.resize(WH);
912 }
913 
915 {
916  // x,y,z vectors have the same size.
917  return points3D_x.size();
918 }
919 
920 // Similar to calling "rangeImage.setSize(H,W)" but this method provides memory
921 // pooling to speed-up the memory allocation.
922 void CObservation3DRangeScan::rangeImage_setSize(const int H, const int W)
923 {
924 #ifdef COBS3DRANGE_USE_MEMPOOL
925  // Request memory from the memory pool:
927  if (pool)
928  {
930  mem_params.H = H;
931  mem_params.W = W;
932 
934  pool->request_memory(mem_params);
935 
936  if (mem_block)
937  { // Take the memory via swaps:
938  rangeImage.swap(mem_block->rangeImage);
939  delete mem_block;
940  return;
941  }
942  }
943 // otherwise, continue with the normal method:
944 #endif
945  // Fall-back to normal method:
946  rangeImage.setSize(H, W);
947 }
948 
949 // Return true if \a relativePoseIntensityWRTDepth equals the pure rotation
950 // (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon)
952 {
953  static const double EPSILON = 1e-7;
954  static mrpt::poses::CPose3D ref_pose(
955  0, 0, 0, DEG2RAD(-90), 0, DEG2RAD(-90));
956 
957  return (relativePoseIntensityWRTDepth.m_coords.array().abs() < EPSILON)
958  .all() &&
959  ((ref_pose.getRotationMatrix() -
961  .array()
962  .abs() < EPSILON)
963  .all();
964 }
965 
969 {
970  out_scan2d.sensorLabel = sensorLabel;
971  out_scan2d.timestamp = this->timestamp;
972 
973  if (!this->hasRangeImage)
974  { // Nothing to do!
975  out_scan2d.resizeScan(0);
976  return;
977  }
978 
979  const size_t nCols = this->rangeImage.cols();
980  const size_t nRows = this->rangeImage.rows();
981  if (fp.rangeMask_min)
982  { // sanity check:
983  ASSERT_EQUAL_(fp.rangeMask_min->cols(), rangeImage.cols());
984  ASSERT_EQUAL_(fp.rangeMask_min->rows(), rangeImage.rows());
985  }
986  if (fp.rangeMask_max)
987  { // sanity check:
988  ASSERT_EQUAL_(fp.rangeMask_max->cols(), rangeImage.cols());
989  ASSERT_EQUAL_(fp.rangeMask_max->rows(), rangeImage.rows());
990  }
991 
992  // Compute the real horizontal FOV from the range camera intrinsic calib
993  // data:
994  // Note: this assumes the range image has been "undistorted", which is true
995  // for data
996  // from OpenNI, and will be in the future for libfreenect in MRPT,
997  // but it's
998  // not implemented yet (as of Mar 2012), so this is an approximation
999  // in that case.
1000  const double cx = this->cameraParams.cx();
1001  const double cy = this->cameraParams.cy();
1002  const double fx = this->cameraParams.fx();
1003  const double fy = this->cameraParams.fy();
1004 
1005  // (Imagine the camera seen from above to understand this geometry)
1006  const double real_FOV_left = atan2(cx, fx);
1007  const double real_FOV_right = atan2(nCols - 1 - cx, fx);
1008 
1009  // FOV of the equivalent "fake" "laser scanner":
1010  const float FOV_equiv = 2. * std::max(real_FOV_left, real_FOV_right);
1011 
1012  // Now, we should create more "fake laser" points than columns in the image,
1013  // since laser scans are assumed to sample space at evenly-spaced angles,
1014  // while in images it is like ~tan(angle).
1015  ASSERT_ABOVE_(
1016  sp.oversampling_ratio, (sp.use_origin_sensor_pose ? 0.0 : 1.0));
1017  const size_t nLaserRays =
1018  static_cast<size_t>(nCols * sp.oversampling_ratio);
1019 
1020  // Prepare 2D scan data fields:
1021  out_scan2d.aperture = FOV_equiv;
1022  out_scan2d.maxRange = this->maxRange;
1023  out_scan2d.resizeScan(nLaserRays);
1024 
1025  out_scan2d.resizeScanAndAssign(
1026  nLaserRays, 2.0 * this->maxRange,
1027  false); // default: all ranges=invalid
1028  if (sp.use_origin_sensor_pose)
1029  out_scan2d.sensorPose = mrpt::poses::CPose3D();
1030  else
1031  out_scan2d.sensorPose = this->sensorPose;
1032 
1033  // The vertical FOVs given by the user can be translated into limits of the
1034  // tangents (tan>0 means above, i.e. z>0):
1035  const float tan_min = -tan(std::abs(sp.angle_inf));
1036  const float tan_max = tan(std::abs(sp.angle_sup));
1037 
1038  // Precompute the tangents of the vertical angles of each "ray"
1039  // for every row in the range image:
1040  std::vector<float> vert_ang_tan(nRows);
1041  for (size_t r = 0; r < nRows; r++)
1042  vert_ang_tan[r] = static_cast<float>((cy - r) / fy);
1043 
1044  if (!sp.use_origin_sensor_pose)
1045  {
1046  // Algorithm 1: each column in the range image corresponds to a known
1047  // orientation in the 2D scan:
1048  // -------------------
1049  out_scan2d.rightToLeft = false;
1050 
1051  // Angle "counter" for the fake laser scan direction, and the increment:
1052  double ang = -FOV_equiv * 0.5;
1053  const double A_ang = FOV_equiv / (nLaserRays - 1);
1054 
1055  TRangeImageFilter rif(fp);
1056 
1057  // Go thru columns, and keep the minimum distance (along the +X axis,
1058  // not 3D distance!)
1059  // for each direction (i.e. for each column) which also lies within the
1060  // vertical FOV passed
1061  // by the user.
1062  for (size_t i = 0; i < nLaserRays; i++, ang += A_ang)
1063  {
1064  // Equivalent column in the range image for the "i'th" ray:
1065  const double tan_ang = tan(ang);
1066  // make sure we don't go out of range (just in case):
1067  const size_t c = std::min(
1068  static_cast<size_t>(std::max(0.0, cx + fx * tan_ang)),
1069  nCols - 1);
1070 
1071  bool any_valid = false;
1072  float closest_range = out_scan2d.maxRange;
1073 
1074  for (size_t r = 0; r < nRows; r++)
1075  {
1076  const float D = this->rangeImage.coeff(r, c);
1077  if (!rif.do_range_filter(r, c, D)) continue;
1078 
1079  // All filters passed:
1080  const float this_point_tan = vert_ang_tan[r] * D;
1081  if (this_point_tan > tan_min && this_point_tan < tan_max)
1082  {
1083  any_valid = true;
1084  mrpt::utils::keep_min(closest_range, D);
1085  }
1086  }
1087 
1088  if (any_valid)
1089  {
1090  out_scan2d.setScanRangeValidity(i, true);
1091  // Compute the distance in 2D from the "depth" in closest_range:
1092  out_scan2d.setScanRange(
1093  i, closest_range * std::sqrt(1.0 + tan_ang * tan_ang));
1094  }
1095  } // end for columns
1096  }
1097  else
1098  {
1099  // Algorithm 2: project to 3D and reproject (for a different sensorPose
1100  // at the origin)
1101  // ------------------------------------------------------------------------
1102  out_scan2d.rightToLeft = true;
1103 
1104  T3DPointsProjectionParams projParams;
1105  projParams.takeIntoAccountSensorPoseOnRobot = true;
1106 
1108  mrpt::make_aligned_shared<mrpt::opengl::CPointCloud>();
1109  this->project3DPointsFromDepthImageInto(*pc, projParams, fp);
1110 
1111  const std::vector<float> &xs = pc->getArrayX(), &ys = pc->getArrayY(),
1112  &zs = pc->getArrayZ();
1113  const size_t N = xs.size();
1114 
1115  const double A_ang = FOV_equiv / (nLaserRays - 1);
1116  const double ang0 = -FOV_equiv * 0.5;
1117 
1118  for (size_t i = 0; i < N; i++)
1119  {
1120  if (zs[i] < sp.z_min || zs[i] > sp.z_max) continue;
1121 
1122  const double phi_wrt_origin = atan2(ys[i], xs[i]);
1123 
1124  int i_range = (phi_wrt_origin - ang0) / A_ang;
1125  if (i_range < 0 || i_range >= int(nLaserRays)) continue;
1126 
1127  const float r_wrt_origin = ::hypotf(xs[i], ys[i]);
1128  if (out_scan2d.scan[i_range] > r_wrt_origin)
1129  out_scan2d.setScanRange(i_range, r_wrt_origin);
1130  out_scan2d.setScanRangeValidity(i_range, true);
1131  }
1132  }
1133 }
1134 
1136 {
1138 
1139  this->load(); // Make sure the 3D point cloud, etc... are all loaded in
1140  // memory.
1141 
1142  o << "Homogeneous matrix for the sensor's 3D pose, relative to robot "
1143  "base:\n";
1144  o << sensorPose.getHomogeneousMatrixVal() << sensorPose << endl;
1145 
1146  o << "maxRange = " << maxRange << " m" << endl;
1147 
1148  o << "Has 3D point cloud? ";
1149  if (hasPoints3D)
1150  {
1151  o << "YES: " << points3D_x.size() << " points";
1153  o << ". External file: " << points3D_getExternalStorageFile()
1154  << endl;
1155  else
1156  o << " (embedded)." << endl;
1157  }
1158  else
1159  o << "NO" << endl;
1160 
1161  o << "Has raw range data? " << (hasRangeImage ? "YES" : "NO");
1162  if (hasRangeImage)
1163  {
1165  o << ". External file: " << rangeImage_getExternalStorageFile()
1166  << endl;
1167  else
1168  o << " (embedded)." << endl;
1169  }
1170 
1171  o << endl << "Has intensity data? " << (hasIntensityImage ? "YES" : "NO");
1172  if (hasIntensityImage)
1173  {
1175  o << ". External file: " << intensityImage.getExternalStorageFile()
1176  << endl;
1177  else
1178  o << " (embedded).\n";
1179  // Channel?
1180  o << "Source channel: "
1183  value2name(intensityImageChannel)
1184  << endl;
1185  }
1186 
1187  o << endl << "Has confidence data? " << (hasConfidenceImage ? "YES" : "NO");
1188  if (hasConfidenceImage)
1189  {
1191  o << ". External file: " << confidenceImage.getExternalStorageFile()
1192  << endl;
1193  else
1194  o << " (embedded)." << endl;
1195  }
1196 
1197  o << endl << "Has pixel labels? " << (hasPixelLabels() ? "YES" : "NO");
1198  if (hasPixelLabels())
1199  {
1200  o << " Human readable labels:" << endl;
1202  pixelLabels->pixelLabelNames.begin();
1203  it != pixelLabels->pixelLabelNames.end(); ++it)
1204  o << " label[" << it->first << "]: '" << it->second << "'" << endl;
1205  }
1206 
1207  o << endl << endl;
1208  o << "Depth camera calibration parameters:" << endl;
1209  {
1210  CConfigFileMemory cfg;
1211  cameraParams.saveToConfigFile("DEPTH_CAM_PARAMS", cfg);
1212  o << cfg.getContent() << endl;
1213  }
1214  o << endl << "Intensity camera calibration parameters:" << endl;
1215  {
1216  CConfigFileMemory cfg;
1217  cameraParamsIntensity.saveToConfigFile("INTENSITY_CAM_PARAMS", cfg);
1218  o << cfg.getContent() << endl;
1219  }
1220  o << endl
1221  << endl
1222  << "Pose of the intensity cam. wrt the depth cam:\n"
1225 }
1226 
1228  mrpt::utils::CStream& out) const
1229 {
1230  const uint8_t version = 1; // for possible future changes.
1231  out << version;
1232 
1233  // 1st: Save number MAX_NUM_DIFFERENT_LABELS so we can reconstruct the
1234  // object in the class factory later on.
1235  out << BITFIELD_BYTES;
1236 
1237  // 2nd: data-specific serialization:
1238  this->internal_writeToStream(out);
1239 }
1240 
1241 // Deserialization and class factory. All in one, ladies and gentlemen
1245 {
1246  uint8_t version;
1247  in >> version;
1248 
1249  switch (version)
1250  {
1251  case 1:
1252  {
1253  // 1st: Read NUM BYTES
1254  uint8_t bitfield_bytes;
1255  in >> bitfield_bytes;
1256 
1257  // Hand-made class factory. May be a good solution if there will be
1258  // not too many different classes:
1260  switch (bitfield_bytes)
1261  {
1262  case 1:
1264  break;
1265  case 2:
1267  break;
1268  case 3:
1269  case 4:
1271  break;
1272  case 5:
1273  case 6:
1274  case 7:
1275  case 8:
1277  break;
1278  default:
1279  throw std::runtime_error(
1280  "Unknown type of pixelLabel inner class while "
1281  "deserializing!");
1282  };
1283  // 2nd: data-specific serialization:
1284  new_obj->internal_readFromStream(in);
1285 
1286  return new_obj;
1287  }
1288  break;
1289 
1290  default:
1292  break;
1293  };
1294 }
1295 
1297  : angle_sup(mrpt::utils::DEG2RAD(5)),
1298  angle_inf(mrpt::utils::DEG2RAD(5)),
1299  z_min(-std::numeric_limits<double>::max()),
1300  z_max(std::numeric_limits<double>::max()),
1301  oversampling_ratio(1.2),
1302  use_origin_sensor_pose(false)
1303 {
1304 }
#define ASSERT_EQUAL_(__A, __B)
bool isSuitable(const CObservation3DRangeScan_Points_MemPoolParams &req) const
An implementation of the Levenberg-Marquardt algorithm for least-square minimization.
bool m_points3D_external_stored
If set to true, m_points3D_external_file is valid.
A pair (x,y) of pixel coordinates (subpixel resolution).
Definition: TPixelCoord.h:21
virtual void internal_writeToStream(mrpt::utils::CStream &out) const =0
std::string m_rangeImage_external_file
rangeImage is in CImage::getImagesPathBase()+<this_file_name>
Mainly for internal use within CObservation3DRangeScan::project3DPointsFromDepthImageInto() ...
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
bool isSuitable(const CObservation3DRangeScan_Ranges_MemPoolParams &req) const
void getZoneAsObs(CObservation3DRangeScan &obs, const unsigned int &r1, const unsigned int &r2, const unsigned int &c1, const unsigned int &c2)
Extract a ROI of the 3D observation as a new one.
#define min(a, b)
static bool EXTERNALS_AS_TEXT_value
void readFromStream(mrpt::utils::CStream &in, int version) override
Introduces a pure virtual method responsible for loading from a CStream This can not be used directly...
size_t WH
Width*Height, that is, the number of 3D points.
TIntensityChannelID
Enum type for intensityImageChannel.
void resizePoints3DVectors(const size_t nPoints)
Use this method instead of resizing all three points3D_x, points3D_y & points3D_z to allow the usage ...
#define ASSERT_ABOVE_(__A, __B)
double focalLengthMeters
The focal length of the camera, in meters (can be used among &#39;intrinsicParams&#39; to determine the pixel...
Definition: TCamera.h:63
void mempool_donate_range_matrix(CObservation3DRangeScan &obs)
mrpt::utils::TCamera cameraParamsIntensity
Projection parameters of the intensity (graylevel or RGB) camera.
std::vector< uint16_t > idxs_x
for each point, the corresponding (x,y) pixel coordinates
#define IMPLEMENTS_SERIALIZABLE(class_name, base, NameSpace)
This must be inserted in all CSerializable classes implementation files.
void setScanRange(const size_t i, const float val)
void unload() const noexcept
For external storage image objects only, this method unloads the image from memory (or does nothing i...
Definition: CImage.cpp:1909
std::vector< uint16_t > points3D_idxs_x
If hasPoints3D=true, the (x,y) pixel coordinates for each (X,Y,Z) point in points3D_x, points3D_y, points3D_z.
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Definition: TCamera.h:176
double oversampling_ratio
(Default=1.2=120%) How many more laser scans rays to create (read docs for CObservation3DRangeScan::c...
void dump_to_pool(const DATA_PARAMS &params, POOLABLE_DATA *block)
Saves the passed data block (characterized by params) to the pool.
double angle_sup
(Default=5 degrees) [Only if use_origin_sensor_pose=false] The upper & lower half-FOV angle (in radia...
This file implements several operations that operate element-wise on individual or pairs of container...
bool m_rangeImage_external_stored
If set to true, m_rangeImage_external_file is valid.
void getDescriptionAsText(std::ostream &o) const override
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
Declares a class derived from "CObservation" that encapsules a 3D range scan measurement, as from a time-of-flight range camera or any other RGBD sensor.
const mrpt::math::CMatrix * rangeMask_min
(Default: nullptr) If provided, each data range will be tested to be greater-than (rangeMask_min) or ...
Look-up-table struct for project3DPointsFromDepthImageInto()
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:42
signed char int8_t
Definition: rptypes.h:40
STL namespace.
const Scalar * const_iterator
Definition: eigen_plugins.h:27
void swap(CObservation &o)
Swap with another observation, ONLY the data defined here in the base class CObservation.
double z_min
(Default:-inf, +inf) [Only if use_origin_sensor_pose=true] Only obstacle points with Z coordinates wi...
POOLABLE_DATA * request_memory(const DATA_PARAMS &params)
Request a block of data which fulfils the size requirements stated in params.
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
void keep_min(T &var, const K test_val)
If the second argument is below the first one, set the first argument to this lower value...
void rangeImage_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won&#39;t normally want to call this, it&#39;s only used from internal MRPT programs.
T square(const T x)
Inline function for the square of a number.
Definition: bits.h:55
mrpt::math::CMatrix rangeImage
If hasRangeImage=true, a matrix of floats with the range data as captured by the camera (in meters) ...
unsigned char uint8_t
Definition: rptypes.h:41
float maxRange
The maximum range allowed by the device, in meters (e.g.
mrpt::utils::TCamera cameraParams
Projection parameters of the depth camera.
const uint8_t BITFIELD_BYTES
Minimum number of bytes required to hold MAX_NUM_DIFFERENT_LABELS bits.
A generic system for versatile memory pooling.
double fx() const
Get the value of the focal length x-value (in pixels).
Definition: TCamera.h:178
This class implements a config file-like interface over a memory-stored string list.
void getContent(std::string &str) const
Return the current contents of the virtual "config file".
void WriteBufferFixEndianness(const T *ptr, size_t ElementCount)
Writes a sequence of elemental datatypes, taking care of reordering their bytes from the running arch...
Definition: CStream.h:159
double fy() const
Get the value of the focal length y-value (in pixels).
Definition: TCamera.h:180
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:41
std::string rangeImage_getExternalStorageFileAbsolutePath() const
This base provides a set of functions for maths stuff.
Definition: CArrayNumeric.h:19
mrpt::poses::CPose3D relativePoseIntensityWRTDepth
Relative pose of the intensity camera wrt the depth camera (which is the coordinates origin for this ...
#define MRPT_END
mrpt::math::CArrayDouble< 3 > m_coords
The translation vector [x,y,z] access directly or with x(), y(), z() setter/getter methods...
Definition: CPose3D.h:98
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal() const
Definition: CPose3D.h:229
A helper class that can convert an enum value into its textual representation, and viceversa...
Definition: TEnumType.h:38
const GLubyte * c
Definition: glext.h:6313
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
virtual void unload() override
Unload all images, for the case they being delayed-load images stored in external files (othewise...
void swap(CObservation3DRangeScan &o)
Very efficient method to swap the contents of two observations.
#define CALIB_DECIMAT
Transparently opens a compressed "gz" file and reads uncompressed data from it.
void vec2cam(const CVectorDouble &x, TCamera &camPar)
std::string fileNameChangeExtension(const std::string &filename, const std::string &newExtension)
Replace the filename extension by another one.
Definition: filesystem.cpp:369
Used in CObservation3DRangeScan::convertTo2DScan()
std::string m_points3D_external_file
3D points are in CImage::getImagesPathBase()+<this_file_name>
This namespace contains representation of robot actions and observations.
uint32_t ncols
Camera resolution.
Definition: TCamera.h:54
bool hasRangeImage
true means the field rangeImage contains valid data
double x
X,Y,Z coordinates.
mrpt::system::CGenericMemoryPool< CObservation3DRangeScan_Ranges_MemPoolParams, CObservation3DRangeScan_Ranges_MemPoolData > TMyRangesMemPool
void convertTo2DScan(mrpt::obs::CObservation2DRangeScan &out_scan2d, const T3DPointsTo2DScanParams &scanParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams())
Convert this 3D observation into an "equivalent 2D fake laser scan", with a configurable vertical FOV...
std::string extractFileExtension(const std::string &filePath, bool ignore_gz=false)
Extract the extension of a filename.
Definition: filesystem.cpp:97
TIntensityChannelID intensityImageChannel
The source of the intensityImage; typically the visible channel.
#define DEG2RAD
void resizeScanAndAssign(const size_t len, const float rangeVal, const bool rangeValidity, const int32_t rangeIntensity=0)
Resizes all data vectors to allocate a given number of scan rays and assign default values...
std::string points3D_getExternalStorageFileAbsolutePath() const
bool hasPoints3D
true means the field points3D contains valid data.
GLsizei const GLchar ** string
Definition: glext.h:4101
void swap(CImage &o)
Very efficient swap of two images (just swap the internal pointers)
Definition: CImage.cpp:138
double cx() const
Get the value of the principal point x-coordinate (in pixels).
Definition: TCamera.h:174
float stdError
The "sigma" error of the device in meters, used while inserting the scan in an occupancy grid...
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
virtual void internal_readFromStream(mrpt::utils::CStream &in)=0
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates) ...
Definition: TCamera.h:57
#define MRPT_START
void loadFromTextFile(const std::string &file)
Load matrix from a text file, compatible with MATLAB text format.
std::string sensorLabel
An arbitrary label that can be used to identify the sensor.
Definition: CObservation.h:60
void vector_strong_clear(VECTOR_T &v)
Like calling a std::vector<>&#39;s clear() method, but really forcing deallocating the memory...
Definition: bits.h:265
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
mrpt::system::TTimeStamp timestamp
The associated UTC time-stamp.
Definition: CObservation.h:58
A "CObservation"-derived class that represents a 2D range scan measurement (typically from a laser sc...
#define CFileGZOutputStream
Saves data to a file and transparently compress the data using the given compression level...
GLdouble GLdouble GLdouble r
Definition: glext.h:3705
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot.
static TPixelLabelInfoBase * readAndBuildFromStream(mrpt::utils::CStream &in)
mrpt::math::CArrayDouble< 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
Definition: TCamera.h:60
const mrpt::math::CMatrix * rangeMask_max
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
Definition: CPose3D.h:88
Declares a class that represents any robot&#39;s observation.
Definition: CObservation.h:41
void resizeScan(const size_t len)
Resizes all data vectors to allocate a given number of scan rays.
TPixelLabelInfoBase::Ptr pixelLabels
All information about pixel labeling is stored in this (smart pointer to) structure; refer to TPixelL...
Used in CObservation3DRangeScan::project3DPointsFromDepthImageInto()
bool hasIntensityImage
true means the field intensityImage contains valid data
void extract_patch(CImage &patch, const unsigned int col=0, const unsigned int row=0, const unsigned int width=1, const unsigned int height=1) const
Extract a patch from this image, saveing it into "patch" (its previous contents will be overwritten)...
Definition: CImage.cpp:1367
uint32_t nrows
Definition: TCamera.h:54
GLuint in
Definition: glext.h:7274
std::vector< float > points3D_x
If hasPoints3D=true, the (X,Y,Z) coordinates of the 3D point cloud detected by the camera...
mrpt::system::CGenericMemoryPool< CObservation3DRangeScan_Points_MemPoolParams, CObservation3DRangeScan_Points_MemPoolData > TMyPointsMemPool
void rangeImage_setSize(const int HEIGHT, const int WIDTH)
Similar to calling "rangeImage.setSize(H,W)" but this method provides memory pooling to speed-up the ...
float aperture
The "aperture" or field-of-view of the range finder, in radians (typically M_PI = 180 degrees)...
#define ASSERT_(f)
bool hasPixelLabels() const
Returns true if the field CObservation3DRangeScan::pixelLabels contains a non-NULL smart pointer...
static double recoverCameraCalibrationParameters(const CObservation3DRangeScan &in_obs, mrpt::utils::TCamera &out_camParams, const double camera_offset=0.01)
A Levenberg-Marquart-based optimizer to recover the calibration parameters of a 3D camera given a ran...
void project3DPointsFromDepthImageInto(POINTMAP &dest_pointcloud, const T3DPointsProjectionParams &projectParams, const TRangeImageFilterParams &filterParams=TRangeImageFilterParams())
Project the RGB+D images into a 3D point cloud (with color if the target map supports it) and optiona...
void cam2vec(const TCamera &camPar, CVectorDouble &x)
GLenum GLint GLint y
Definition: glext.h:3538
static CObservation3DRangeScan::TCached3DProjTables lut_3dproj
void points3D_convertToExternalStorage(const std::string &fileName, const std::string &use_this_base_dir)
Users won&#39;t normally want to call this, it&#39;s only used from internal MRPT programs.
bool doDepthAndIntensityCamerasCoincide() const
Return true if relativePoseIntensityWRTDepth equals the pure rotation (0,0,0,-90deg,0,-90deg) (with a small comparison epsilon)
mrpt::utils::CImage confidenceImage
If hasConfidenceImage=true, an image with the "confidence" value [range 0-255] as estimated by the ca...
dynamic_vector< double > CVectorDouble
Column vector, like Eigen::MatrixXd, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:44
GLsizei const GLfloat * value
Definition: glext.h:4117
void cost_func(const CVectorDouble &par, const TLevMarData &d, CVectorDouble &err)
std::string getExternalStorageFile() const noexcept
Only if isExternallyStored() returns true.
Definition: CImage.h:783
GLenum GLint x
Definition: glext.h:3538
bool isExternallyStored() const noexcept
See setExternalStorage().
Definition: CImage.h:780
void mempool_donate_xyz_buffers(CObservation3DRangeScan &obs)
mrpt::utils::ContainerReadOnlyProxyAccessor< std::vector< float > > scan
The range values of the scan, in meters.
void getRotationMatrix(mrpt::math::CMatrixDouble33 &ROT) const
Get the 3x3 rotation matrix.
Definition: CPose3D.h:237
std::shared_ptr< CPointCloud > Ptr
Definition: CPointCloud.h:52
Lightweight 3D point.
mrpt::utils::CImage intensityImage
If hasIntensityImage=true, a color or gray-level intensity image of the same size than "rangeImage"...
This class is a "CSerializable" wrapper for "CMatrixFloat".
Definition: CMatrix.h:25
size_t getScanSize() const
Get the size of the scan pointcloud.
bool strCmpI(const std::string &s1, const std::string &s2)
Return true if the two strings are equal (case insensitive)
unsigned __int32 uint32_t
Definition: rptypes.h:47
bool range_is_depth
true: Kinect-like ranges: entries of rangeImage are distances along the +X axis; false: Ranges in ran...
TLevMarData(const CObservation3DRangeScan &obs_, const double z_offset_)
GLfloat GLfloat p
Definition: glext.h:6305
GLenum const GLfloat * params
Definition: glext.h:3534
Virtual interface to all pixel-label information structs.
mrpt::poses::CPose3D sensorPose
The 6D pose of the sensor on the robot at the moment of starting the scan.
const CObservation3DRangeScan & obs
Grayscale or RGB visible channel of the camera sensor.
bool takeIntoAccountSensorPoseOnRobot
(Default: false) If false, local (sensor-centric) coordinates of points are generated.
fixed floating point &#39;f&#39;
Definition: math_frwds.h:76
Structure to hold the parameters of a pinhole camera model.
Definition: TCamera.h:32
virtual void load() const override
Makes sure all images and other fields which may be externally stored are loaded in memory...
void writeToStream(mrpt::utils::CStream &out, int *getVersion) const override
Introduces a pure virtual method responsible for writing to a CStream.
bool rightToLeft
The scanning direction: true=counterclockwise; false=clockwise.
bool use_origin_sensor_pose
(Default:false) If false, the conversion will be such that the 2D observation pose on the robot coinc...
static CGenericMemoryPool< DATA_PARAMS, POOLABLE_DATA > * getInstance(const size_t max_pool_entries=5)
Construct-on-first-use (~singleton) pattern: Return the unique instance of this class for a given tem...
float maxRange
The maximum range allowed by the device, in meters (e.g.
virtual void getDescriptionAsText(std::ostream &o) const
Build a detailed, multi-line textual description of the observation contents and dump it to the outpu...
void setScanRangeValidity(const size_t i, const bool val)
bool hasConfidenceImage
true means the field confidenceImage contains valid data
void saveToConfigFile(const std::string &section, mrpt::utils::CConfigFileBase &cfg) const
Save as a config block:
Definition: TCamera.cpp:117
bool do_range_filter(size_t r, size_t c, const float D) const
Returns true if the point (r,c) with depth D passes all filters.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019