Skip to content

Commit

Permalink
Add Hausdorff
Browse files Browse the repository at this point in the history
Remove 0.5 from Chamfer
Add reference and equations to docs.
rename compute_distance -> compute_metrics
Return Tensor instead of vector
  • Loading branch information
ssheorey committed Nov 18, 2024
1 parent 312476a commit a4f379d
Show file tree
Hide file tree
Showing 15 changed files with 431 additions and 208 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
5 changes: 3 additions & 2 deletions cpp/open3d/t/geometry/Geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,9 @@ class Geometry : public core::IsDevice {
};
/// Metrics for comparing point clouds and triangle meshes.
enum class Metric {
ChamferDistance, ///< Chamfer Distance
FScore ///< F-Score
ChamferDistance, ///< Chamfer Distance
HausdorffDistance, ///< Hausdorff Distance
FScore ///< F-Score
};

/// Holder for various parameters required by metrics
Expand Down
8 changes: 4 additions & 4 deletions cpp/open3d/t/geometry/PointCloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1332,9 +1332,9 @@ int PointCloud::PCAPartition(int max_points) {
return num_partitions;
}

std::vector<float> PointCloud::ComputeDistance(const PointCloud &pcd2,
std::vector<Metric> metrics,
MetricParameters params) const {
core::Tensor PointCloud::ComputeMetrics(const PointCloud &pcd2,
std::vector<Metric> metrics,
MetricParameters params) const {
if (!IsCPU() || !pcd2.IsCPU()) {
utility::LogWarning(
"ComputeDistance is implemented only on CPU. Computing on "
Expand All @@ -1357,7 +1357,7 @@ std::vector<float> PointCloud::ComputeDistance(const PointCloud &pcd2,
std::tie(indices12, distance12) = tree2.KnnSearch(points1, 1);
std::tie(indices21, distance21) = tree2.KnnSearch(points2, 1);

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

} // namespace geometry
Expand Down
32 changes: 29 additions & 3 deletions cpp/open3d/t/geometry/PointCloud.h
Original file line number Diff line number Diff line change
Expand Up @@ -698,14 +698,40 @@ class PointCloud : public Geometry, public DrawableGeometry {
/// \return The number of partitions.
int PCAPartition(int max_points);

/// Compute various distances / metrics between two point clouds. Currently,
/// Chamfer distance and F-Score are supported.
/// 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.
std::vector<float> ComputeDistance(
/// \returns Tensor containing the requested metrics.
core::Tensor ComputeMetrics(
const PointCloud &pcd2,
std::vector<Metric> metrics = {Metric::ChamferDistance},
MetricParameters params = MetricParameters()) const;
Expand Down
9 changes: 4 additions & 5 deletions cpp/open3d/t/geometry/TriangleMesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1591,10 +1591,9 @@ PointCloud TriangleMesh::SamplePointsUniformly(
return pcd.To(GetDevice());
}

std::vector<float> TriangleMesh::ComputeDistance(
const TriangleMesh &mesh2,
std::vector<Metric> metrics,
MetricParameters params) const {
core::Tensor TriangleMesh::ComputeMetrics(const TriangleMesh &mesh2,
std::vector<Metric> metrics,
MetricParameters params) const {
if (!IsCPU() || !mesh2.IsCPU()) {
utility::LogWarning(
"ComputeDistance is implemented only on CPU. Computing on "
Expand All @@ -1616,7 +1615,7 @@ std::vector<float> TriangleMesh::ComputeDistance(
core::Tensor distance21 = scene1.ComputeDistance(points2);
core::Tensor distance12 = scene2.ComputeDistance(points1);

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

} // namespace geometry
Expand Down
36 changes: 32 additions & 4 deletions cpp/open3d/t/geometry/TriangleMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -1020,15 +1020,43 @@ class TriangleMesh : public Geometry, public DrawableGeometry {
PointCloud SamplePointsUniformly(size_t number_of_points,
bool use_triangle_normal = false);

/// Compute various distances / metrics between two triangle meshes. This
/// uses ray casting for distance computations between a triangle mesh and a
/// sampled point cloud.
/// 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.
std::vector<float> ComputeDistance(
/// \returns Tensor containing the requested metrics.
core::Tensor ComputeMetrics(
const TriangleMesh &mesh2,
std::vector<Metric> metrics = {Metric::ChamferDistance},
MetricParameters params = MetricParameters()) const;
Expand Down
30 changes: 21 additions & 9 deletions cpp/open3d/t/geometry/kernel/Metrics.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,20 +13,32 @@ namespace open3d {
namespace t {
namespace geometry {

std::vector<float> ComputeDistanceCommon(core::Tensor distance12,
core::Tensor distance21,
std::vector<Metric> metrics,
MetricParameters params) {
std::vector<float> metric_values;
core::Tensor ComputeMetricsCommon(core::Tensor distance12,
core::Tensor distance21,
std::vector<Metric> metrics,
MetricParameters params) {
int n_metrics = metrics.size();
if (std::find(metrics.begin(), metrics.end(), Metric::FScore) !=
metrics.end()) {
n_metrics += params.fscore_radius.size() - 1;
}
core::Tensor metric_values({n_metrics}, core::Float32,
distance12.GetDevice());
float metric_val;

int idx = 0;
for (Metric metric : metrics) {
switch (metric) {
case Metric::ChamferDistance:
metric_val = 0.5 *
(distance21.Reshape({-1}).Mean({0}).Item<float>() +
metric_val = (distance21.Reshape({-1}).Mean({0}).Item<float>() +
distance12.Reshape({-1}).Mean({0}).Item<float>());
metric_values.push_back(metric_val);
metric_values[idx++] = metric_val;
break;
case Metric::HausdorffDistance:
metric_val = std::max(
distance12.Reshape({-1}).Max({0}).Item<float>(),
distance21.Reshape({-1}).Max({0}).Item<float>());
metric_values[idx++] = metric_val;
break;
case Metric::FScore:
float *p_distance12 = distance12.GetDataPtr<float>(),
Expand All @@ -46,7 +58,7 @@ std::vector<float> ComputeDistanceCommon(core::Tensor distance12,
if (precision + recall > 0) {
fscore = 2 * precision * recall / (precision + recall);
}
metric_values.push_back(fscore);
metric_values[idx++] = fscore;
}
break;
}
Expand Down
8 changes: 4 additions & 4 deletions cpp/open3d/t/geometry/kernel/Metrics.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@ namespace open3d {
namespace t {
namespace geometry {

std::vector<float> ComputeDistanceCommon(core::Tensor distance12,
core::Tensor distance21,
std::vector<Metric> metrics,
MetricParameters params);
core::Tensor ComputeMetricsCommon(core::Tensor distance12,
core::Tensor distance21,
std::vector<Metric> metrics,
MetricParameters params);
}
} // namespace t
} // namespace open3d
7 changes: 5 additions & 2 deletions cpp/pybind/t/geometry/geometry.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,10 +47,13 @@ void pybind_geometry_declarations(py::module& m) {
py::module m_geometry = m.def_submodule(
"geometry", "Tensor-based geometry defining module.");

py::enum_<Metric>(m_geometry, "Metric",
"Metrics for comparing point clouds and triangle meshes.")
py::enum_<Metric>(
m_geometry, "Metric",
"Enum for metrics for comparing point clouds and triangle meshes.")
.value("ChamferDistance", Metric::ChamferDistance,
"Chamfer Distance")
.value("HausdorffDistance", Metric::HausdorffDistance,
"Hausdorff Distance")
.value("FScore", Metric::FScore, "F-Score")
.export_values();
py::bind_vector<std::vector<Metric>>(m_geometry, "VectorMetric");
Expand Down
16 changes: 13 additions & 3 deletions cpp/pybind/t/geometry/pointcloud.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -770,14 +770,24 @@ the partition id for each point.
)");

pointcloud.def(
"compute_distance", &PointCloud::ComputeDistance, "pcd2"_a,
"compute_metrics", &PointCloud::ComputeMetrics, "pcd2"_a,
"metrics"_a, "params"_a,
R"(Compute various distances / metrics between two point clouds. Currently, Chamfer distance and F-Score are supported.
R"(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.
.. math:
\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)} \\
Args:
pcd2 (t.geometry.PointCloud): Other point cloud to compare with.
metrics (Sequence[t.geometry.Metric]): List of Metric s to compute. Multiple metrics can be computed at once for efficiency.
params (t.geometry.MetricParameters): This holds parameters required by different metrics.)");
params (t.geometry.MetricParameters): This holds parameters required by different metrics.
Returns:
Tensor containing the requested metrics.)");
}

} // namespace geometry
Expand Down
24 changes: 18 additions & 6 deletions cpp/pybind/t/geometry/trianglemesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -323,7 +323,7 @@ values with respect to a plane.
generated. The value describes the signed distance to the plane.
Returns:
LineSet with he extracted contours.
LineSet with the extracted contours.
This example shows how to create a hemisphere from a sphere::
Expand Down Expand Up @@ -1049,7 +1049,7 @@ or has a negative value, it is ignored.
Example:
This code computes the overall surface area of a box:
This code computes the overall surface area of a box::
import open3d as o3d
box = o3d.t.geometry.TriangleMesh.create_box()
Expand Down Expand Up @@ -1094,14 +1094,26 @@ Example::
)");

triangle_mesh.def(
"compute_distance", &TriangleMesh::ComputeDistance, "mesh2"_a,
"compute_metrics", &TriangleMesh::ComputeMetrics, "mesh2"_a,
"metrics"_a, "params"_a,
R"(Compute various distances / metrics between two triangle meshes. Currently, Chamfer distance and F-Score are supported. This uses ray casting for distance computations between a triangle mesh and a sampled point cloud.
R"(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 [\\[Knapitsch2017\\]](../tutorial/reference.html#Knapitsch2017) 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 the 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.
.. math::
\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)} \\
As a side effect, the triangle areas are saved in the "areas" attribute.
Args:
mesh2 (t.geometry.TriangleMesh): Other point cloud to compare with.
mesh2 (t.geometry.TriangleMesh): Other triangle mesh to compare with.
metrics (Sequence[t.geometry.Metric]): List of Metric s to compute. Multiple metrics can be computed at once for efficiency.
params (t.geometry.MetricParameters): This holds parameters required by different metrics.)");
params (t.geometry.MetricParameters): This holds parameters required by different metrics.
Returns:
Tensor containing the requested metrics.)");
}

} // namespace geometry
Expand Down
Loading

0 comments on commit a4f379d

Please sign in to comment.