mirror of https://github.com/CGAL/cgal
Shape_detection: using proper triangulated polygonal faces for linear_least_squares (#8314)
## Summary of Changes Polygonal faces are now triangulated and face normals are calculated using PMP::compute_face_normal. The calculated face normals and triangulations are buffered in Least_squares_plane_fit_region. However, Least_squares_plane_fit_sorting is independent and does not benefit from that buffered data. ## Release Management * Affected package(s): Shape_detection * Issue(s) solved (if any): fix #7992
This commit is contained in:
commit
8730ff5d55
|
|
@ -19,6 +19,9 @@
|
|||
// Internal includes.
|
||||
#include <CGAL/Shape_detection/Region_growing/internal/property_map.h>
|
||||
#include <CGAL/Shape_detection/Region_growing/internal/utils.h>
|
||||
#ifdef CGAL_SD_RG_USE_PMP
|
||||
#include <CGAL/Polygon_mesh_processing/compute_normal.h>
|
||||
#endif
|
||||
|
||||
namespace CGAL {
|
||||
namespace Shape_detection {
|
||||
|
|
@ -83,6 +86,7 @@ namespace Polygon_mesh {
|
|||
using Point_3 = typename GeomTraits::Point_3;
|
||||
using Vector_3 = typename GeomTraits::Vector_3;
|
||||
using Plane_3 = typename GeomTraits::Plane_3;
|
||||
using Triangle_3 = typename GeomTraits::Triangle_3;
|
||||
|
||||
using Squared_length_3 = typename GeomTraits::Compute_squared_length_3;
|
||||
using Squared_distance_3 = typename GeomTraits::Compute_squared_distance_3;
|
||||
|
|
@ -156,7 +160,54 @@ namespace Polygon_mesh {
|
|||
m_squared_length_3(m_traits.compute_squared_length_3_object()),
|
||||
m_squared_distance_3(m_traits.compute_squared_distance_3_object()),
|
||||
m_scalar_product_3(m_traits.compute_scalar_product_3_object()),
|
||||
m_cross_product_3(m_traits.construct_cross_product_vector_3_object()) {
|
||||
m_cross_product_3(m_traits.construct_cross_product_vector_3_object()),
|
||||
m_face_normals( get(CGAL::dynamic_face_property_t<Vector_3>(), pmesh) ),
|
||||
m_face_triangulations( get(CGAL::dynamic_face_property_t<std::vector<Triangle_3>>(), pmesh) )
|
||||
{
|
||||
|
||||
#ifdef CGAL_SD_RG_USE_PMP
|
||||
auto get_face_normal = [this](Item face, const PolygonMesh& pmesh)
|
||||
{
|
||||
return Polygon_mesh_processing::compute_face_normal(face, pmesh, parameters::vertex_point_map(m_vertex_to_point_map));
|
||||
};
|
||||
#else
|
||||
auto get_face_normal = [this](Item face, const PolygonMesh& pmesh) -> Vector_3
|
||||
{
|
||||
const auto hedge = halfedge(face, pmesh);
|
||||
const auto vertices = vertices_around_face(hedge, pmesh);
|
||||
CGAL_precondition(vertices.size() >= 3);
|
||||
|
||||
auto vertex = vertices.begin();
|
||||
const Point_3& p1 = get(m_vertex_to_point_map, *vertex); ++vertex;
|
||||
const Point_3& p2 = get(m_vertex_to_point_map, *vertex); ++vertex;
|
||||
Point_3 p3 = get(m_vertex_to_point_map, *vertex);
|
||||
while(collinear(p1, p2, p3))
|
||||
{
|
||||
if (++vertex == vertices.end()) return NULL_VECTOR;
|
||||
p3 = get(m_vertex_to_point_map, *vertex);
|
||||
}
|
||||
|
||||
const Vector_3 u = p2 - p1;
|
||||
const Vector_3 v = p3 - p1;
|
||||
return m_cross_product_3(u, v);
|
||||
};
|
||||
#endif
|
||||
|
||||
for (const Item &i : faces(pmesh)) {
|
||||
put(m_face_normals, i, get_face_normal(i, pmesh));
|
||||
std::vector<Point_3> pts;
|
||||
auto h = halfedge(i, pmesh);
|
||||
auto s = h;
|
||||
|
||||
do {
|
||||
pts.push_back(get(m_vertex_to_point_map, target(h, pmesh)));
|
||||
h = next(h, pmesh);
|
||||
} while (h != s);
|
||||
|
||||
std::vector<Triangle_3> face_triangulation;
|
||||
internal::triangulate_face<GeomTraits>(pts, face_triangulation);
|
||||
put(m_face_triangulations, i, face_triangulation);
|
||||
}
|
||||
|
||||
CGAL_precondition(faces(m_face_graph).size() > 0);
|
||||
const FT max_distance = parameters::choose_parameter(
|
||||
|
|
@ -234,7 +285,7 @@ namespace Polygon_mesh {
|
|||
const FT squared_distance_threshold =
|
||||
m_distance_threshold * m_distance_threshold;
|
||||
|
||||
const Vector_3 face_normal = get_face_normal(query);
|
||||
const Vector_3 face_normal = get(m_face_normals, query);
|
||||
const FT cos_value = m_scalar_product_3(face_normal, m_normal_of_best_fit);
|
||||
const FT squared_cos_value = cos_value * cos_value;
|
||||
|
||||
|
|
@ -284,7 +335,7 @@ namespace Polygon_mesh {
|
|||
// The best fit plane will be a plane through this face centroid with
|
||||
// its normal being the face's normal.
|
||||
const Point_3 face_centroid = get_face_centroid(face);
|
||||
const Vector_3 face_normal = get_face_normal(face);
|
||||
const Vector_3 face_normal = get(m_face_normals, face);
|
||||
if (face_normal == CGAL::NULL_VECTOR) return false;
|
||||
|
||||
CGAL_precondition(face_normal != CGAL::NULL_VECTOR);
|
||||
|
|
@ -308,15 +359,15 @@ namespace Polygon_mesh {
|
|||
// The best fit plane will be a plane fitted to all vertices of all
|
||||
// region faces with its normal being perpendicular to the plane.
|
||||
// Given that the points, and no normals, are used in estimating
|
||||
// the plane, the estimated normal will point into an arbitray
|
||||
// the plane, the estimated normal will point into an arbitrary
|
||||
// one of the two possible directions.
|
||||
// We flip it into the correct direction (the one that the majority
|
||||
// of faces agree with) below.
|
||||
// This fix is proposed by nh2:
|
||||
// https://github.com/CGAL/cgal/pull/4563
|
||||
const Plane_3 unoriented_plane_of_best_fit =
|
||||
internal::create_plane_from_faces(
|
||||
m_face_graph, region, m_vertex_to_point_map, m_traits).first;
|
||||
internal::create_plane_from_triangulated_faces(
|
||||
region, m_face_triangulations, m_traits).first;
|
||||
const Vector_3 unoriented_normal_of_best_fit =
|
||||
unoriented_plane_of_best_fit.orthogonal_vector();
|
||||
|
||||
|
|
@ -325,7 +376,7 @@ namespace Polygon_mesh {
|
|||
// Approach: each face gets one vote to keep or flip the current plane normal.
|
||||
long votes_to_keep_normal = 0;
|
||||
for (const auto &face : region) {
|
||||
const Vector_3 face_normal = get_face_normal(face);
|
||||
const Vector_3 face_normal = get(m_face_normals, face);
|
||||
const bool agrees =
|
||||
m_scalar_product_3(face_normal, unoriented_normal_of_best_fit) > FT(0);
|
||||
votes_to_keep_normal += (agrees ? 1 : -1);
|
||||
|
|
@ -357,6 +408,9 @@ namespace Polygon_mesh {
|
|||
const Scalar_product_3 m_scalar_product_3;
|
||||
const Cross_product_3 m_cross_product_3;
|
||||
|
||||
typename boost::property_map<Face_graph, CGAL::dynamic_face_property_t<Vector_3> >::const_type m_face_normals;
|
||||
typename boost::property_map<Face_graph, CGAL::dynamic_face_property_t<std::vector<Triangle_3>> >::const_type m_face_triangulations;
|
||||
|
||||
Plane_3 m_plane_of_best_fit;
|
||||
Vector_3 m_normal_of_best_fit;
|
||||
|
||||
|
|
@ -383,25 +437,6 @@ namespace Polygon_mesh {
|
|||
return Point_3(x, y, z);
|
||||
}
|
||||
|
||||
// Compute normal of the face.
|
||||
template<typename Face>
|
||||
Vector_3 get_face_normal(const Face& face) const {
|
||||
|
||||
const auto hedge = halfedge(face, m_face_graph);
|
||||
const auto vertices = vertices_around_face(hedge, m_face_graph);
|
||||
CGAL_precondition(vertices.size() >= 3);
|
||||
|
||||
auto vertex = vertices.begin();
|
||||
const Point_3& point1 = get(m_vertex_to_point_map, *vertex); ++vertex;
|
||||
const Point_3& point2 = get(m_vertex_to_point_map, *vertex); ++vertex;
|
||||
const Point_3& point3 = get(m_vertex_to_point_map, *vertex);
|
||||
|
||||
const Vector_3 u = point2 - point1;
|
||||
const Vector_3 v = point3 - point1;
|
||||
const Vector_3 face_normal = m_cross_product_3(u, v);
|
||||
return face_normal;
|
||||
}
|
||||
|
||||
// The maximum squared distance from the vertices of the face
|
||||
// to the best fit plane.
|
||||
template<typename Face>
|
||||
|
|
|
|||
|
|
@ -46,6 +46,11 @@
|
|||
#include <CGAL/boost/iterator/counting_iterator.hpp>
|
||||
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
|
||||
#include <CGAL/Iterator_range.h>
|
||||
#ifdef CGAL_SD_RG_USE_PMP
|
||||
#include <CGAL/Polygon_mesh_processing/triangulate_hole.h>
|
||||
#else
|
||||
#include <CGAL/centroid.h>
|
||||
#endif
|
||||
|
||||
namespace CGAL {
|
||||
namespace Shape_detection {
|
||||
|
|
@ -61,7 +66,7 @@ namespace internal {
|
|||
mutable T it;
|
||||
};
|
||||
|
||||
// TODO: this should be customisable in named function parameters
|
||||
// TODO: this should be customizable in named function parameters
|
||||
template<class T, bool = CGAL::is_iterator<T>::value>
|
||||
struct hash_item {};
|
||||
|
||||
|
|
@ -329,6 +334,30 @@ namespace internal {
|
|||
return create_plane(tmp, item_map, traits);
|
||||
}
|
||||
|
||||
template <class Traits>
|
||||
void
|
||||
triangulate_face(const std::vector<typename Traits::Point_3>& points,
|
||||
std::vector<typename Traits::Triangle_3>& triangles)
|
||||
{
|
||||
#ifdef CGAL_SD_RG_USE_PMP
|
||||
std::vector<CGAL::Triple<int, int, int>> output;
|
||||
|
||||
Polygon_mesh_processing::triangulate_hole_polyline(points, std::back_inserter(output), parameters::use_2d_constrained_delaunay_triangulation(true));
|
||||
|
||||
triangles.reserve(output.size());
|
||||
for (const auto& t : output)
|
||||
triangles.emplace_back(points[t.first], points[t.second], points[t.third]);
|
||||
#else
|
||||
//use a triangulation using the centroid
|
||||
std::size_t nb_edges = points.size();
|
||||
typename Traits::Point_3 c = CGAL::centroid(points.begin(), points.end());
|
||||
triangles.reserve(nb_edges);
|
||||
for (std::size_t i=0; i<nb_edges-1; ++i)
|
||||
triangles.emplace_back(points[i], points[i+1], c);
|
||||
triangles.emplace_back(points.back(), points.front(), c);
|
||||
#endif
|
||||
}
|
||||
|
||||
template<
|
||||
typename Traits,
|
||||
typename FaceGraph,
|
||||
|
|
@ -369,14 +398,7 @@ namespace internal {
|
|||
if (points.size()==3)
|
||||
triangles.push_back(ITriangle_3(points[0], points[1], points[2]));
|
||||
else
|
||||
{
|
||||
//use a triangulation using the centroid
|
||||
std::size_t nb_edges = points.size();
|
||||
IPoint_3 c = CGAL::centroid(points.begin(), points.end());
|
||||
points.push_back(points.front());
|
||||
for (std::size_t i=0; i<nb_edges; ++i)
|
||||
triangles.push_back(ITriangle_3(points[i], points[i+1], c));
|
||||
}
|
||||
triangulate_face<ITraits>(points, triangles);
|
||||
}
|
||||
CGAL_precondition(triangles.size() >= region.size());
|
||||
IPlane_3 fitted_plane;
|
||||
|
|
@ -395,6 +417,59 @@ namespace internal {
|
|||
return std::make_pair(plane, static_cast<FT>(score));
|
||||
}
|
||||
|
||||
template<
|
||||
typename Traits,
|
||||
typename Region,
|
||||
typename FaceToTrianglesMap>
|
||||
std::pair<typename Traits::Plane_3, typename Traits::FT>
|
||||
create_plane_from_triangulated_faces(
|
||||
const Region& region,
|
||||
const FaceToTrianglesMap &face_to_triangles_map, const Traits&) {
|
||||
|
||||
using FT = typename Traits::FT;
|
||||
using Plane_3 = typename Traits::Plane_3;
|
||||
using Triangle_3 = typename Traits::Triangle_3;
|
||||
|
||||
using ITraits = CGAL::Exact_predicates_inexact_constructions_kernel;
|
||||
using IConverter = CGAL::Cartesian_converter<Traits, ITraits>;
|
||||
|
||||
using IFT = typename ITraits::FT;
|
||||
using IPoint_3 = typename ITraits::Point_3;
|
||||
using ITriangle_3 = typename ITraits::Triangle_3;
|
||||
using IPlane_3 = typename ITraits::Plane_3;
|
||||
|
||||
std::vector<ITriangle_3> triangles;
|
||||
CGAL_precondition(region.size() > 0);
|
||||
triangles.reserve(region.size());
|
||||
const IConverter iconverter = IConverter();
|
||||
|
||||
for (const typename Region::value_type face : region) {
|
||||
const std::vector<Triangle_3>& tris = get(face_to_triangles_map, face);
|
||||
|
||||
// Degenerate polygons are omitted.
|
||||
if (tris.empty())
|
||||
continue;
|
||||
|
||||
for (const auto &tri : tris)
|
||||
triangles.push_back(iconverter(tri));
|
||||
}
|
||||
CGAL_precondition(!triangles.empty());
|
||||
IPlane_3 fitted_plane;
|
||||
IPoint_3 fitted_centroid;
|
||||
const IFT score = CGAL::linear_least_squares_fitting_3(
|
||||
triangles.begin(), triangles.end(),
|
||||
fitted_plane, fitted_centroid,
|
||||
CGAL::Dimension_tag<2>(), ITraits(),
|
||||
CGAL::Eigen_diagonalize_traits<IFT, 3>());
|
||||
|
||||
const Plane_3 plane(
|
||||
static_cast<FT>(fitted_plane.a()),
|
||||
static_cast<FT>(fitted_plane.b()),
|
||||
static_cast<FT>(fitted_plane.c()),
|
||||
static_cast<FT>(fitted_plane.d()));
|
||||
return std::make_pair(plane, static_cast<FT>(score));
|
||||
}
|
||||
|
||||
template<
|
||||
typename Traits,
|
||||
typename Region,
|
||||
|
|
|
|||
Loading…
Reference in New Issue