ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
ecvPointCloud.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - CloudViewer: www.cloudViewer.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.cloudViewer.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #ifdef _MSC_VER
11 // To get rid of the warnings about dominant inheritance
12 #pragma warning(disable : 4250)
13 #endif
14 
15 // cloudViewer
16 #include <PointCloudTpl.h>
17 
18 // Local
19 #include "ecvColorScale.h"
20 #include "ecvKDTreeSearchParam.h"
21 #include "ecvNormalVectors.h"
22 #include "ecvWaveform.h"
23 
24 // Qt
25 #if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0)
26 #include <QOpenGLBuffer>
27 #define QGLBuffer QOpenGLBuffer
28 #else
29 #include <QGLBuffer>
30 #endif
31 
32 class ccMesh;
33 class QGLBuffer;
34 class ccPolyline;
35 class ccScalarField;
36 class ccGenericPrimitive;
37 class ecvOrientedBBox;
38 class ccPointCloudLOD;
39 class ecvProgressDialog;
40 
41 namespace cloudViewer {
42 namespace geometry {
43 class Image;
44 class RGBDImage;
45 class VoxelGrid;
46 
47 #ifdef CV_RANSAC_SUPPORT
49 class CV_DB_LIB_API RansacParams {
50 public:
51  enum RANSAC_PRIMITIVE_TYPES {
52  RPT_PLANE = 0,
53  RPT_SPHERE = 1,
54  RPT_CYLINDER = 2,
55  RPT_CONE = 3,
56  RPT_TORUS = 4,
57  };
58 
59 public:
60  float epsilon; // distance threshold
61  float bitmapEpsilon; // bitmap resolution
62  unsigned supportPoints; // this is the minimal numer of points required for
63  // a primitive
64  float maxNormalDev_deg; // maximal normal deviation from ideal shape (in
65  // degrees)
66  float probability; // probability that no better candidate was overlooked
67  // during sampling
68  bool randomColor; // should the resulting detected shapes sub point cloud
69  // be colored randomly
70  std::vector<RANSAC_PRIMITIVE_TYPES> primEnabled; // RANSAC_PRIMITIVE_TYPES
71  float minRadius; // minimum radius threshold
72  float maxRadius; // maximum radius threshold
73  RansacParams()
74  : epsilon(0.005f),
75  bitmapEpsilon(0.01f),
76  supportPoints(500),
77  maxNormalDev_deg(25.0f),
78  probability(0.01f),
79  randomColor(true),
80  minRadius(0.0000001f),
81  maxRadius(1000000.0f) {
82  primEnabled.push_back(RPT_PLANE);
83  primEnabled.push_back(RPT_SPHERE);
84  primEnabled.push_back(RPT_CYLINDER);
85  }
86 
87  RansacParams(float scale)
88  : epsilon(0.005f * scale),
89  bitmapEpsilon(0.01f * scale),
90  supportPoints(500),
91  maxNormalDev_deg(25.0f),
92  probability(0.01f),
93  randomColor(true),
94  minRadius(0.0000001f),
95  maxRadius(1000000.0f) {
96  primEnabled.push_back(RPT_PLANE);
97  primEnabled.push_back(RPT_SPHERE);
98  primEnabled.push_back(RPT_CYLINDER);
99  }
100 };
101 
102 class CV_DB_LIB_API RansacResult {
103 public:
104  std::string getTypeName() const;
105  unsigned getDrawingPrecision() const;
106  bool setDrawingPrecision(unsigned steps);
107 
108 public:
109  std::vector<size_t> indices;
110  std::shared_ptr<ccGenericPrimitive> primitive = nullptr;
111 };
112 
113 using RansacResults = std::vector<RansacResult>;
114 #endif
115 
116 } // namespace geometry
117 
118 namespace camera {
119 class PinholeCameraIntrinsic;
120 }
121 } // namespace cloudViewer
122 
123 /***************************************************
124  ccPointCloud
125 ***************************************************/
126 
129 #if defined(CV_ENV_32)
130 const unsigned CC_MAX_NUMBER_OF_POINTS_PER_CLOUD = 128000000;
131 #else // CV_ENV_64 (but maybe CC_ENV_128 one day ;)
132 const unsigned CC_MAX_NUMBER_OF_POINTS_PER_CLOUD =
133  2000000000; // we must keep it below MAX_INT to avoid probable issues
134  // ;)
135 #endif
136 
138 
147  : public cloudViewer::PointCloudTpl<ccGenericPointCloud> {
148 public:
151 
153 
158  ccPointCloud(QString name = QString()) throw();
159  ccPointCloud(const ccPointCloud& cloud);
160  ccPointCloud(const std::vector<Eigen::Vector3d>& points,
161  const std::string& name = "cloud");
162 
164  ~ccPointCloud() override;
165 
167  CV_CLASS_ENUM getClassID() const override { return CV_TYPES::POINT_CLOUD; }
168 
169 public: // clone, copy, etc.
171 
180  const ccGenericPointCloud* sourceCloud = nullptr);
181 
183 
193  const ccGenericPointCloud* sourceCloud = nullptr);
194 
204  const std::vector<size_t>& indices,
205  bool invert = false);
206 
209  WRN_OUT_OF_MEM_FOR_COLORS = 1,
210  WRN_OUT_OF_MEM_FOR_NORMALS = 2,
211  WRN_OUT_OF_MEM_FOR_SFS = 4,
212  WRN_OUT_OF_MEM_FOR_FWF = 8
213  };
214 
216 
227  int* warnings = nullptr,
228  bool withChildEntities = true) const;
229 
231 
237  ccPointCloud* cloneThis(ccPointCloud* destCloud = nullptr,
238  bool ignoreChildren = false);
239 
240  // inherited from ccGenericPointCloud
242  bool ignoreChildren = false) override;
243 
245 
250  const ccPointCloud& operator+=(const ccPointCloud& cloud);
252  ccPointCloud operator+(const ccPointCloud& cloud) const {
253  return (ccPointCloud(*this) += cloud);
254  }
255 
256 public: // features deletion/clearing
258 
260  void clear() override;
261 
263 
267 
270 
273 
276  inline void colorsHaveChanged() {
277  m_vboManager.updateFlags |= vboSet::UPDATE_COLORS;
278  }
280  inline void normalsHaveChanged() {
281  m_vboManager.updateFlags |= vboSet::UPDATE_NORMALS;
282  }
284  inline void pointsHaveChanged() {
285  m_vboManager.updateFlags |= vboSet::UPDATE_POINTS;
286  }
287 
288 public: // features allocation/resize
290 
294  bool reserve(unsigned numberOfPoints) override;
295 
297 
304  bool reserveThePointsTable(unsigned _numberOfPoints);
305 
307 
315 
317 
325 
327 
332  bool resize(unsigned numberOfPoints) override;
333 
335 
344  bool resizeTheRGBTable(bool fillWithWhite = false);
345 
347 
355 
357  inline void shrinkToFit() {
358  if (size() < capacity()) resize(size());
359  }
360 
361 public: // scalar-fields management
367 
370 
371  // inherited from base class
372  void deleteScalarField(int index) override;
373  void deleteAllScalarFields() override;
374  int addScalarField(const char* uniqueName) override;
375 
377  bool sfColorScaleShown() const;
379  void showSFColorsScale(bool state);
380 
381 public: // associated (scan) grid structure
385  using Shared = QSharedPointer<Grid>;
386 
388  Grid();
389 
391 
393  Grid(const Grid& grid) = default;
394 
396  bool init(unsigned rowCount, unsigned colCount, bool withRGB = false);
397 
399  void setIndex(unsigned row, unsigned col, int index);
400 
402  void setColor(unsigned row, unsigned col, const ecvColor::Rgb& rgb);
403 
406 
408  QImage toImage() const;
409 
410  // inherited from ccSerializableObject
411  inline bool isSerializable() const override { return true; }
412  bool toFile(QFile& out, short dataVersion) const override;
413  bool fromFile(QFile& in,
414  short dataVersion,
415  int flags,
416  LoadedIDMap& oldToNewIDMap) override;
417  short minimumFileVersion() const override;
418 
420  unsigned w;
422  unsigned h;
423 
425  unsigned validCount;
427  unsigned minValidIndex;
429  unsigned maxValidIndex;
430 
432  std::vector<int> indexes;
434  std::vector<ecvColor::Rgb> colors;
435 
438  };
439 
441  size_t gridCount() const { return m_grids.size(); }
443  inline Grid::Shared& grid(size_t gridIndex) { return m_grids[gridIndex]; }
445  inline const Grid::Shared& grid(size_t gridIndex) const {
446  return m_grids[gridIndex];
447  }
449  inline bool addGrid(Grid::Shared grid) {
450  try {
451  m_grids.push_back(grid);
452  } catch (const std::bad_alloc&) {
453  return false;
454  }
455  return true;
456  }
458  inline void removeGrids() { m_grids.resize(0); }
459 
461 
464  double minTriangleAngle_deg = 0.0) const;
465 
466 public: // normals computation/orientation
468 
470  bool computeNormalsWithGrids(double minTriangleAngle_deg = 1.0,
471  ecvProgressDialog* pDlg = nullptr);
472 
475 
478  ecvProgressDialog* pDlg = nullptr);
479 
482  CV_LOCAL_MODEL_TYPES model,
483  ccNormalVectors::Orientation preferredOrientation,
484  PointCoordinateType defaultRadius,
485  ecvProgressDialog* pDlg = nullptr);
486 
488  bool orientNormalsWithMST(unsigned kNN = 6,
489  ecvProgressDialog* pDlg = nullptr);
490 
492  bool orientNormalsWithFM(unsigned char level,
493  ecvProgressDialog* pDlg = nullptr);
494 
495 public: // waveform (e.g. from airborne scanners)
497  bool hasFWF() const;
498 
500  ccWaveformProxy waveformProxy(unsigned index) const;
501 
503  using FWFDescriptorSet = QMap<uint8_t, WaveformDescriptor>;
504 
506  using FWFDataContainer = std::vector<uint8_t>;
507  using SharedFWFDataContainer = QSharedPointer<const FWFDataContainer>;
508 
510  FWFDescriptorSet& fwfDescriptors() { return m_fwfDescriptors; }
512  const FWFDescriptorSet& fwfDescriptors() const { return m_fwfDescriptors; }
513 
515  std::vector<ccWaveform>& waveforms() { return m_fwfWaveforms; }
517  const std::vector<ccWaveform>& waveforms() const { return m_fwfWaveforms; }
518 
523 
525  SharedFWFDataContainer& fwfData() { return m_fwfData; }
527  const SharedFWFDataContainer& fwfData() const { return m_fwfData; }
528 
530 
534 
536  bool computeFWFAmplitude(double& minVal,
537  double& maxVal,
538  ecvProgressDialog* pDlg = nullptr) const;
539 
541  void clearFWFData();
542 
543 public: // other methods
545 
548 
549  // inherited from base class
550  void invalidateBoundingBox() override;
551 
552  // inherited from ccHObject
553  void getDrawingParameters(glDrawParams& params) const override;
554  unsigned getUniqueIDForDisplay() const override;
555 
556  // inherited from ccDrawableObject
557  bool hasColors() const override;
558  bool hasNormals() const override;
559  bool hasScalarFields() const override;
560  bool hasDisplayedScalarField() const override;
561 
562  // inherited from cloudViewer::GenericCloud
563  unsigned char testVisibility(const CCVector3& P) const override;
564 
565  // inherited from cloudViewer::GenericIndexedCloud
566  bool normalsAvailable() const override { return hasNormals(); }
567  const CCVector3* getNormal(unsigned pointIndex) const
568  override; // equivalent to getPointNormal, but for cloudViewer
569 
570  // inherited from ccGenericPointCloud
571  const ecvColor::Rgb* getScalarValueColor(ScalarType d) const override;
573  unsigned pointIndex) const override;
574  ScalarType getPointDisplayedDistance(unsigned pointIndex) const override;
575 
576  const ecvColor::Rgb& getPointColor(unsigned pointIndex) const override;
577  const ColorsTableType& getPointColors() const { return *rgbColors(); }
578  ecvColor::Rgb& getPointColorPtr(size_t pointIndex);
579  Eigen::Vector3d getEigenColor(size_t index) const;
580  std::vector<Eigen::Vector3d> getEigenColors() const;
581  void setEigenColors(const std::vector<Eigen::Vector3d>& colors);
582 
584  unsigned pointIndex) const override;
585  const CCVector3& getPointNormal(unsigned pointIndex) const override;
586  CCVector3& getPointNormalPtr(size_t pointIndex) const;
587  std::vector<CCVector3> getPointNormals() const;
588  std::vector<CCVector3*> getPointNormalsPtr() const;
589  void setPointNormals(const std::vector<CCVector3>& normals);
590  Eigen::Vector3d getEigenNormal(size_t index) const;
591  std::vector<Eigen::Vector3d> getEigenNormals() const;
592  void setEigenNormals(const std::vector<Eigen::Vector3d>& normals);
593 
595  bool inside = true) override;
597 
598  virtual void applyRigidTransformation(const ccGLMatrix& trans) override;
599  virtual void scale(PointCoordinateType fx,
602  CCVector3 center = CCVector3(0, 0, 0)) override;
603  inline void refreshBB() override { invalidateBoundingBox(); }
607  bool removeSelectedPoints = false,
608  VisibilityTableType* visTable = nullptr,
609  std::vector<int>* newIndexesOfRemainingPoints = nullptr,
610  bool silent = false,
611  cloudViewer::ReferenceCloud* selection = nullptr) override;
612  bool removeVisiblePoints(VisibilityTableType* visTable = nullptr,
613  std::vector<int>* newIndexes = nullptr) override;
616 
618  inline void enableVisibilityCheck(bool state) {
619  m_visibilityCheckEnabled = state;
620  }
621 
623  bool hasSensor() const;
624 
626 
629  QSharedPointer<cloudViewer::ReferenceCloud> computeCPSet(
630  ccGenericPointCloud& otherCloud,
631  cloudViewer::GenericProgressCallback* progressCb = nullptr,
632  unsigned char octreeLevel = 0);
633 
636  ccGenericPointCloud* cloud,
637  cloudViewer::GenericProgressCallback* progressCb = nullptr,
638  unsigned char octreeLevel = 0);
639 
641 
643  void setPointColor(size_t pointIndex, const ecvColor::Rgb& col);
644  void setPointColor(size_t pointIndex, const ecvColor::Rgba& col);
645  void setPointColor(size_t pointIndex, const Eigen::Vector3d& col);
646  void setEigenColor(size_t index, const Eigen::Vector3d& color);
647 
649 
651  void setPointNormalIndex(size_t pointIndex, CompressedNormType norm);
652 
654 
657  void setPointNormal(size_t pointIndex, const CCVector3& N);
658  void setEigenNormal(size_t index, const Eigen::Vector3d& normal);
659 
661 
664 
666 
668  void addNorm(const CCVector3& N);
669  void addEigenNorm(const Eigen::Vector3d& N);
670  void addEigenNorms(const std::vector<Eigen::Vector3d>& normals);
671 
672  void addNorms(const std::vector<CCVector3>& Ns);
673  void addNorms(const std::vector<CompressedNormType>& idxes);
674  std::vector<CompressedNormType> getNorms() const;
675  void getNorms(std::vector<CompressedNormType>& idxes) const;
676 
678 
682  void addNormAtIndex(const PointCoordinateType* N, unsigned index);
683 
686 
688 
692 
694 
699  ccScalarField* dipDirSF);
700 
702 
704  void addRGBColor(const ecvColor::Rgb& C);
705  void addRGBColors(const std::vector<ecvColor::Rgb>& colors);
706  void addEigenColor(const Eigen::Vector3d& color);
707  void addEigenColors(const std::vector<Eigen::Vector3d>& colors);
708 
710 
715  addRGBColor(ecvColor::Rgb(r, g, b));
716  }
717 
719 
722  inline void addGreyColor(ColorCompType g) {
723  addRGBColor(ecvColor::Rgb(g, g, g));
724  }
725 
727 
730 
732 
739  bool colorize(float r, float g, float b);
740 
742 
748  bool setRGBColorByHeight(unsigned char heightDim,
749  ccColorScale::Shared colorScale);
750 
752 
758  bool setRGBColorByBanding(unsigned char dim, double freq);
759 
762 
764  bool convertCurrentScalarFieldToColors(bool mixWithExistingColor = false);
765 
767 
769  bool setRGBColorWithCurrentScalarField(bool mixWithExistingColor = false);
770 
772 
779  return setRGBColor(ecvColor::Rgb(r, g, b));
780  }
781 
783 
787  bool setRGBColor(const ecvColor::Rgb& col);
788 
790  enum RGB_FILTER_TYPES { NONE, BILATERAL, GAUSSIAN, MEAN, MEDIAN };
791 
794  bool applyToSFduringRGB = false;
795  RGB_FILTER_TYPES filterType = RGB_FILTER_TYPES::NONE;
796  unsigned char burntOutColorThreshold = 0;
797  bool commandLine = false;
798  double sigmaSF = -1;
799  double spatialSigma = -1;
800  bool blendGrayscale = false;
801  unsigned char blendGrayscaleThreshold = 0;
802  double blendGrayscalePercent = 0.5;
803  };
804 
806 
824  PointCoordinateType sigma,
825  PointCoordinateType sigmaSF,
826  RgbFilterOptions filterParams,
827  cloudViewer::GenericProgressCallback* progressCb = nullptr);
828 
831 
833 
839  ScalarType maxVal,
840  bool outside = false);
841 
843 
848  ccPointCloud* filterPointsByScalarValue(std::vector<ScalarType> values,
849  bool outside = false);
850 
852 
856  void hidePointsByScalarValue(ScalarType minVal, ScalarType maxVal);
857 
859 
862  void hidePointsByScalarValue(std::vector<ScalarType> values);
863 
864  enum UnrollMode {
865  CYLINDER = 0,
866  CONE = 1,
867  STRAIGHTENED_CONE = 2,
868  STRAIGHTENED_CONE2 = 3
869  };
870 
874  unsigned char
876  };
879  };
882  double coneAngle_deg;
883  };
884 
886 
896  UnrollMode mode,
898  bool exportDeviationSF = false,
899  double startAngle_deg = 0.0,
900  double stopAngle_deg = 360.0,
901  cloudViewer::GenericProgressCallback* progressCb = nullptr) const;
902 
905 
907 
912 
914  ColorsTableType* rgbColors() const { return m_rgbColors; }
915 
917  NormsIndexesTableType* normals() const { return m_normals; }
918 
920 
928  unsigned char orthoDim,
929  bool inside = true);
930 
932 
939  unsigned pointCountBefore,
940  bool ignoreChildren = false);
941 
945  bool useCustomIntensityRange = false,
946  double minI = 0.0,
947  double maxI = 1.0);
948 
950  bool exportCoordToSF(bool exportDims[3]);
951 
953  bool setCoordFromSF(bool importDims[3],
955  PointCoordinateType defaultValueForNaN);
956 
958  bool exportNormalToSF(bool exportDims[3]);
959 
960 public: // for python interface
961  inline virtual bool IsEmpty() const override { return !hasPoints(); }
962 
963  inline virtual Eigen::Vector3d GetMinBound() const override {
964  return ComputeMinBound(CCVector3::fromArrayContainer(m_points));
965  }
966 
967  inline virtual Eigen::Vector3d GetMaxBound() const override {
968  return ComputeMaxBound(CCVector3::fromArrayContainer(m_points));
969  }
970  inline virtual Eigen::Vector3d GetCenter() const override {
971  return ComputeCenter(CCVector3::fromArrayContainer(m_points));
972  }
973 
974  virtual ccBBox GetAxisAlignedBoundingBox() const override;
975  virtual ecvOrientedBBox GetOrientedBoundingBox() const override;
976  virtual ccPointCloud& Transform(const Eigen::Matrix4d& trans) override;
977  virtual ccPointCloud& Translate(const Eigen::Vector3d& translation,
978  bool relative = true) override;
979  inline ccPointCloud& Translate(const CCVector3& T) {
980  return Translate(CCVector3d::fromArray(T), true);
981  }
982  virtual ccPointCloud& Scale(const double s,
983  const Eigen::Vector3d& center) override;
984  virtual ccPointCloud& Rotate(const Eigen::Matrix3d& R,
985  const Eigen::Vector3d& center) override;
986 
988  bool HasCovariances() const {
989  return !m_points.empty() && covariances_.size() == m_points.size();
990  }
991 
994 
1002  std::shared_ptr<ccPointCloud> SelectByIndex(
1003  const std::vector<size_t>& indices, bool invert = false) const;
1004 
1012  ccPointCloud& RemoveNonFinitePoints(bool remove_nan = true,
1013  bool remove_infinite = true);
1014 
1023  std::shared_ptr<ccPointCloud> VoxelDownSample(double voxel_size);
1024 
1034  std::tuple<std::shared_ptr<ccPointCloud>,
1035  Eigen::MatrixXi,
1036  std::vector<std::vector<int>>>
1037  VoxelDownSampleAndTrace(double voxel_size,
1038  const Eigen::Vector3d& min_bound,
1039  const Eigen::Vector3d& max_bound,
1040  bool approximate_class = false) const;
1041 
1050  std::shared_ptr<ccPointCloud> UniformDownSample(
1051  size_t every_k_points) const;
1052 
1061  std::shared_ptr<ccPointCloud> RandomDownSample(double sampling_ratio) const;
1062 
1071  std::shared_ptr<ccPointCloud> FarthestPointDownSample(
1072  const size_t num_samples, const size_t start_index = 0) const;
1073 
1080  std::shared_ptr<ccPointCloud> Crop(const ccBBox& bbox) const;
1081 
1088  std::shared_ptr<ccPointCloud> Crop(const ecvOrientedBBox& bbox) const;
1089 
1095  std::tuple<std::shared_ptr<ccPointCloud>, std::vector<size_t>>
1096  RemoveRadiusOutliers(size_t nb_points, double search_radius) const;
1097 
1103  std::tuple<std::shared_ptr<ccPointCloud>, std::vector<size_t>>
1104  RemoveStatisticalOutliers(size_t nb_neighbors, double std_ratio) const;
1105 
1116  const cloudViewer::geometry::KDTreeSearchParam& search_param =
1118  bool fast_normal_computation = true);
1119 
1125  const Eigen::Vector3d& orientation_reference =
1126  Eigen::Vector3d(0.0, 0.0, 1.0));
1127 
1133  const Eigen::Vector3d& camera_location = Eigen::Vector3d::Zero());
1134 
1142 
1150  std::vector<double> ComputePointCloudDistance(const ccPointCloud& target);
1151 
1159  static std::vector<Eigen::Matrix3d> EstimatePerPointCovariances(
1160  const ccPointCloud& input,
1161  const cloudViewer::geometry::KDTreeSearchParam& search_param =
1163 
1171  const cloudViewer::geometry::KDTreeSearchParam& search_param =
1173 
1178  std::vector<double> ComputeMahalanobisDistance() const;
1179 
1182  std::vector<double> ComputeNearestNeighborDistance() const;
1183 
1184  double ComputeResolution() const;
1185 
1187  std::tuple<std::shared_ptr<ccMesh>, std::vector<size_t>> ComputeConvexHull()
1188  const;
1189 
1199  std::tuple<std::shared_ptr<ccMesh>, std::vector<size_t>> HiddenPointRemoval(
1200  const Eigen::Vector3d& camera_location, const double radius) const;
1201 
1213  std::vector<int> ClusterDBSCAN(double eps,
1214  size_t min_points,
1215  bool print_progress = false) const;
1216 
1217 #ifdef CV_RANSAC_SUPPORT
1230  cloudViewer::geometry::RansacResults ExecuteRANSAC(
1231  const cloudViewer::geometry::RansacParams& params =
1232  cloudViewer::geometry::RansacParams(),
1233  bool print_progress = false);
1234 #endif
1235 
1245  std::tuple<Eigen::Vector4d, std::vector<size_t>> SegmentPlane(
1246  const double distance_threshold = 0.01,
1247  const int ransac_n = 3,
1248  const int num_iterations = 100) const;
1249 
1269  static std::shared_ptr<ccPointCloud> CreateFromDepthImage(
1270  const cloudViewer::geometry::Image& depth,
1272  const Eigen::Matrix4d& extrinsic = Eigen::Matrix4d::Identity(),
1273  double depth_scale = 1000.0,
1274  double depth_trunc = 1000.0,
1275  int stride = 1,
1276  bool project_valid_depth_only = true);
1277 
1294  static std::shared_ptr<ccPointCloud> CreateFromRGBDImage(
1297  const Eigen::Matrix4d& extrinsic = Eigen::Matrix4d::Identity(),
1298  bool project_valid_depth_only = true);
1299 
1306  std::shared_ptr<ccPointCloud> CreateFromVoxelGrid(
1307  const cloudViewer::geometry::VoxelGrid& voxel_grid);
1308 
1312  ccPointCloud& PaintUniformColor(const Eigen::Vector3d& color);
1313 
1314 public:
1316  std::vector<Eigen::Matrix3d> covariances_;
1317 
1318 protected:
1319  // inherited from ccHObject
1321  void applyGLTransformation(const ccGLMatrix& trans) override;
1322  bool toFile_MeOnly(QFile& out, short dataVersion) const override;
1323  short minimumFileVersion_MeOnly() const override;
1324  bool fromFile_MeOnly(QFile& in,
1325  short dataVersion,
1326  int flags,
1327  LoadedIDMap& oldToNewIDMap) override;
1328  void notifyGeometryUpdate() override;
1329 
1330  // inherited from ccPointCloud
1333  void swapPoints(unsigned firstIndex, unsigned secondIndex) override;
1334 
1335  virtual void removePoints(size_t index) override;
1336 
1339 
1342 
1346 
1351 
1353  std::vector<Grid::Shared> m_grids;
1354 
1356 
1359 
1360 protected: // VBO
1362  void releaseVBOs();
1363 
1364  class VBO : public QGLBuffer {
1365  public:
1368 
1370 
1372  int init(int count,
1373  bool withColors,
1374  bool withNormals,
1375  bool* reallocated = nullptr);
1376 
1378  : QGLBuffer(QGLBuffer::VertexBuffer), rgbShift(0), normalShift(0) {}
1379  };
1380 
1382  struct vboSet {
1384  enum STATES { NEW, INITIALIZED, FAILED };
1385 
1388  UPDATE_POINTS = 1,
1389  UPDATE_COLORS = 2,
1390  UPDATE_NORMALS = 4,
1391  UPDATE_ALL = UPDATE_POINTS | UPDATE_COLORS | UPDATE_NORMALS
1392  };
1393 
1395  : hasColors(false),
1396  colorIsSF(false),
1397  sourceSF(nullptr),
1398  hasNormals(false),
1399  totalMemSizeBytes(0),
1400  updateFlags(0),
1401  state(NEW) {}
1402 
1403  std::vector<VBO*> vbos;
1410 
1413  };
1414 
1417 
1418 public: // Level of Detail (LOD)
1420 
1422  bool initLOD();
1423 
1425  void clearLOD();
1426 
1427 protected: // Level of Detail (LOD)
1430 
1431 protected: // waveform (e.g. from airborne scanners)
1434 
1436  std::vector<ccWaveform> m_fwfWaveforms;
1437 
1440 };
CV_LOCAL_MODEL_TYPES
Definition: CVConst.h:121
Vector3Tpl< PointCoordinateType > CCVector3
Default 3D Vector.
Definition: CVGeom.h:798
float PointCoordinateType
Type of the coordinates of a (N-D) point.
Definition: CVTypes.h:16
int64_t CV_CLASS_ENUM
Type of object type flags (64 bits)
Definition: CVTypes.h:97
#define CV_DB_LIB_API
Definition: CV_db.h:15
std::shared_ptr< core::Tensor > image
double normal[3]
int size
std::string name
int count
int points
math::float4 color
cmdLineReadable * params[]
size_t stride
Array of RGB colors for each point.
Array of compressed 3D normals (single index)
static Vector3Tpl fromArray(const int a[3])
Constructor from an int array.
Definition: CVGeom.h:268
static std::vector< Eigen::Matrix< double, 3, 1 > > fromArrayContainer(const std::vector< Vector3Tpl< PointCoordinateType >> &container)
Definition: CVGeom.h:301
Bounding box structure.
Definition: ecvBBox.h:25
QSharedPointer< ccColorScale > Shared
Shared pointer type.
Definition: ecvColorScale.h:74
Float version of ccGLMatrixTpl.
Definition: ecvGLMatrix.h:19
Double version of ccGLMatrixTpl.
Definition: ecvGLMatrix.h:56
A 3D cloud interface with associated features (color, normals, octree, etc.)
std::vector< unsigned char > VisibilityTableType
Array of "visibility" information for each point.
Generic primitive interface.
Triangular mesh.
Definition: ecvMesh.h:35
Orientation
'Default' orientations
L.O.D. (Level of Detail) structure.
int init(int count, bool withColors, bool withNormals, bool *reallocated=nullptr)
Inits the VBO.
A 3D cloud and its associated features (color, normals, scalar fields, etc.)
std::tuple< std::shared_ptr< ccPointCloud >, Eigen::MatrixXi, std::vector< std::vector< int > > > VoxelDownSampleAndTrace(double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound, bool approximate_class=false) const
Function to downsample using geometry.ccPointCloud.VoxelDownSample.
void enableVisibilityCheck(bool state)
bool applyFilterToRGB(PointCoordinateType sigma, PointCoordinateType sigmaSF, RgbFilterOptions filterParams, cloudViewer::GenericProgressCallback *progressCb=nullptr)
Applies a spatial Gaussian filter on RGB colors.
bool normalsAvailable() const override
Returns whether normals are available.
void drawMeOnly(CC_DRAW_CONTEXT &context) override
Draws the entity only (not its children)
std::shared_ptr< ccPointCloud > Crop(const ccBBox &bbox) const
Function to crop ccPointCloud into output ccPointCloud.
void addEigenNorm(const Eigen::Vector3d &N)
void setCurrentDisplayedScalarField(int index)
Sets the currently displayed scalar field.
const Grid::Shared & grid(size_t gridIndex) const
Returns an associated grid (const verson)
static std::shared_ptr< ccPointCloud > CreateFromRGBDImage(const cloudViewer::geometry::RGBDImage &image, const cloudViewer::camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), bool project_valid_depth_only=true)
Factory function to create a pointcloud from an RGB-D image and a camera model.
void addRGBColors(const std::vector< ecvColor::Rgb > &colors)
void setEigenColor(size_t index, const Eigen::Vector3d &color)
virtual ccPointCloud & Transform(const Eigen::Matrix4d &trans) override
Apply transformation (4x4 matrix) to the geometry coordinates.
ccScalarField * m_currentDisplayedScalarField
Currently displayed scalar field.
void addColorRampInfo(CC_DRAW_CONTEXT &context)
Adds associated SF color ramp info to current GL context.
std::vector< ccWaveform > m_fwfWaveforms
Per-point waveform accessors.
bool setRGBColor(const ecvColor::Rgb &col)
Set a unique color for the whole cloud.
bool sfColorScaleShown() const
Returns whether color scale should be displayed or not.
vboSet m_vboManager
Set of VBOs attached to this cloud.
bool setRGBColorByBanding(unsigned char dim, double freq)
Assigns color to points by 'banding'.
bool hasSensor() const
Returns whether the mesh as an associated sensor or not.
ccPointCloud & NormalizeNormals()
Normalize point normals to length 1.`.
std::tuple< std::shared_ptr< ccMesh >, std::vector< size_t > > HiddenPointRemoval(const Eigen::Vector3d &camera_location, const double radius) const
This is an implementation of the Hidden Point Removal operator described in Katz et....
bool convertNormalToRGB()
Converts normals to RGB colors.
bool m_sfColorScaleDisplayed
ColorsTableType * rgbColors() const
Returns pointer on RGB colors table.
QMap< uint8_t, WaveformDescriptor > FWFDescriptorSet
Waveform descriptors set.
std::vector< Eigen::Vector3d > getEigenColors() const
bool EstimateNormals(const cloudViewer::geometry::KDTreeSearchParam &search_param=cloudViewer::geometry::KDTreeSearchParamKNN(), bool fast_normal_computation=true)
Function to compute the normals of a point cloud.
void clearFWFData()
Clears all associated FWF data.
static ccPointCloud * From(cloudViewer::GenericCloud *cloud, const ccGenericPointCloud *sourceCloud=nullptr)
Creates a new point cloud object from a GenericCloud.
ScalarType getPointDisplayedDistance(unsigned pointIndex) const override
Returns scalar value associated to a given point.
ccPointCloud & operator=(const ccPointCloud &cloud)
Fuses another 3D entity with this one.
const FWFDescriptorSet & fwfDescriptors() const
Gives access to the FWF descriptors (const version)
virtual void applyRigidTransformation(const ccGLMatrix &trans) override
Applies a rigid transformation (rotation + translation)
bool resizeTheNormsTable()
Resizes the compressed normals array.
void addNorms(const std::vector< CCVector3 > &Ns)
void unallocateColors()
Erases the cloud colors.
NormsIndexesTableType * m_normals
Normals (compressed)
static std::shared_ptr< ccPointCloud > CreateFromDepthImage(const cloudViewer::geometry::Image &depth, const cloudViewer::camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), double depth_scale=1000.0, double depth_trunc=1000.0, int stride=1, bool project_valid_depth_only=true)
Factory function to create a pointcloud from a depth image and a camera model.
void deleteAllScalarFields() override
Deletes all scalar fields associated to this cloud.
void refreshBB() override
Forces bounding-box update.
bool initLOD()
Intializes the LOD structure.
const CompressedNormType & getPointNormalIndex(unsigned pointIndex) const override
Returns compressed normal corresponding to a given point.
void addNorms(const std::vector< CompressedNormType > &idxes)
void addEigenColor(const Eigen::Vector3d &color)
void getDrawingParameters(glDrawParams &params) const override
Returns main OpenGL parameters for this entity.
void setEigenNormal(size_t index, const Eigen::Vector3d &normal)
void setPointNormalIndex(size_t pointIndex, CompressedNormType norm)
Sets a particular point compressed normal.
void addEigenNorms(const std::vector< Eigen::Vector3d > &normals)
bool orientNormalsTowardViewPoint(CCVector3 &VP, ecvProgressDialog *pDlg=nullptr)
Normals are forced to point to O.
bool HasCovariances() const
Returns 'true' if the point cloud contains per-point covariance matrix.
bool OrientNormalsTowardsCameraLocation(const Eigen::Vector3d &camera_location=Eigen::Vector3d::Zero())
Function to orient the normals of a point cloud.
void setEigenColors(const std::vector< Eigen::Vector3d > &colors)
static ccPointCloud * From(const ccPointCloud *sourceCloud, const std::vector< size_t > &indices, bool invert=false)
Function to select points from input ccPointCloud into output ccPointCloud.
cloudViewer::ReferenceCloud * crop(const ecvOrientedBBox &bbox) override
std::vector< double > ComputeNearestNeighborDistance() const
void setNormsTable(NormsIndexesTableType *norms)
Sets the (compressed) normals table.
std::tuple< Eigen::Vector4d, std::vector< size_t > > SegmentPlane(const double distance_threshold=0.01, const int ransac_n=3, const int num_iterations=100) const
Segment ccPointCloud plane using the RANSAC algorithm.
std::shared_ptr< ccPointCloud > CreateFromVoxelGrid(const cloudViewer::geometry::VoxelGrid &voxel_grid)
Function to create a PointCloud from a VoxelGrid.
ccPointCloudLOD * m_lod
L.O.D. structure.
Eigen::Vector3d getEigenNormal(size_t index) const
std::vector< double > ComputeMahalanobisDistance() const
Function to compute the Mahalanobis distance for points in an input point cloud.
virtual ccPointCloud & Rotate(const Eigen::Matrix3d &R, const Eigen::Vector3d &center) override
Apply rotation to the geometry coordinates and normals. Given a rotation matrix , and center ,...
FWFDescriptorSet & fwfDescriptors()
Gives access to the FWF descriptors.
ccPointCloud & Translate(const CCVector3 &T)
bool convertRGBToGreyScale()
Converts RGB to grey scale colors.
bool fromFile_MeOnly(QFile &in, short dataVersion, int flags, LoadedIDMap &oldToNewIDMap) override
Loads own object data.
void addNorm(const CCVector3 &N)
Pushes a normal vector on stack (shortcut)
NormsIndexesTableType * normals() const
Returns pointer on compressed normals indexes table.
virtual void scale(PointCoordinateType fx, PointCoordinateType fy, PointCoordinateType fz, CCVector3 center=CCVector3(0, 0, 0)) override
Multiplies all coordinates by constant factors (one per dimension)
double ComputeResolution() const
short minimumFileVersion_MeOnly() const override
std::vector< ccWaveform > & waveforms()
Gives access to the associated FWF data.
bool computeNormalsWithGrids(double minTriangleAngle_deg=1.0, ecvProgressDialog *pDlg=nullptr)
Compute the normals with the associated grid structure(s)
bool reserveTheFWFTable()
Reserves the FWF table.
QSharedPointer< const FWFDataContainer > SharedFWFDataContainer
const CCVector3 * getNormal(unsigned pointIndex) const override
If per-point normals are available, returns the one at a specific index.
std::shared_ptr< ccPointCloud > FarthestPointDownSample(const size_t num_samples, const size_t start_index=0) const
Function to downsample input pointcloud into output pointcloud with a set of points has farthest dist...
ccWaveformProxy waveformProxy(unsigned index) const
Returns a proxy on a given waveform.
int addScalarField(const char *uniqueName) override
Creates a new scalar field and registers it.
bool interpolateColorsFrom(ccGenericPointCloud *cloud, cloudViewer::GenericProgressCallback *progressCb=nullptr, unsigned char octreeLevel=0)
Interpolate colors from another cloud (nearest neighbor only)
bool hasNormals() const override
Returns whether normals are enabled or not.
bool enhanceRGBWithIntensitySF(int sfIdx, bool useCustomIntensityRange=false, double minI=0.0, double maxI=1.0)
void applyGLTransformation(const ccGLMatrix &trans) override
Applies a GL transformation to the entity.
virtual bool IsEmpty() const override
bool resizeTheRGBTable(bool fillWithWhite=false)
Resizes the RGB colors array.
void normalsHaveChanged()
Notify a modification of normals display parameters or contents.
ccPointCloud * unroll(UnrollMode mode, UnrollBaseParams *params, bool exportDeviationSF=false, double startAngle_deg=0.0, double stopAngle_deg=360.0, cloudViewer::GenericProgressCallback *progressCb=nullptr) const
Unrolls the cloud and its normals on a cylinder or a cone.
void notifyGeometryUpdate() override
void showSFColorsScale(bool state)
Sets whether color scale should be displayed or not.
unsigned char testVisibility(const CCVector3 &P) const override
void unalloactePoints()
Erases the cloud points.
int m_currentDisplayedScalarFieldIndex
Currently displayed scalar field index.
void addGreyColor(ColorCompType g)
Pushes a grey color on stack (shortcut)
const ecvColor::Rgb * getScalarValueColor(ScalarType d) const override
Returns color corresponding to a given scalar value.
void OrientNormalsConsistentTangentPlane(size_t k)
Function to consistently orient estimated normals based on consistent tangent planes as described in ...
void invalidateBoundingBox() override
Invalidates bounding box.
bool computeNormalsWithOctree(CV_LOCAL_MODEL_TYPES model, ccNormalVectors::Orientation preferredOrientation, PointCoordinateType defaultRadius, ecvProgressDialog *pDlg=nullptr)
Compute the normals by approximating the local surface around each point.
bool orientNormalsWithFM(unsigned char level, ecvProgressDialog *pDlg=nullptr)
Orient normals with Fast Marching.
bool reserve(unsigned numberOfPoints) override
Reserves memory for all the active features.
std::tuple< std::shared_ptr< ccPointCloud >, std::vector< size_t > > RemoveStatisticalOutliers(size_t nb_neighbors, double std_ratio) const
Function to remove points that are further away from their nb_neighbor neighbors in average.
bool resizeTheFWFTable()
Resizes the FWF table.
bool removeVisiblePoints(VisibilityTableType *visTable=nullptr, std::vector< int > *newIndexes=nullptr) override
Removes all the 'visible' points (as defined by the visibility array)
bool hasFWF() const
Returns whether the cloud has associated Full WaveForm data.
bool OrientNormalsToAlignWithDirection(const Eigen::Vector3d &orientation_reference=Eigen::Vector3d(0.0, 0.0, 1.0))
Function to orient the normals of a point cloud.
bool exportCoordToSF(bool exportDims[3])
Exports the specified coordinate dimension(s) to scalar field(s)
const ColorsTableType & getPointColors() const
std::shared_ptr< ccPointCloud > Crop(const ecvOrientedBBox &bbox) const
Function to crop ccPointCloud into output ccPointCloud.
ccGenericPointCloud * createNewCloudFromVisibilitySelection(bool removeSelectedPoints=false, VisibilityTableType *visTable=nullptr, std::vector< int > *newIndexesOfRemainingPoints=nullptr, bool silent=false, cloudViewer::ReferenceCloud *selection=nullptr) override
std::vector< int > ClusterDBSCAN(double eps, size_t min_points, bool print_progress=false) const
Cluster ccPointCloud using the DBSCAN algorithm Ester et al., "A Density-Based Algorithm for Discover...
ccPointCloud(QString name=QString())
Default constructor.
void pointsHaveChanged()
Notify a modification of points display parameters or contents.
bool computeFWFAmplitude(double &minVal, double &maxVal, ecvProgressDialog *pDlg=nullptr) const
Computes the maximum amplitude of all associated waveforms.
void releaseVBOs()
Release VBOs.
bool orientNormalsWithMST(unsigned kNN=6, ecvProgressDialog *pDlg=nullptr)
Orient the normals with a Minimum Spanning Tree.
ccPointCloud & RemoveNonFinitePoints(bool remove_nan=true, bool remove_infinite=true)
Remove all points fromt he point cloud that have a nan entry, or infinite entries.
ccMesh * triangulateGrid(const Grid &grid, double minTriangleAngle_deg=0.0) const
Meshes a scan grid.
bool colorize(float r, float g, float b)
Multiplies all color components of all points by coefficients.
std::shared_ptr< ccPointCloud > RandomDownSample(double sampling_ratio) const
Function to downsample input pointcloud into output pointcloud randomly.
const ccPointCloud & operator+=(const ccPointCloud &cloud)
void setEigenNormals(const std::vector< Eigen::Vector3d > &normals)
virtual Eigen::Vector3d GetMinBound() const override
Returns min bounds for geometry coordinates.
void hidePointsByScalarValue(ScalarType minVal, ScalarType maxVal)
Hides points whose scalar values falls into an interval.
bool hasDisplayedScalarField() const override
Returns whether an active scalar field is available or not.
void getNorms(std::vector< CompressedNormType > &idxes) const
bool reserveTheNormsTable()
Reserves memory to store the compressed normals.
bool convertNormalToDipDirSFs(ccScalarField *dipSF, ccScalarField *dipDirSF)
Converts normals to two scalar fields: 'dip' and 'dip direction'.
ccGenericPointCloud * clone(ccGenericPointCloud *destCloud=nullptr, bool ignoreChildren=false) override
Clones this entity.
ecvColor::Rgb & getPointColorPtr(size_t pointIndex)
bool exportNormalToSF(bool exportDims[3])
Exports the specified normal dimension(s) to scalar field(s)
RGB_FILTER_TYPES
RGB filter types.
cloudViewer::ReferenceCloud * crop(const ccBBox &box, bool inside=true) override
Crops the cloud inside (or outside) a bounding box.
bool setCoordFromSF(bool importDims[3], cloudViewer::ScalarField *sf, PointCoordinateType defaultValueForNaN)
Sets coordinate(s) from a scalar field.
bool reserveTheRGBTable()
Reserves memory to store the RGB colors.
virtual ccBBox GetAxisAlignedBoundingBox() const override
Returns an axis-aligned bounding box of the geometry.
bool compressFWFData()
Compresses the associated FWF data container.
bool m_visibilityCheckEnabled
Whether visibility check is available or not (during comparison)
int getCurrentDisplayedScalarFieldIndex() const
Returns the currently displayed scalar field index (or -1 if none)
std::tuple< std::shared_ptr< ccPointCloud >, std::vector< size_t > > RemoveRadiusOutliers(size_t nb_points, double search_radius) const
Function to remove points that have less than nb_points in a sphere of a given radius.
void clear() override
Clears the entity from all its points and features.
ccPointCloud * cloneThis(ccPointCloud *destCloud=nullptr, bool ignoreChildren=false)
Clones this entity.
virtual Eigen::Vector3d GetCenter() const override
Returns the center of the geometry coordinates.
virtual void removePoints(size_t index) override
const ccPointCloud & operator+=(ccPointCloud *)
ccPointCloud operator+(const ccPointCloud &cloud) const
void addNormAtIndex(const PointCoordinateType *N, unsigned index)
Adds a normal vector to the one at a specific index.
void unallocateNorms()
Erases the cloud normals.
CCVector3 & getPointNormalPtr(size_t pointIndex) const
void swapPoints(unsigned firstIndex, unsigned secondIndex) override
std::vector< CCVector3 * > getPointNormalsPtr() const
virtual ccPointCloud & Translate(const Eigen::Vector3d &translation, bool relative=true) override
Apply translation to the geometry coordinates.
bool toFile_MeOnly(QFile &out, short dataVersion) const override
Save own object data.
static std::vector< Eigen::Matrix3d > EstimatePerPointCovariances(const ccPointCloud &input, const cloudViewer::geometry::KDTreeSearchParam &search_param=cloudViewer::geometry::KDTreeSearchParamKNN())
Static function to compute the covariance matrix for each point of a point cloud. Doesn't change the ...
bool hasColors() const override
Returns whether colors are enabled or not.
std::vector< uint8_t > FWFDataContainer
Waveform data container.
unsigned getUniqueIDForDisplay() const override
Returns object unqiue ID used for display.
static ccPointCloud * From(const cloudViewer::GenericIndexedCloud *cloud, const ccGenericPointCloud *sourceCloud=nullptr)
Creates a new point cloud object from a GenericIndexedCloud.
bool resize(unsigned numberOfPoints) override
Resizes all the active features arrays.
std::vector< Grid::Shared > m_grids
Associated grid structure.
bool setRGBColorByHeight(unsigned char heightDim, ccColorScale::Shared colorScale)
Assigns color to points proportionnaly to their 'height'.
void setPointNormals(const std::vector< CCVector3 > &normals)
void deleteScalarField(int index) override
Deletes a specific scalar field.
void setPointColor(size_t pointIndex, const ecvColor::Rgba &col)
void setPointColor(size_t pointIndex, const ecvColor::Rgb &col)
Sets a particular point color.
bool addGrid(Grid::Shared grid)
Adds an associated grid.
void setPointColor(size_t pointIndex, const Eigen::Vector3d &col)
void setPointNormal(size_t pointIndex, const CCVector3 &N)
Sets a particular point normal (shortcut)
std::vector< CompressedNormType > getNorms() const
void removeGrids()
Remove all associated grids.
cloudViewer::ReferenceCloud * crop2D(const ccPolyline *poly, unsigned char orthoDim, bool inside=true)
Crops the cloud inside (or outside) a 2D polyline.
const SharedFWFDataContainer & fwfData() const
Gives access to the associated FWF data container (const version)
ccPointCloud * filterPointsByScalarValue(std::vector< ScalarType > values, bool outside=false)
Filters out points whose scalar values falls into an interval.
ccScalarField * getCurrentDisplayedScalarField() const
Returns the currently displayed scalar (or 0 if none)
SharedFWFDataContainer & fwfData()
Gives access to the associated FWF data container.
ColorsTableType * m_rgbColors
Colors.
std::shared_ptr< ccPointCloud > VoxelDownSample(double voxel_size)
Function to downsample input ccPointCloud into output ccPointCloud with a voxel.
SharedFWFDataContainer m_fwfData
Waveforms raw data storage.
Grid::Shared & grid(size_t gridIndex)
Returns an associated grid.
const ecvColor::Rgb & getPointColor(unsigned pointIndex) const override
Returns color corresponding to a given point.
std::vector< Eigen::Matrix3d > covariances_
Covariance Matrix for each point.
Eigen::Vector3d getEigenColor(size_t index) const
QSharedPointer< cloudViewer::ReferenceCloud > computeCPSet(ccGenericPointCloud &otherCloud, cloudViewer::GenericProgressCallback *progressCb=nullptr, unsigned char octreeLevel=0)
Computes the closest point of this cloud relatively to another cloud.
void addEigenColors(const std::vector< Eigen::Vector3d > &colors)
void shrinkToFit()
Removes unused capacity.
std::vector< double > ComputePointCloudDistance(const ccPointCloud &target)
Function to compute the point to point distances between point clouds.
FWFDescriptorSet m_fwfDescriptors
General waveform descriptors.
const CCVector3 & getPointNormal(unsigned pointIndex) const override
Returns normal corresponding to a given point.
ccPointCloud * filterPointsByScalarValue(ScalarType minVal, ScalarType maxVal, bool outside=false)
Filters out points whose scalar values falls into an interval.
void addRGBColor(const ecvColor::Rgb &C)
Pushes an RGB color on stack.
bool convertCurrentScalarFieldToColors(bool mixWithExistingColor=false)
virtual Eigen::Vector3d GetMaxBound() const override
Returns max bounds for geometry coordinates.
void colorsHaveChanged()
CCVector3 computeGravityCenter()
Returns the cloud gravity center.
bool setRGBColor(ColorCompType r, ColorCompType g, ColorCompType b)
Set a unique color for the whole cloud (shortcut)
void EstimateCovariances(const cloudViewer::geometry::KDTreeSearchParam &search_param=cloudViewer::geometry::KDTreeSearchParamKNN())
Function to compute the covariance matrix for each point of a point cloud.
ccPointCloud * partialClone(const cloudViewer::ReferenceCloud *selection, int *warnings=nullptr, bool withChildEntities=true) const
Creates a new point cloud object from a ReferenceCloud (selection)
bool hasScalarFields() const override
Returns whether one or more scalar fields are instantiated.
void addNormIndex(CompressedNormType index)
Pushes a compressed normal vector.
const ecvColor::Rgb * getPointScalarValueColor(unsigned pointIndex) const override
Returns color corresponding to a given point associated scalar value.
ccPointCloud & PaintUniformColor(const Eigen::Vector3d &color)
Assigns each vertex in the ccMesh the same color.
void hidePointsByScalarValue(std::vector< ScalarType > values)
Hides points whose scalar values falls into an interval.
std::tuple< std::shared_ptr< ccMesh >, std::vector< size_t > > ComputeConvexHull() const
Function that computes the convex hull of the point cloud using qhull.
void clearLOD()
Clears the LOD structure.
bool reserveThePointsTable(unsigned _numberOfPoints)
Reserves memory to store the points coordinates.
bool orientNormalsWithGrids(ecvProgressDialog *pDlg=nullptr)
Orient the normals with the associated grid structure(s)
bool setRGBColorWithCurrentScalarField(bool mixWithExistingColor=false)
Sets RGB colors with current scalar field (values & parameters)
const ccPointCloud & append(ccPointCloud *cloud, unsigned pointCountBefore, bool ignoreChildren=false)
Appends a cloud to this one.
const std::vector< ccWaveform > & waveforms() const
Gives access to the associated FWF data (const version)
void addRGBColor(ColorCompType r, ColorCompType g, ColorCompType b)
Pushes an RGB color on stack (shortcut)
std::shared_ptr< ccPointCloud > SelectByIndex(const std::vector< size_t > &indices, bool invert=false) const
Function to select points from input ccPointCloud into output ccPointCloud.
std::vector< Eigen::Vector3d > getEigenNormals() const
int addScalarField(ccScalarField *sf)
Adds an existing scalar field to this cloud.
CLONE_WARNINGS
Warnings for the partialClone method (bit flags)
std::shared_ptr< ccPointCloud > UniformDownSample(size_t every_k_points) const
Function to downsample input ccPointCloud into output ccPointCloud uniformly.
virtual ecvOrientedBBox GetOrientedBoundingBox() const override
std::vector< CCVector3 > getPointNormals() const
void invertNormals()
Inverts normals (if any)
size_t gridCount() const
Returns the number of associated grids.
virtual ccPointCloud & Scale(const double s, const Eigen::Vector3d &center) override
Apply scaling to the geometry coordinates. Given a scaling factor , and center , a given point is tr...
Colored polyline.
Definition: ecvPolyline.h:24
A scalar field associated to display-related parameters.
Serializable object interface.
QMultiMap< unsigned, unsigned > LoadedIDMap
Map of loaded unique IDs (old ID --> new ID)
Waveform proxy.
Definition: ecvWaveform.h:189
A generic 3D point cloud with index-based point access.
A very simple point cloud (no point duplication)
A simple scalar field (to be associated to a point cloud)
Definition: ScalarField.h:25
Contains the pinhole camera intrinsic parameters.
The Image class stores image with customizable width, height, num of channels and bytes per channel.
Definition: Image.h:33
KDTree search parameters for pure KNN search.
Base class for KDTree search parameters.
RGBDImage is for a pair of registered color and depth images,.
Definition: RGBDImage.h:27
VoxelGrid is a collection of voxels which are aligned in grid.
Definition: VoxelGrid.h:64
RGB color structure.
Definition: ecvColorTypes.h:49
RGBA color structure.
Graphical progress indicator (thread-safe)
double colors[3]
double normals[3]
unsigned int CompressedNormType
Compressed normals type.
Definition: ecvBasicTypes.h:16
unsigned char ColorCompType
Default color components type (R,G and B)
Definition: ecvColorTypes.h:29
const unsigned CC_MAX_NUMBER_OF_POINTS_PER_CLOUD
#define QGLBuffer
Definition: ecvPointCloud.h:27
ImGuiContext * context
Definition: Window.cpp:76
@ CONE
Definition: CVTypes.h:123
@ POINT_CLOUD
Definition: CVTypes.h:104
@ CYLINDER
Definition: CVTypes.h:126
Definition: Eigen.h:103
Generic file read and write utility for python interface.
Definition: Eigen.h:85
unsigned char octreeLevel
ccGenericPointCloud * sourceCloud
Display context.
Grid structure.
unsigned validCount
Number of valid indexes.
unsigned minValidIndex
Minimum valid index.
std::vector< ecvColor::Rgb > colors
Grid colors (size: w x h, or 0 = no color)
bool fromFile(QFile &in, short dataVersion, int flags, LoadedIDMap &oldToNewIDMap) override
Loads data from binary stream.
short minimumFileVersion() const override
Returns the minimum file version required to save this instance.
ccGLMatrixd sensorPosition
Sensor position (expressed relatively to the cloud points)
Grid()
Default constructor.
QImage toImage() const
Converts the grid to an RGB image (needs colors)
unsigned h
Grid height.
bool toFile(QFile &out, short dataVersion) const override
Saves data to binary stream.
unsigned maxValidIndex
Maximum valid index.
void setIndex(unsigned row, unsigned col, int index)
Sets an index at a given position inside the grid.
std::vector< int > indexes
Grid indexes (size: w x h)
void updateMinAndMaxValidIndexes()
Updates the min and max valid indexes.
void setColor(unsigned row, unsigned col, const ecvColor::Rgb &rgb)
Sets a color at a given position inside the grid.
Grid(const Grid &grid)=default
Copy constructor.
bool isSerializable() const override
Returns whether object is serializable of not.
bool init(unsigned rowCount, unsigned colCount, bool withRGB=false)
Inits the grid.
QSharedPointer< Grid > Shared
Shared type.
unsigned w
Grid width.
PointCoordinateType radius
unrolling cylinder radius (or cone base radius)
unsigned char axisDim
unrolling cylinder/cone axis (X=0, Y=1 or Z=2)
STATES state
Current state.
STATES
States of the VBO(s)
UPDATE_FLAGS
Update flags.
std::vector< VBO * > vbos
ccScalarField * sourceSF
Display parameters of a 3D entity.