12 #pragma warning(disable : 4250)
25 #if QT_VERSION >= QT_VERSION_CHECK(6, 0, 0)
26 #include <QOpenGLBuffer>
27 #define QGLBuffer QOpenGLBuffer
47 #ifdef CV_RANSAC_SUPPORT
51 enum RANSAC_PRIMITIVE_TYPES {
62 unsigned supportPoints;
64 float maxNormalDev_deg;
70 std::vector<RANSAC_PRIMITIVE_TYPES> primEnabled;
77 maxNormalDev_deg(25.0f),
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);
87 RansacParams(
float scale)
88 : epsilon(0.005f * scale),
89 bitmapEpsilon(0.01f * scale),
91 maxNormalDev_deg(25.0f),
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);
104 std::string getTypeName()
const;
105 unsigned getDrawingPrecision()
const;
106 bool setDrawingPrecision(
unsigned steps);
109 std::vector<size_t> indices;
110 std::shared_ptr<ccGenericPrimitive> primitive =
nullptr;
113 using RansacResults = std::vector<RansacResult>;
119 class PinholeCameraIntrinsic;
129 #if defined(CV_ENV_32)
161 const
std::
string&
name = "cloud");
204 const std::vector<size_t>& indices,
205 bool invert =
false);
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
227 int* warnings =
nullptr,
228 bool withChildEntities =
true)
const;
238 bool ignoreChildren =
false);
242 bool ignoreChildren =
false)
override;
277 m_vboManager.updateFlags |= vboSet::UPDATE_COLORS;
281 m_vboManager.updateFlags |= vboSet::UPDATE_NORMALS;
285 m_vboManager.updateFlags |= vboSet::UPDATE_POINTS;
294 bool reserve(
unsigned numberOfPoints)
override;
332 bool resize(
unsigned numberOfPoints)
override;
358 if (
size() < capacity()) resize(
size());
396 bool init(
unsigned rowCount,
unsigned colCount,
bool withRGB =
false);
399 void setIndex(
unsigned row,
unsigned col,
int index);
412 bool toFile(QFile& out,
short dataVersion)
const override;
446 return m_grids[gridIndex];
451 m_grids.push_back(grid);
452 }
catch (
const std::bad_alloc&) {
464 double minTriangleAngle_deg = 0.0)
const;
515 std::vector<ccWaveform>&
waveforms() {
return m_fwfWaveforms; }
517 const std::vector<ccWaveform>&
waveforms()
const {
return m_fwfWaveforms; }
573 unsigned pointIndex)
const override;
584 unsigned pointIndex)
const override;
595 bool inside =
true)
override;
603 inline void refreshBB()
override { invalidateBoundingBox(); }
607 bool removeSelectedPoints =
false,
609 std::vector<int>* newIndexesOfRemainingPoints =
nullptr,
613 std::vector<int>* newIndexes =
nullptr)
override;
619 m_visibilityCheckEnabled = state;
673 void addNorms(
const std::vector<CompressedNormType>& idxes);
675 void getNorms(std::vector<CompressedNormType>& idxes)
const;
794 bool applyToSFduringRGB =
false;
796 unsigned char burntOutColorThreshold = 0;
797 bool commandLine =
false;
799 double spatialSigma = -1;
800 bool blendGrayscale =
false;
801 unsigned char blendGrayscaleThreshold = 0;
802 double blendGrayscalePercent = 0.5;
840 bool outside =
false);
849 bool outside =
false);
867 STRAIGHTENED_CONE = 2,
868 STRAIGHTENED_CONE2 = 3
898 bool exportDeviationSF =
false,
899 double startAngle_deg = 0.0,
900 double stopAngle_deg = 360.0,
928 unsigned char orthoDim,
939 unsigned pointCountBefore,
940 bool ignoreChildren =
false);
945 bool useCustomIntensityRange =
false,
961 inline virtual bool IsEmpty()
const override {
return !hasPoints(); }
970 inline virtual Eigen::Vector3d
GetCenter()
const override {
978 bool relative =
true)
override;
983 const Eigen::Vector3d& center)
override;
985 const Eigen::Vector3d& center)
override;
989 return !m_points.empty() && covariances_.size() == m_points.size();
1003 const std::vector<size_t>& indices,
bool invert =
false)
const;
1013 bool remove_infinite =
true);
1034 std::tuple<std::shared_ptr<ccPointCloud>,
1036 std::vector<std::vector<int>>>
1038 const Eigen::Vector3d& min_bound,
1039 const Eigen::Vector3d& max_bound,
1040 bool approximate_class =
false)
const;
1051 size_t every_k_points)
const;
1072 const size_t num_samples,
const size_t start_index = 0)
const;
1095 std::tuple<std::shared_ptr<ccPointCloud>, std::vector<size_t>>
1103 std::tuple<std::shared_ptr<ccPointCloud>, std::vector<size_t>>
1118 bool fast_normal_computation =
true);
1125 const Eigen::Vector3d& orientation_reference =
1126 Eigen::Vector3d(0.0, 0.0, 1.0));
1133 const Eigen::Vector3d& camera_location = Eigen::Vector3d::Zero());
1200 const Eigen::Vector3d& camera_location,
const double radius)
const;
1215 bool print_progress =
false)
const;
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);
1246 const double distance_threshold = 0.01,
1247 const int ransac_n = 3,
1248 const int num_iterations = 100)
const;
1272 const Eigen::Matrix4d& extrinsic = Eigen::Matrix4d::Identity(),
1273 double depth_scale = 1000.0,
1274 double depth_trunc = 1000.0,
1276 bool project_valid_depth_only =
true);
1297 const Eigen::Matrix4d& extrinsic = Eigen::Matrix4d::Identity(),
1298 bool project_valid_depth_only =
true);
1333 void swapPoints(
unsigned firstIndex,
unsigned secondIndex)
override;
1375 bool* reallocated =
nullptr);
1391 UPDATE_ALL = UPDATE_POINTS | UPDATE_COLORS | UPDATE_NORMALS
1399 totalMemSizeBytes(0),
Vector3Tpl< PointCoordinateType > CCVector3
Default 3D Vector.
float PointCoordinateType
Type of the coordinates of a (N-D) point.
int64_t CV_CLASS_ENUM
Type of object type flags (64 bits)
std::shared_ptr< core::Tensor > image
cmdLineReadable * params[]
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.
static std::vector< Eigen::Matrix< double, 3, 1 > > fromArrayContainer(const std::vector< Vector3Tpl< PointCoordinateType >> &container)
QSharedPointer< ccColorScale > Shared
Shared pointer type.
Float version of ccGLMatrixTpl.
Double version of ccGLMatrixTpl.
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.
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 ¶ms) 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 ¢er) 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.
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 ¢er) override
Apply scaling to the geometry coordinates. Given a scaling factor , and center , a given point is tr...
A scalar field associated to display-related parameters.
Serializable object interface.
QMultiMap< unsigned, unsigned > LoadedIDMap
Map of loaded unique IDs (old ID --> new ID)
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)
Contains the pinhole camera intrinsic parameters.
The Image class stores image with customizable width, height, num of channels and bytes per channel.
KDTree search parameters for pure KNN search.
Base class for KDTree search parameters.
RGBDImage is for a pair of registered color and depth images,.
VoxelGrid is a collection of voxels which are aligned in grid.
Graphical progress indicator (thread-safe)
unsigned int CompressedNormType
Compressed normals type.
unsigned char ColorCompType
Default color components type (R,G and B)
const unsigned CC_MAX_NUMBER_OF_POINTS_PER_CLOUD
Generic file read and write utility for python interface.
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)
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.
PointCoordinateType radius
unrolling cylinder radius (or cone base radius)
unsigned char axisDim
unrolling cylinder/cone axis (X=0, Y=1 or Z=2)
double coneAngle_deg
Cone apex.
STATES state
Current state.
STATES
States of the VBO(s)
UPDATE_FLAGS
Update flags.
std::vector< VBO * > vbos
Display parameters of a 3D entity.