Skip to content

Commit

Permalink
SamplePointsUniformly, F-Score and Chamfer Distance
Browse files Browse the repository at this point in the history
  • Loading branch information
ssheorey committed Nov 15, 2024
1 parent 9d0cfc8 commit 2f8a97c
Show file tree
Hide file tree
Showing 15 changed files with 592 additions and 1 deletion.
16 changes: 16 additions & 0 deletions cpp/open3d/t/geometry/Geometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,22 @@ class Geometry : public core::IsDevice {
int dimension_;
std::string name_;
};
/// Metrics for comparing point clouds and triangle meshes.
enum class Metric {
ChamferDistance, ///< Chamfer 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;
};

} // namespace geometry
} // namespace t
Expand Down
30 changes: 30 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,35 @@ int PointCloud::PCAPartition(int max_points) {
return num_partitions;
}

std::vector<float> PointCloud::ComputeDistance(
const PointCloud &pcd2,
std::initializer_list<Metric> metrics,
MetricParameters params) const {
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"));
core::Tensor indices12, distance12, indices21, 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, distance12) = tree2.KnnSearch(points1, 1);
std::tie(indices21, distance21) = tree2.KnnSearch(points2, 1);

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

} // namespace geometry
} // namespace t
} // namespace open3d
13 changes: 13 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,18 @@ 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.
/// \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(
const PointCloud &pcd2,
std::initializer_list<Metric> metrics = {Metric::ChamferDistance},
MetricParameters params = MetricParameters()) const;

protected:
core::Device device_ = core::Device("CPU:0");
TensorMap point_attr_;
Expand Down
114 changes: 113 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,107 @@ 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());
}

std::vector<float> TriangleMesh::ComputeDistance(
const TriangleMesh &mesh2,
std::initializer_list<Metric> metrics,
MetricParameters params) const {
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 ComputeDistanceCommon(distance12, distance21, metrics, params);
}

} // namespace geometry
} // namespace t
} // namespace open3d
26 changes: 26 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,31 @@ 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 distances / metrics between two triangle meshes. This
/// uses ray casting for distance computations between a triangle mesh and a
/// sampled point cloud.
/// \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(
const TriangleMesh &mesh2,
std::initializer_list<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
58 changes: 58 additions & 0 deletions cpp/open3d/t/geometry/kernel/Metrics.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,58 @@
// ----------------------------------------------------------------------------
// - Open3D: www.open3d.org -
// ----------------------------------------------------------------------------
// Copyright (c) 2018-2024 www.open3d.org
// SPDX-License-Identifier: MIT
// ----------------------------------------------------------------------------

#include <vector>

#include "open3d/core/Tensor.h"
#include "open3d/t/geometry/Geometry.h"
namespace open3d {
namespace t {
namespace geometry {

std::vector<float> OPEN3D_LOCAL
ComputeDistanceCommon(core::Tensor distance12,
core::Tensor distance21,
std::initializer_list<Metric> metrics,
MetricParameters params) {
std::vector<float> metric_values;
float metric_val;

for (Metric metric : metrics) {
switch (metric) {
case Metric::ChamferDistance:
metric_val = 0.5 * (distance21.Mean({-1}).Item<float>() +
distance12.Mean({-1}).Item<float>());
metric_values.push_back(metric_val);
break;
case Metric::FScore:
float *p_distance12 = distance12.GetDataPtr<float>(),
*p_distance21 = distance21.GetDataPtr<float>();
for (float radius : params.fscore_radius) {
// Workaround since we don't have Tensor::CountNonZeros
float precision = 0., recall = 0.;
for (size_t i = 0;
i < static_cast<size_t>(distance12.GetLength()); ++i)
precision += p_distance12[i] < radius;
precision *= 100. / distance12.GetLength();
for (size_t i = 0;
i < static_cast<size_t>(distance21.GetLength()); ++i)
recall += p_distance21[i] < radius;
recall *= 100. / distance21.GetLength();
float fscore = 0.0;
if (precision + recall > 0) {
fscore = 2 * precision * recall / (precision + recall);
}
metric_values.push_back(fscore);
}
break;
}
}
return metric_values;
}
} // namespace geometry
} // namespace t
} // namespace open3d
22 changes: 22 additions & 0 deletions cpp/open3d/t/geometry/kernel/Metrics.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
// ----------------------------------------------------------------------------
// - Open3D: www.open3d.org -
// ----------------------------------------------------------------------------
// Copyright (c) 2018-2024 www.open3d.org
// SPDX-License-Identifier: MIT
// ----------------------------------------------------------------------------

#include <vector>

#include "open3d/core/Tensor.h"
#include "open3d/t/geometry/Geometry.h"
namespace open3d {
namespace t {
namespace geometry {

std::vector<float> ComputeDistanceCommon(core::Tensor distance12,
core::Tensor distance21,
std::initializer_list<Metric> metrics,
MetricParameters params);
}
} // namespace t
} // namespace open3d
11 changes: 11 additions & 0 deletions cpp/open3d/t/geometry/kernel/TriangleMesh.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,17 @@ void ComputeTriangleAreasCPU(const core::Tensor& vertices,
const core::Tensor& triangles,
core::Tensor& triangle_areas);

std::array<core::Tensor, 3> SamplePointsUniformlyCPU(
const core::Tensor& triangles,
const core::Tensor& vertices,
const core::Tensor& triangle_areas,
const core::Tensor& vertex_normals,
const core::Tensor& vertex_colors,
const core::Tensor& triangle_normals,
const core::Tensor& texture_uvs,
const core::Tensor& albedo,
size_t number_of_points);

#ifdef BUILD_CUDA_MODULE
void NormalizeNormalsCUDA(core::Tensor& normals);

Expand Down
Loading

0 comments on commit 2f8a97c

Please sign in to comment.