Skip to content

Commit

Permalink
Add some legacy warppers for Tensor PointCloud (#5330)
Browse files Browse the repository at this point in the history
  • Loading branch information
yuecideng authored Aug 12, 2022
1 parent 572231d commit 07601e7
Show file tree
Hide file tree
Showing 4 changed files with 295 additions and 33 deletions.
60 changes: 58 additions & 2 deletions cpp/open3d/t/geometry/PointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -359,6 +359,14 @@ PointCloud PointCloud::RandomDownSample(double sampling_ratio) const {
false, false);
}

PointCloud PointCloud::FarthestPointDownSample(size_t num_samples) const {
// We want the sampled points has the attributes of the original point
// cloud, so full copy is needed.
const open3d::geometry::PointCloud lpcd = ToLegacy();
return FromLegacy(*lpcd.FarthestPointDownSample(num_samples),
GetPointPositions().GetDtype(), GetDevice());
}

std::tuple<PointCloud, core::Tensor> PointCloud::RemoveRadiusOutliers(
size_t nb_points, double search_radius) const {
if (nb_points < 1 || search_radius <= 0) {
Expand Down Expand Up @@ -841,6 +849,32 @@ open3d::geometry::PointCloud PointCloud::ToLegacy() const {
return pcd_legacy;
}

std::tuple<TriangleMesh, core::Tensor> PointCloud::HiddenPointRemoval(
const core::Tensor &camera_location, double radius) const {
core::AssertTensorShape(camera_location, {3});
core::AssertTensorDevice(camera_location, GetDevice());

// The HiddenPointRemoval only need positions attribute.
PointCloud tpcd(GetPointPositions());
const open3d::geometry::PointCloud lpcd = tpcd.ToLegacy();
const Eigen::Vector3d camera_location_eigen =
core::eigen_converter::TensorToEigenMatrixXd(
camera_location.Reshape({3, 1}));

std::shared_ptr<open3d::geometry::TriangleMesh> lmesh;
std::vector<size_t> pt_map;
std::tie(lmesh, pt_map) =
lpcd.HiddenPointRemoval(camera_location_eigen, radius);

// Convert pt_map into Int64 Tensor.
std::vector<int64_t> indices(pt_map.begin(), pt_map.end());

return std::make_tuple(
TriangleMesh::FromLegacy(*lmesh, GetPointPositions().GetDtype(),
core::Int64, GetDevice()),
core::Tensor(std::move(indices)).To(GetDevice()));
}

core::Tensor PointCloud::ClusterDBSCAN(double eps,
size_t min_points,
bool print_progress) const {
Expand All @@ -850,7 +884,29 @@ core::Tensor PointCloud::ClusterDBSCAN(double eps,
open3d::geometry::PointCloud lpcd = tpcd.ToLegacy();
std::vector<int> labels =
lpcd.ClusterDBSCAN(eps, min_points, print_progress);
return core::Tensor(std::move(labels));
return core::Tensor(std::move(labels)).To(GetDevice());
}

std::tuple<core::Tensor, core::Tensor> PointCloud::SegmentPlane(
const double distance_threshold,
const int ransac_n,
const int num_iterations,
const double probability) const {
// The RANSAC plane fitting only need positions attribute.
PointCloud tpcd(GetPointPositions());
const open3d::geometry::PointCloud lpcd = tpcd.ToLegacy();
std::vector<size_t> inliers;
Eigen::Vector4d plane;
std::tie(plane, inliers) = lpcd.SegmentPlane(distance_threshold, ransac_n,
num_iterations, probability);

// Convert inliers into Int64 Tensor.
std::vector<int64_t> indices(inliers.begin(), inliers.end());

return std::make_tuple(
core::eigen_converter::EigenMatrixToTensor(plane).Flatten().To(
GetDevice()),
core::Tensor(std::move(indices)).To(GetDevice()));
}

TriangleMesh PointCloud::ComputeConvexHull(bool joggle_inputs) const {
Expand Down Expand Up @@ -920,7 +976,7 @@ TriangleMesh PointCloud::ComputeConvexHull(bool joggle_inputs) const {

TriangleMesh convex_hull(vertices, triangles);
convex_hull.SetVertexAttr("point_indices", point_indices);
return convex_hull;
return convex_hull.To(GetPointPositions().GetDevice());
}

AxisAlignedBoundingBox PointCloud::GetAxisAlignedBoundingBox() const {
Expand Down
47 changes: 46 additions & 1 deletion cpp/open3d/t/geometry/PointCloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -358,6 +358,15 @@ class PointCloud : public Geometry, public DrawableGeometry {
/// number of points in the pointcloud.
PointCloud RandomDownSample(double sampling_ratio) const;

/// \brief Downsample a pointcloud into output pointcloud with a set of
/// points has farthest distance.
///
/// The sampling is performed by selecting the farthest point from previous
/// selected points iteratively.
///
/// \param num_samples Number of points to be sampled.
PointCloud FarthestPointDownSample(size_t num_samples) const;

/// \brief Remove points that have less than \p nb_points neighbors in a
/// sphere of a given radius.
///
Expand Down Expand Up @@ -387,6 +396,24 @@ class PointCloud : public Geometry, public DrawableGeometry {
/// \brief Returns the device attribute of this PointCloud.
core::Device GetDevice() const override { return device_; }

/// \brief This is an implementation of the Hidden Point Removal operator
/// described in Katz et. al. 'Direct Visibility of Point Sets', 2007.
///
/// Additional information about the choice of radius
/// for noisy point clouds can be found in Mehra et. al. 'Visibility of
/// Noisy Point Cloud Data', 2010.
///
/// This is a wrapper for a CPU implementation and a copy of the point cloud
/// data and resulting visible triangle mesh and indiecs will be made.
///
/// \param camera_location All points not visible from that location will be
/// removed.
/// \param radius The radius of the spherical projection.
/// \return Tuple of visible triangle mesh and indices of visible points on
/// the same device as the point cloud.
std::tuple<TriangleMesh, core::Tensor> HiddenPointRemoval(
const core::Tensor &camera_location, double radius) const;

/// \brief Cluster PointCloud using the DBSCAN algorithm
/// Ester et al., "A Density-Based Algorithm for Discovering Clusters
/// in Large Spatial Databases with Noise", 1996
Expand All @@ -398,11 +425,29 @@ class PointCloud : public Geometry, public DrawableGeometry {
/// \param print_progress If `true` the progress is visualized in the
/// console.
/// \return A Tensor list of point labels on the same device as the point
/// cloud, -1 indicates noise according to the algorithm
/// cloud, -1 indicates noise according to the algorithm.
core::Tensor ClusterDBSCAN(double eps,
size_t min_points,
bool print_progress = false) const;

/// \brief Segment PointCloud plane using the RANSAC algorithm.
/// This is a wrapper for a CPU implementation and a copy of the point cloud
/// data and resulting plane model and inlier indiecs will be made.
///
/// \param distance_threshold Max distance a point can be from the plane
/// model, and still be considered an inlier.
/// \param ransac_n Number of initial points to be considered inliers in
/// each iteration.
/// \param num_iterations Maximum number of iterations.
/// \param probability Expected probability of finding the optimal plane.
/// \return Tuple of the plane model ax + by + cz + d = 0 and the indices of
/// the plane inliers on the same device as the point cloud.
std::tuple<core::Tensor, core::Tensor> SegmentPlane(
const double distance_threshold = 0.01,
const int ransac_n = 3,
const int num_iterations = 100,
const double probability = 0.99999999) const;

/// Compute the convex hull of a point cloud using qhull.
///
/// This runs on the CPU.
Expand Down
125 changes: 111 additions & 14 deletions cpp/pybind/t/geometry/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,6 +206,13 @@ The attributes of the point cloud have different levels::
"Downsample a pointcloud by selecting random index point "
"and its attributes.",
"sampling_ratio"_a);
pointcloud.def("farthest_point_down_sample",
&PointCloud::FarthestPointDownSample,
"Downsample a pointcloud into output pointcloud with a set "
"of points has farthest distance.The sampling is performed "
"by selecting the farthest point from previous selected "
"points iteratively",
"num_samples"_a);
pointcloud.def("remove_radius_outliers", &PointCloud::RemoveRadiusOutliers,
"nb_points"_a, "search_radius"_a,
"Remove points that have less than nb_points neighbors in a "
Expand Down Expand Up @@ -279,12 +286,107 @@ The attributes of the point cloud have different levels::
"depth_scale"_a = 1000.0, "depth_max"_a = 3.0,
"Project a colored point cloud to a RGBD image.");
pointcloud.def(
"cluster_dbscan", &PointCloud::ClusterDBSCAN,
"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 list of point "
"labels, -1 indicates noise according to the algorithm.",
"eps"_a, "min_points"_a, "print_progress"_a = false);
"hidden_point_removal", &PointCloud::HiddenPointRemoval,
"camera_location"_a, "radius"_a,
R"(Removes hidden points from a point cloud and returns a mesh of
the remaining points. Based on Katz et al. 'Direct Visibility of Point Sets',
2007. Additional information about the choice of radius for noisy point clouds
can be found in Mehra et. al. 'Visibility of Noisy Point Cloud Data', 2010.
This is a wrapper for a CPU implementation and a copy of the point cloud data
and resulting visible triangle mesh and indiecs will be made.
Args:
camera_location. All points not visible from that location will be removed.
radius. The radius of the spherical projection.
Return:
Tuple of visible triangle mesh and indices of visible points on the same
device as the point cloud.
Example:
We use armadillo mesh to compute the visible points from given camera::
# Convert mesh to a point cloud and estimate dimensions.
armadillo_data = o3d.data.ArmadilloMesh()
pcd = o3d.io.read_triangle_mesh(
armadillo_data.path).sample_points_poisson_disk(5000)
diameter = np.linalg.norm(
np.asarray(pcd.get_max_bound()) - np.asarray(pcd.get_min_bound()))
# Define parameters used for hidden_point_removal.
camera = o3d.core.Tensor([0, 0, diameter], o3d.core.float32)
radius = diameter * 100
# Get all points that are visible from given view point.
pcd = o3d.t.geometry.PointCloud.from_legacy(pcd)
_, pt_map = pcd.hidden_point_removal(camera, radius)
pcd = pcd.select_by_index(pt_map)
o3d.visualization.draw([pcd], point_size=5))");
pointcloud.def(
"cluster_dbscan", &PointCloud::ClusterDBSCAN, "eps"_a,
"min_points"_a, "print_progress"_a = false,
R"(Cluster PointCloud using the DBSCAN algorithm Ester et al.,'A
Density-Based Algorithm for Discovering Clusters in Large Spatial Databases
with Noise', 1996. This is a wrapper for a CPU implementation and a copy of the
point cloud data and resulting labels will be made.
Args:
eps. Density parameter that is used to find neighbouring points.
min_points. Minimum number of points to form a cluster.
print_progress (default False). If 'True' the progress is visualized in the console.
Return:
A Tensor list of point labels on the same device as the point cloud, -1
indicates noise according to the algorithm.
Example:
We use Redwood dataset for demonstration::
import matplotlib.pyplot as plt
sample_ply_data = o3d.data.PLYPointCloud()
pcd = o3d.t.io.read_point_cloud(sample_ply_data.path)
labels = pcd.cluster_dbscan(eps=0.02, min_points=10, print_progress=True)
max_label = labels.max().item()
colors = plt.get_cmap("tab20")(
labels.numpy() / (max_label if max_label > 0 else 1))
colors = o3d.core.Tensor(colors[:, :3], o3d.core.float32)
colors[labels < 0] = 0
pcd.point['colors'] = colors
o3d.visualization.draw([pcd]))");
pointcloud.def(
"segment_plane", &PointCloud::SegmentPlane,
"distance_threshold"_a = 0.01, "ransac_n"_a = 3,
"num_iterations"_a = 100, "probability"_a = 0.99999999,
R"(Segments a plane in the point cloud using the RANSAC algorithm.
This is a wrapper for a CPU implementation and a copy of the point cloud data and
resulting plane model and inlier indiecs will be made.
Args:
distance_threshold (default 0.01). Max distance a point can be from the plane
model, and still be considered an inlier.
ransac_n (default 3). Number of initial points to be considered inliers in each iteration.
num_iterations (default 100). Maximum number of iterations.
probability (default 0.99999999). Expected probability of finding the optimal plane.
Return:
Tuple of the plane model ax + by + cz + d = 0 and the indices of
the plane inliers on the same device as the point cloud.
Example:
We use Redwood dataset to compute its plane model and inliers::
sample_pcd_data = o3d.data.PCDPointCloud()
pcd = o3d.t.io.read_point_cloud(sample_pcd_data.path)
plane_model, inliers = pcd.segment_plane(distance_threshold=0.01,
ransac_n=3,
num_iterations=1000)
inlier_cloud = pcd.select_by_index(inliers)
inlier_cloud.paint_uniform_color([1.0, 0, 0])
outlier_cloud = pcd.select_by_index(inliers, invert=True)
o3d.visualization.draw([inlier_cloud, outlier_cloud]))");
pointcloud.def(
"compute_convex_hull", &PointCloud::ComputeConvexHull,
"joggle_inputs"_a = false,
Expand Down Expand Up @@ -357,6 +459,9 @@ The attributes of the point cloud have different levels::
{{"sampling_ratio",
"Sampling ratio, the ratio of sample to total number of points "
"in the pointcloud."}});
docstring::ClassMethodDocInject(
m, "PointCloud", "farthest_point_down_sample",
{{"num_samples", "Number of points to be sampled."}});
docstring::ClassMethodDocInject(
m, "PointCloud", "remove_radius_outliers",
{{"nb_points",
Expand All @@ -367,14 +472,6 @@ The attributes of the point cloud have different levels::
{{"color",
"Color of the pointcloud. Floating color values are clipped "
"between 0.0 and 1.0."}});

docstring::ClassMethodDocInject(
m, "PointCloud", "cluster_dbscan",
{{"eps",
"Density parameter that is used to find neighbouring points."},
{"min_points", "Minimum number of points to form a cluster."},
{"print_progress",
"If true the progress is visualized in the console."}});
docstring::ClassMethodDocInject(
m, "PointCloud", "crop",
{{"aabb", "AxisAlignedBoundingBox to crop points."},
Expand Down
Loading

0 comments on commit 07601e7

Please sign in to comment.