Skip to content

Commit

Permalink
SamplePointsUniformly, Chamfer Distance, Hausdorff Distance and F-Sco…
Browse files Browse the repository at this point in the history
…re (#7056)
  • Loading branch information
ssheorey authored Nov 19, 2024
1 parent 9d0cfc8 commit 870dcb9
Show file tree
Hide file tree
Showing 20 changed files with 1,084 additions and 162 deletions.
3 changes: 3 additions & 0 deletions cpp/open3d/Macro.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,6 +10,9 @@
#include <cassert>

// https://gcc.gnu.org/wiki/Visibility updated to use C++11 attribute syntax
// In Open3D, we set symbol visibility based on folder / cmake target through
// cmake. e.g. all symbols in kernel folders are hidden. These macros allow fine
// grained control over symbol visibility.
#if defined(_WIN32) || defined(__CYGWIN__)
#define OPEN3D_DLL_IMPORT __declspec(dllimport)
#define OPEN3D_DLL_EXPORT __declspec(dllexport)
Expand Down
24 changes: 24 additions & 0 deletions cpp/open3d/t/geometry/Geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,8 @@

#pragma once

#include <fmt/format.h>

#include <string>

#include "open3d/core/Device.h"
Expand Down Expand Up @@ -90,6 +92,28 @@ class Geometry : public core::IsDevice {
int dimension_;
std::string name_;
};
/// Metrics for comparing point clouds and triangle meshes.
enum class Metric {
ChamferDistance, ///< Chamfer Distance
HausdorffDistance, ///< Hausdorff Distance
FScore ///< F-Score
};

/// Holder for various parameters required by metrics
struct MetricParameters {
/// Radius for computing the F Score. A match between a point and its
/// nearest neighbor is sucessful if it is within this radius.
std::vector<float> fscore_radius = {0.01};
/// Points are sampled uniformly from the surface of triangle meshes before
/// distance computation. This specifies the number of points sampled. No
/// sampling is done for point clouds.
size_t n_sampled_points = 1000;
std::string ToString() const {
return fmt::format(
"MetricParameters: fscore_radius={}, n_sampled_points={}",
fscore_radius, n_sampled_points);
}
};

} // namespace geometry
} // namespace t
Expand Down
34 changes: 34 additions & 0 deletions cpp/open3d/t/geometry/PointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "open3d/t/geometry/TriangleMesh.h"
#include "open3d/t/geometry/VtkUtils.h"
#include "open3d/t/geometry/kernel/GeometryMacros.h"
#include "open3d/t/geometry/kernel/Metrics.h"
#include "open3d/t/geometry/kernel/PCAPartition.h"
#include "open3d/t/geometry/kernel/PointCloud.h"
#include "open3d/t/geometry/kernel/Transform.h"
Expand Down Expand Up @@ -1331,6 +1332,39 @@ int PointCloud::PCAPartition(int max_points) {
return num_partitions;
}

core::Tensor PointCloud::ComputeMetrics(const PointCloud &pcd2,
std::vector<Metric> metrics,
MetricParameters params) const {
if (IsEmpty() || pcd2.IsEmpty()) {
utility::LogError("One or both input point clouds are empty!");
}
if (!IsCPU() || !pcd2.IsCPU()) {
utility::LogWarning(
"ComputeDistance is implemented only on CPU. Computing on "
"CPU.");
}
core::Tensor points1 = GetPointPositions().To(core::Device("CPU:0")),
points2 = pcd2.GetPointPositions().To(core::Device("CPU:0"));
[[maybe_unused]] core::Tensor indices12, indices21;
core::Tensor sqr_distance12, sqr_distance21;

core::nns::NearestNeighborSearch tree1(points1);
core::nns::NearestNeighborSearch tree2(points2);

if (!tree2.KnnIndex()) {
utility::LogError("[ComputeDistance] Building KNN-Index failed!");
}
if (!tree1.KnnIndex()) {
utility::LogError("[ComputeDistance] Building KNN-Index failed!");
}

std::tie(indices12, sqr_distance12) = tree2.KnnSearch(points1, 1);
std::tie(indices21, sqr_distance21) = tree1.KnnSearch(points2, 1);

return ComputeMetricsCommon(sqr_distance12.Sqrt_(), sqr_distance21.Sqrt_(),
metrics, params);
}

} // namespace geometry
} // namespace t
} // namespace open3d
39 changes: 39 additions & 0 deletions cpp/open3d/t/geometry/PointCloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@

#pragma once

#include <initializer_list>
#include <string>
#include <unordered_map>
#include <unordered_set>
Expand Down Expand Up @@ -697,6 +698,44 @@ class PointCloud : public Geometry, public DrawableGeometry {
/// \return The number of partitions.
int PCAPartition(int max_points);

/// Compute various metrics between two point clouds. Currently, Chamfer
/// distance, Hausdorff distance and F-Score
/// <a href="../tutorial/reference.html#Knapitsch2017">[[Knapitsch2017]]</a>
/// are supported. The Chamfer distance is the sum of the mean distance to
/// the nearest neighbor from the points of the first point cloud to the
/// second point cloud. The F-Score at a fixed threshold radius is the
/// harmonic mean of the Precision and Recall. Recall is the percentage of
/// surface points from the first point cloud that have the second point
/// cloud points within the threshold radius, while Precision is the
/// percentage of points from the second point cloud that have the first
/// point cloud points within the threhold radius.

/// \f{eqnarray*}{
/// \text{Chamfer Distance: } d_{CD}(X,Y) &=& \frac{1}{|X|}\sum_{i \in X}
/// || x_i - n(x_i, Y) || + \frac{1}{|Y|}\sum_{i \in Y} || y_i - n(y_i, X)
/// || \\{}
/// \text{Hausdorff distance: } d_H(X,Y) &=& \max \left\{ \max_{i \in X}
/// || x_i - n(x_i, Y) ||, \max_{i \in Y} || y_i - n(y_i, X) || \right\}
/// \\{}
/// \text{Precision: } P(X,Y|d) &=& \frac{100}{|X|} \sum_{i \in X} || x_i
/// - n(x_i, Y) || < d \\{}
/// \text{Recall: } R(X,Y|d) &=& \frac{100}{|Y|} \sum_{i \in Y} || y_i -
/// n(y_i, X) || < d \\{}
/// \text{F-Score: } F(X,Y|d) &=& \frac{2 P(X,Y|d) R(X,Y|d)}{P(X,Y|d) +
/// R(X,Y|d)}
/// \f}

/// \param pcd2 Other point cloud to compare with.
/// \param metrics List of Metric s to compute. Multiple metrics can be
/// computed at once for efficiency.
/// \param params MetricParameters struct holds parameters required by
/// different metrics.
/// \returns Tensor containing the requested metrics.
core::Tensor ComputeMetrics(
const PointCloud &pcd2,
std::vector<Metric> metrics = {Metric::ChamferDistance},
MetricParameters params = MetricParameters()) const;

protected:
core::Device device_ = core::Device("CPU:0");
TensorMap point_attr_;
Expand Down
116 changes: 115 additions & 1 deletion cpp/open3d/t/geometry/TriangleMesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@
#include <unordered_map>

#include "open3d/core/CUDAUtils.h"
#include "open3d/core/Device.h"
#include "open3d/core/Dtype.h"
#include "open3d/core/EigenConverter.h"
#include "open3d/core/ShapeUtil.h"
#include "open3d/core/Tensor.h"
Expand All @@ -28,6 +30,7 @@
#include "open3d/t/geometry/PointCloud.h"
#include "open3d/t/geometry/RaycastingScene.h"
#include "open3d/t/geometry/VtkUtils.h"
#include "open3d/t/geometry/kernel/Metrics.h"
#include "open3d/t/geometry/kernel/PCAPartition.h"
#include "open3d/t/geometry/kernel/PointCloud.h"
#include "open3d/t/geometry/kernel/Transform.h"
Expand Down Expand Up @@ -315,6 +318,12 @@ TriangleMesh &TriangleMesh::ComputeTriangleAreas() {
utility::LogWarning("TriangleMesh has no triangle indices.");
return *this;
}
if (HasTriangleAttr("areas")) {
utility::LogWarning(
"TriangleMesh already has triangle areas: remove "
"'areas' triangle attribute if you'd like to update.");
return *this;
}

core::Tensor triangle_areas = ComputeTriangleAreasHelper(*this);
SetTriangleAttr("areas", triangle_areas);
Expand Down Expand Up @@ -1404,7 +1413,9 @@ TriangleMesh TriangleMesh::RemoveNonManifoldEdges() {
core::Tensor tris_cpu =
GetTriangleIndices().To(core::Device()).Contiguous();

ComputeTriangleAreas();
if (!HasTriangleAttr("areas")) {
ComputeTriangleAreas();
}
core::Tensor tri_areas_cpu =
GetTriangleAttr("areas").To(core::Device()).Contiguous();

Expand Down Expand Up @@ -1507,6 +1518,109 @@ core::Tensor TriangleMesh::GetNonManifoldEdges(
return result;
}

PointCloud TriangleMesh::SamplePointsUniformly(
size_t number_of_points, bool use_triangle_normal /*=false*/) {
if (number_of_points <= 0) {
utility::LogError("number_of_points <= 0");
}
if (IsEmpty()) {
utility::LogError("Input mesh is empty. Cannot sample points.");
}
if (!HasTriangleIndices()) {
utility::LogError("Input mesh has no triangles. Cannot sample points.");
}
if (use_triangle_normal && !HasTriangleNormals()) {
ComputeTriangleNormals(true);
}
if (!HasTriangleAttr("areas")) {
ComputeTriangleAreas(); // Compute area of each triangle
}
if (!IsCPU()) {
utility::LogWarning(
"SamplePointsUniformly is implemented only on CPU. Computing "
"on CPU.");
}
bool use_vert_normals = HasVertexNormals() && !use_triangle_normal;
bool use_albedo =
HasTriangleAttr("texture_uvs") && GetMaterial().HasAlbedoMap();
bool use_vert_colors = HasVertexColors() && !use_albedo;

auto cpu = core::Device();
core::Tensor null_tensor({0}, core::Float32); // zero size tensor
auto triangles = GetTriangleIndices().To(cpu).Contiguous(),
vertices = GetVertexPositions().To(cpu).Contiguous();
auto float_dt = vertices.GetDtype();
auto areas = GetTriangleAttr("areas").To(cpu, float_dt).Contiguous(),
vertex_normals =
use_vert_normals
? GetVertexNormals().To(cpu, float_dt).Contiguous()
: null_tensor,
triangle_normals =
use_triangle_normal
? GetTriangleNormals().To(cpu, float_dt).Contiguous()
: null_tensor,
vertex_colors =
use_vert_colors
? GetVertexColors().To(cpu, core::Float32).Contiguous()
: null_tensor,
texture_uvs = use_albedo ? GetTriangleAttr("texture_uvs")
.To(cpu, float_dt)
.Contiguous()
: null_tensor,
// With correct range conversion [0,255] -> [0,1]
albedo = use_albedo ? GetMaterial()
.GetAlbedoMap()
.To(core::Float32)
.To(cpu)
.AsTensor()
: null_tensor;
if (use_vert_colors) {
if (GetVertexColors().GetDtype() == core::UInt8) vertex_colors /= 255;
if (GetVertexColors().GetDtype() == core::UInt16)
vertex_colors /= 65535;
}

std::array<core::Tensor, 3> result =
kernel::trianglemesh::SamplePointsUniformlyCPU(
triangles, vertices, areas, vertex_normals, vertex_colors,
triangle_normals, texture_uvs, albedo, number_of_points);

PointCloud pcd(result[0]);
if (use_vert_normals || use_triangle_normal) pcd.SetPointNormals(result[1]);
if (use_albedo || use_vert_colors) pcd.SetPointColors(result[2]);
return pcd.To(GetDevice());
}

core::Tensor TriangleMesh::ComputeMetrics(const TriangleMesh &mesh2,
std::vector<Metric> metrics,
MetricParameters params) const {
if (IsEmpty() || mesh2.IsEmpty()) {
utility::LogError("One or both input triangle meshes are empty!");
}
if (!IsCPU() || !mesh2.IsCPU()) {
utility::LogWarning(
"ComputeDistance is implemented only on CPU. Computing on "
"CPU.");
}
auto cpu_mesh1 = To(core::Device("CPU:0")),
cpu_mesh2 = mesh2.To(core::Device("CPU:0"));
core::Tensor points1 =
cpu_mesh1.SamplePointsUniformly(params.n_sampled_points)
.GetPointPositions();
core::Tensor points2 =
cpu_mesh2.SamplePointsUniformly(params.n_sampled_points)
.GetPointPositions();

RaycastingScene scene1, scene2;
scene1.AddTriangles(cpu_mesh1);
scene2.AddTriangles(cpu_mesh2);

core::Tensor distance21 = scene1.ComputeDistance(points2);
core::Tensor distance12 = scene2.ComputeDistance(points1);

return ComputeMetricsCommon(distance12, distance21, metrics, params);
}

} // namespace geometry
} // namespace t
} // namespace open3d
54 changes: 54 additions & 0 deletions cpp/open3d/t/geometry/TriangleMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ namespace t {
namespace geometry {

class LineSet;
class PointCloud;

/// \class TriangleMesh
/// \brief A triangle mesh contains vertices and triangles.
Expand Down Expand Up @@ -1007,6 +1008,59 @@ class TriangleMesh : public Geometry, public DrawableGeometry {
/// If mesh is empty or has no triangles, returns an empty tensor.
core::Tensor GetNonManifoldEdges(bool allow_boundary_edges = true) const;

/// Sample points uniformly from the triangle mesh surface and return as a
/// PointCloud. Normals and colors are interpolated from the triangle mesh.
/// If texture_uvs and albedo are present, these are used to estimate the
/// sampled point color, otherwise vertex colors are used, if present.
/// During sampling, triangle areas are computed and saved in the "areas"
/// attribute.
/// \param number_of_points The number of points to sample.
/// \param use_triangle_normal If true, use the triangle normal as the
/// normal of the sampled point. Otherwise, interpolate the vertex normals.
PointCloud SamplePointsUniformly(size_t number_of_points,
bool use_triangle_normal = false);

/// Compute various metrics between two triangle meshes. This uses ray
/// casting for distance computations between a sampled point cloud and a
/// triangle mesh. Currently, Chamfer distance, Hausdorff distance and
/// F-Score <a
/// href="../tutorial/reference.html#Knapitsch2017">[[Knapitsch2017]]</a>
/// are supported. The Chamfer distance is the sum of the mean distance to
/// the nearest neighbor from the sampled surface points of the first mesh
/// to the second mesh and vice versa. The F-Score at a fixed threshold
/// radius is the harmonic mean of the Precision and Recall. Recall is the
/// percentage of surface points from the first mesh that have the second
/// mesh within the threshold radius, while Precision is the percentage of
/// sampled points from the second mesh that have the first mesh surface
/// within the threhold radius.

/// \f{eqnarray*}{
/// \text{Chamfer Distance: } d_{CD}(X,Y) &=& \frac{1}{|X|}\sum_{i \in X}
/// || x_i - n(x_i, Y) || + \frac{1}{|Y|}\sum_{i \in Y} || y_i - n(y_i, X)
/// || \\{}
/// \text{Hausdorff distance: } d_H(X,Y) &=& \max \left\{ \max_{i \in X}
/// || x_i - n(x_i, Y) ||, \max_{i \in Y} || y_i - n(y_i, X) || \right\}
/// \\{}
/// \text{Precision: } P(X,Y|d) &=& \frac{100}{|X|} \sum_{i \in X} || x_i
/// - n(x_i, Y) || < d \\{}
/// \text{Recall: } R(X,Y|d) &=& \frac{100}{|Y|} \sum_{i \in Y} || y_i -
/// n(y_i, X) || < d \\{}
/// \text{F-Score: } F(X,Y|d) &=& \frac{2 P(X,Y|d) R(X,Y|d)}{P(X,Y|d) +
/// R(X,Y|d)}
/// \f}

/// As a side effect, the triangle areas are saved in the "areas" attribute.
/// \param mesh2 Other point cloud to compare with.
/// \param metrics List of Metric s to compute. Multiple metrics can be
/// computed at once for efficiency.
/// \param params MetricParameters struct holds parameters required by
/// different metrics.
/// \returns Tensor containing the requested metrics.
core::Tensor ComputeMetrics(
const TriangleMesh &mesh2,
std::vector<Metric> metrics = {Metric::ChamferDistance},
MetricParameters params = MetricParameters()) const;

protected:
core::Device device_ = core::Device("CPU:0");
TensorMap vertex_attr_;
Expand Down
1 change: 1 addition & 0 deletions cpp/open3d/t/geometry/kernel/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ target_sources(tgeometry_kernel PRIVATE
PCAPartition.cpp
PointCloud.cpp
PointCloudCPU.cpp
Metrics.cpp
TriangleMesh.cpp
TriangleMeshCPU.cpp
Transform.cpp
Expand Down
Loading

0 comments on commit 870dcb9

Please sign in to comment.