Open3D (C++ API)
|
#include <PointCloud.h>
Public Member Functions | |
PointCloud () | |
~PointCloud () override | |
PointCloud & | Clear () override |
bool | IsEmpty () const override |
Eigen::Vector3d | GetMinBound () const override |
Eigen::Vector3d | GetMaxBound () const override |
Eigen::Vector3d | GetCenter () const override |
AxisAlignedBoundingBox | GetAxisAlignedBoundingBox () const override |
OrientedBoundingBox | GetOrientedBoundingBox () const override |
PointCloud & | Transform (const Eigen::Matrix4d &transformation) override |
PointCloud & | Translate (const Eigen::Vector3d &translation, bool relative=true) override |
PointCloud & | Scale (const double scale, bool center=true) override |
PointCloud & | Rotate (const Eigen::Vector3d &rotation, bool center=true, RotationType type=RotationType::XYZ) override |
PointCloud & | operator+= (const PointCloud &cloud) |
PointCloud | operator+ (const PointCloud &cloud) const |
bool | HasPoints () const |
bool | HasNormals () const |
bool | HasColors () const |
PointCloud & | NormalizeNormals () |
PointCloud & | PaintUniformColor (const Eigen::Vector3d &color) |
Assigns each point in the PointCloud the same color. More... | |
PointCloud & | RemoveNoneFinitePoints (bool remove_nan=true, bool remove_infinite=true) |
std::shared_ptr< PointCloud > | SelectDownSample (const std::vector< size_t > &indices, bool invert=false) const |
std::shared_ptr< PointCloud > | VoxelDownSample (double voxel_size) const |
std::tuple< std::shared_ptr< PointCloud >, Eigen::MatrixXi > | VoxelDownSampleAndTrace (double voxel_size, const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound, bool approximate_class=false) const |
std::shared_ptr< PointCloud > | UniformDownSample (size_t every_k_points) const |
std::shared_ptr< PointCloud > | Crop (const Eigen::Vector3d &min_bound, const Eigen::Vector3d &max_bound) const |
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > | RemoveRadiusOutliers (size_t nb_points, double search_radius) const |
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > | RemoveStatisticalOutliers (size_t nb_neighbors, double std_ratio) const |
bool | EstimateNormals (const KDTreeSearchParam &search_param=KDTreeSearchParamKNN(), bool fast_normal_computation=true) |
bool | OrientNormalsToAlignWithDirection (const Eigen::Vector3d &orientation_reference=Eigen::Vector3d(0.0, 0.0, 1.0)) |
bool | OrientNormalsTowardsCameraLocation (const Eigen::Vector3d &camera_location=Eigen::Vector3d::Zero()) |
std::vector< double > | ComputePointCloudDistance (const PointCloud &target) |
std::tuple< Eigen::Vector3d, Eigen::Matrix3d > | ComputeMeanAndCovariance () const |
std::vector< double > | ComputeMahalanobisDistance () const |
std::vector< double > | ComputeNearestNeighborDistance () const |
std::shared_ptr< TriangleMesh > | ComputeConvexHull () const |
Function that computes the convex hull of the point cloud using qhull. More... | |
std::vector< int > | ClusterDBSCAN (double eps, size_t min_points, bool print_progress=false) const |
std::shared_ptr< PointCloud > | CreateFromVoxelGrid (const VoxelGrid &voxel_grid) |
![]() | |
~Geometry3D () override | |
![]() | |
virtual | ~Geometry () |
GeometryType | GetGeometryType () const |
int | Dimension () const |
Static Public Member Functions | |
static std::shared_ptr< PointCloud > | CreateFromDepthImage (const Image &depth, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity(), double depth_scale=1000.0, double depth_trunc=1000.0, int stride=1) |
static std::shared_ptr< PointCloud > | CreateFromRGBDImage (const RGBDImage &image, const camera::PinholeCameraIntrinsic &intrinsic, const Eigen::Matrix4d &extrinsic=Eigen::Matrix4d::Identity()) |
Data Fields | |
std::vector< Eigen::Vector3d > | points_ |
std::vector< Eigen::Vector3d > | normals_ |
std::vector< Eigen::Vector3d > | colors_ |
Additional Inherited Members | |
![]() | |
enum | RotationType { RotationType::XYZ, RotationType::YZX, RotationType::ZXY, RotationType::XZY, RotationType::ZYX, RotationType::YXZ, RotationType::AxisAngle } |
![]() | |
enum | GeometryType { GeometryType::Unspecified = 0, GeometryType::PointCloud = 1, GeometryType::VoxelGrid = 2, GeometryType::Octree = 3, GeometryType::LineSet = 4, GeometryType::TriangleMesh = 5, GeometryType::HalfEdgeTriangleMesh = 6, GeometryType::Image = 7, GeometryType::RGBDImage = 8, GeometryType::TetraMesh = 9, GeometryType::OrientedBoundingBox = 10, GeometryType::AxisAlignedBoundingBox = 11 } |
![]() | |
Geometry3D (GeometryType type) | |
Eigen::Vector3d | ComputeMinBound (const std::vector< Eigen::Vector3d > &points) const |
Eigen::Vector3d | ComputeMaxBound (const std::vector< Eigen::Vector3d > &points) const |
Eigen::Vector3d | ComputeCenter (const std::vector< Eigen::Vector3d > &points) const |
void | ResizeAndPaintUniformColor (std::vector< Eigen::Vector3d > &colors, const size_t size, const Eigen::Vector3d &color) const |
void | TransformPoints (const Eigen::Matrix4d &transformation, std::vector< Eigen::Vector3d > &points) const |
void | TransformNormals (const Eigen::Matrix4d &transformation, std::vector< Eigen::Vector3d > &normals) const |
void | TranslatePoints (const Eigen::Vector3d &translation, std::vector< Eigen::Vector3d > &points, bool relative) const |
void | ScalePoints (const double scale, std::vector< Eigen::Vector3d > &points, bool center) const |
void | RotatePoints (const Eigen::Vector3d &rotation, std::vector< Eigen::Vector3d > &points, bool center, RotationType type) const |
void | RotateNormals (const Eigen::Vector3d &rotation, std::vector< Eigen::Vector3d > &normals, bool center, RotationType type) const |
Eigen::Matrix3d | GetRotationMatrix (const Eigen::Vector3d &rotation, RotationType type=RotationType::XYZ) const |
![]() | |
Geometry (GeometryType type, int dimension) | |
|
inline |
|
inlineoverride |
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
std::vector< int > open3d::geometry::PointCloud::ClusterDBSCAN | ( | double | eps, |
size_t | min_points, | ||
bool | print_progress = false |
||
) | const |
Cluster PointCloud using the DBSCAN algorithm Ester et al., "A Density-Based Algorithm for Discovering Clusters in Large Spatial Databases with Noise", 1996 Returns a vector of point labels, -1 indicates noise according to the algorithm.
std::shared_ptr< TriangleMesh > open3d::geometry::PointCloud::ComputeConvexHull | ( | ) | const |
Function that computes the convex hull of the point cloud using qhull.
std::vector< double > open3d::geometry::PointCloud::ComputeMahalanobisDistance | ( | ) | const |
Function to compute the Mahalanobis distance for points in an
input | point cloud https://en.wikipedia.org/wiki/Mahalanobis_distance |
std::tuple< Eigen::Vector3d, Eigen::Matrix3d > open3d::geometry::PointCloud::ComputeMeanAndCovariance | ( | ) | const |
Function to compute the mean and covariance matrix of an
input | point cloud |
std::vector< double > open3d::geometry::PointCloud::ComputeNearestNeighborDistance | ( | ) | const |
Function to compute the distance from a point to its nearest neighbor in the
input | point cloud |
std::vector< double > open3d::geometry::PointCloud::ComputePointCloudDistance | ( | const PointCloud & | target | ) |
Function to compute the point to point distances between point clouds
source | is the first point cloud. |
target | is the second point cloud. |
source |
|
static |
Factory function to create a pointcloud from a depth image and a camera model (PointCloudFactory.cpp) The input depth image can be either a float image, or a uint16_t image. In the latter case, the depth is scaled by 1 / depth_scale, and truncated at depth_trunc distance. The depth image is also sampled with stride, in order to support (fast) coarse point cloud extraction. Return an empty pointcloud if the conversion fails.
|
static |
Factory function to create a pointcloud from an RGB-D image and a camera model (PointCloudFactory.cpp) Return an empty pointcloud if the conversion fails.
std::shared_ptr< PointCloud > open3d::geometry::PointCloud::CreateFromVoxelGrid | ( | const VoxelGrid & | voxel_grid | ) |
Function to create a PointCloud from a VoxelGrid. It transforms the voxel centers to 3D points using the original point cloud coordinate (with respect to the center of the voxel grid).
std::shared_ptr< PointCloud > open3d::geometry::PointCloud::Crop | ( | const Eigen::Vector3d & | min_bound, |
const Eigen::Vector3d & | max_bound | ||
) | const |
Function to crop
input | pointcloud into output pointcloud All points with coordinates less than |
min_bound | or larger than |
max_bound | are clipped. |
bool open3d::geometry::PointCloud::EstimateNormals | ( | const KDTreeSearchParam & | search_param = KDTreeSearchParamKNN() , |
bool | fast_normal_computation = true |
||
) |
Function to compute the normals of a point cloud
cloud | is the input point cloud. It also stores the output normals. Normals are oriented with respect to the input point cloud if normals exist in the input. |
search_param | The KDTree search parameters |
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
inline |
|
inline |
|
inline |
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
inline |
PointCloud open3d::geometry::PointCloud::operator+ | ( | const PointCloud & | cloud | ) | const |
PointCloud & open3d::geometry::PointCloud::operator+= | ( | const PointCloud & | cloud | ) |
bool open3d::geometry::PointCloud::OrientNormalsToAlignWithDirection | ( | const Eigen::Vector3d & | orientation_reference = Eigen::Vector3d(0.0, 0.0, 1.0) | ) |
Function to orient the normals of a point cloud
cloud | is the input point cloud. It must have normals. Normals are oriented with respect to |
orientation_reference |
bool open3d::geometry::PointCloud::OrientNormalsTowardsCameraLocation | ( | const Eigen::Vector3d & | camera_location = Eigen::Vector3d::Zero() | ) |
Function to orient the normals of a point cloud
cloud | is the input point cloud. It also stores the output normals. Normals are oriented with towards |
camera_location |
|
inline |
Assigns each point in the PointCloud the same color.
color. |
PointCloud & open3d::geometry::PointCloud::RemoveNoneFinitePoints | ( | bool | remove_nan = true , |
bool | remove_infinite = true |
||
) |
Remove all points fromt he point cloud that have a nan entry, or infinite entries. Also removes the corresponding normals and color entries.
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > open3d::geometry::PointCloud::RemoveRadiusOutliers | ( | size_t | nb_points, |
double | search_radius | ||
) | const |
Function to remove points that have less than
nb_points | in a sphere of radius |
search_radius |
std::tuple< std::shared_ptr< PointCloud >, std::vector< size_t > > open3d::geometry::PointCloud::RemoveStatisticalOutliers | ( | size_t | nb_neighbors, |
double | std_ratio | ||
) | const |
Function to remove points that are further away from their
nb_neighbor | neighbors in average. |
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
std::shared_ptr< PointCloud > open3d::geometry::PointCloud::SelectDownSample | ( | const std::vector< size_t > & | indices, |
bool | invert = false |
||
) | const |
Function to select points from
input | pointcloud into |
indices | are selected. |
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
|
overridevirtual |
Implements open3d::geometry::Geometry3D.
std::shared_ptr< PointCloud > open3d::geometry::PointCloud::UniformDownSample | ( | size_t | every_k_points | ) | const |
Function to downsample
input | pointcloud into output pointcloud uniformly |
every_k_points | indicates the sample rate. |
std::shared_ptr< PointCloud > open3d::geometry::PointCloud::VoxelDownSample | ( | double | voxel_size | ) | const |
Function to downsample
input | pointcloud into output pointcloud with a voxel |
voxel_size | defines the resolution of the voxel grid, smaller value leads to denser output point cloud. Normals and colors are averaged if they exist. |
std::tuple< std::shared_ptr< PointCloud >, Eigen::MatrixXi > open3d::geometry::PointCloud::VoxelDownSampleAndTrace | ( | double | voxel_size, |
const Eigen::Vector3d & | min_bound, | ||
const Eigen::Vector3d & | max_bound, | ||
bool | approximate_class = false |
||
) | const |
Function to downsample using VoxelDownSample, but specialized for Surface convolution project. Experimental function.
std::vector<Eigen::Vector3d> open3d::geometry::PointCloud::colors_ |
std::vector<Eigen::Vector3d> open3d::geometry::PointCloud::normals_ |
std::vector<Eigen::Vector3d> open3d::geometry::PointCloud::points_ |