remove region growing on polylines

not being able to share vertices does not really
make sense for a polyline. Segment_set should
be used instead
This commit is contained in:
Sébastien Loriot 2022-07-19 17:33:04 +02:00
parent 2c1a0fddd7
commit 367f3805ad
19 changed files with 2 additions and 1406 deletions

View File

@ -10,7 +10,6 @@ to access neighbors of an item.
- `CGAL::Shape_detection::Point_set::Sphere_neighbor_query`
- `CGAL::Shape_detection::Polygon_mesh::Polyline_graph`
- `CGAL::Shape_detection::Polygon_mesh::One_ring_neighbor_query`
- `CGAL::Shape_detection::Polyline::One_ring_neighbor_query`
*/
class NeighborQuery {

View File

@ -15,7 +15,6 @@ A region is represented by a set items, which are included in this region.
- `CGAL::Shape_detection::Point_set::Least_squares_cylinder_fit_region`
- `CGAL::Shape_detection::Segment_set::Least_squares_line_fit_region`
- `CGAL::Shape_detection::Polygon_mesh::Least_squares_plane_fit_region`
- `CGAL::Shape_detection::Polyline::Least_squares_line_fit_region`
*/
class RegionType {

View File

@ -29,12 +29,6 @@ for shape detection in a segment set.
Models that can be used with the `CGAL::Shape_detection::Region_growing`
for shape detection on a polygon mesh.
\defgroup PkgShapeDetectionRGOnPolyline Polyline
\ingroup PkgShapeDetectionRG
Models that can be used with the `CGAL::Shape_detection::Region_growing`
for shape detection on a polyline.
\addtogroup PkgShapeDetectionRG
\defgroup PkgShapeDetectionRANSAC Efficient RANSAC
@ -142,9 +136,4 @@ and the Region Growing approach for detecting shapes in a set of arbitrary items
- `CGAL::Shape_detection::Polygon_mesh::Least_squares_plane_fit_region<GeomTraits, PolygonMesh, FaceRange, VertexToPointMap>`
- `CGAL::Shape_detection::Polygon_mesh::Least_squares_plane_fit_sorting<GeomTraits, PolygonMesh, %NeighborQuery, FaceRange, VertexToPointMap>`
### Polyline ###
- `CGAL::Shape_detection::Polyline::One_ring_neighbor_query<GeomTraits, InputRange>`
- `CGAL::Shape_detection::Polyline::Least_squares_line_fit_region<GeomTraits, InputRange, PointMap>`
- `CGAL::Shape_detection::Polyline::Least_squares_line_fit_sorting<GeomTraits, InputRange, %NeighborQuery, PointMap>`
*/

View File

@ -239,7 +239,6 @@ Together with the generic algorithm's implementation `CGAL::Shape_detection::Reg
- Line and circle detection in a \ref Shape_detection_RegionGrowingPoints "2D point set";
- Line detection in a \ref Shape_detection_RegionGrowingSegments "2D/3D segment set";
- Line detection on a \ref Shape_detection_RegionGrowingPolyline "2D/3D polyline";
- Plane, sphere, and cylinder detection in a \ref Shape_detection_RegionGrowingPoints "3D point set";
- Plane detection on a \ref Shape_detection_RegionGrowingMesh "polygon mesh".
@ -616,33 +615,6 @@ More details are explained in
Section \ref Shape_detection_RegionGrowingFramework_conditions "Framework Regions".
The right choice of these parameters is important for producing the good results.
\subsection Shape_detection_RegionGrowingPolyline Polyline
\cgalFigureBegin{Region_growing_on_polyline, Region_growing/region_growing_on_polyline.png}
A 3D polyline depicted with one color per detected line.
\cgalFigureEnd
If one wants to detect lines along a 2D or 3D polyline, one can use the
- `CGAL::Shape_detection::Polyline::Least_squares_line_fit_region` class that fits a 2D or 3D line
to the chunks of polyline vertices, respectively, and controls the quality of this fit.
As before, one can improve the quality of the region growing by using the class
- `CGAL::Shape_detection::Polyline::Least_squares_line_fit_sorting` - the input vertices are sorted with respect
to the quality of the least squares line fit applied to the neighbors of each vertex.
\subsubsection Shape_detection_RegionGrowingPolyline_parameters Parameters
The line fitting class above depends on three parameters:
- `maximum_distance` - the maximum distance from the polyline vertex to a line;
- `maximum_angle` - the maximum angle in degrees between the polyline edge direction and the direction of a line;
- `minimum_region_size` - the minimum number of vertices a region must have.
As already mentioned, the right choice of these parameters is important for producing the good results.
\section Shape_detection_Comparison Comparison
The Efficient RANSAC algorithm is very quick, however, since it is not deterministic, some small shapes might be missed in the detection process.
@ -699,7 +671,7 @@ with the help of Clément Jamin and under the supervision of Pierre Alliez.
The region growing algorithm on a 3D point set was first implemented by Simon Giraudot based on the prototype version developed by Florent Lafarge
and then generalized to arbitrary items including versions for a 2D point set, a 3D point set, and a polygon mesh by Thien Hoang during the
Google Summer of Code 2018 under the supervision of Dmitry Anisimov. The versions for segments and polylines were added later by Dmitry Anisimov.
Google Summer of Code 2018 under the supervision of Dmitry Anisimov. The version for segments was added later by Dmitry Anisimov.
\section Shape_detection_Acknowledgments Acknowledgments

View File

@ -13,5 +13,4 @@
\example Shape_detection/region_growing_cylinders_on_point_set_3.cpp
\example Shape_detection/region_growing_planes_on_polygon_mesh.cpp
\example Shape_detection/region_growing_lines_on_segment_set.cpp
\example Shape_detection/region_growing_lines_on_polyline.cpp
*/

Binary file not shown.

Before

Width:  |  Height:  |  Size: 10 KiB

View File

@ -22,7 +22,6 @@ if(TARGET CGAL::Eigen3_support)
create_single_source_cgal_program("region_growing_cylinders_on_point_set_3.cpp")
create_single_source_cgal_program("region_growing_planes_on_polygon_mesh.cpp")
create_single_source_cgal_program("region_growing_lines_on_segment_set.cpp")
create_single_source_cgal_program("region_growing_lines_on_polyline.cpp")
foreach(
target
@ -35,8 +34,7 @@ if(TARGET CGAL::Eigen3_support)
region_growing_spheres_on_point_set_3
region_growing_cylinders_on_point_set_3
region_growing_planes_on_polygon_mesh
region_growing_lines_on_segment_set
region_growing_lines_on_polyline)
region_growing_lines_on_segment_set)
target_link_libraries(${target} PUBLIC CGAL::Eigen3_support)
endforeach()

View File

@ -1,121 +0,0 @@
#include "include/utils.h"
#include <CGAL/Simple_cartesian.h>
#include <CGAL/Shape_detection/Region_growing/Region_growing.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
// Typedefs.
using Kernel = CGAL::Simple_cartesian<double>;
using FT = typename Kernel::FT;
using Point_2 = typename Kernel::Point_2;
using Point_3 = typename Kernel::Point_3;
using Plane_3 = typename Kernel::Plane_3;
using Polyline_2 = std::vector<Point_2>;
using Polyline_3 = std::vector<Point_3>;
using Point_map_2 = CGAL::Identity_property_map<Point_2>;
using Point_map_3 = CGAL::Identity_property_map<Point_3>;
using Neighbor_query_2 = CGAL::Shape_detection::Polyline::One_ring_neighbor_query<Kernel, Polyline_2>;
using Region_type_2 = CGAL::Shape_detection::Polyline::Least_squares_line_fit_region<Kernel, Polyline_2, Point_map_2>;
using Region_growing_2 = CGAL::Shape_detection::Region_growing<Neighbor_query_2, Region_type_2>;
using Neighbor_query_3 = CGAL::Shape_detection::Polyline::One_ring_neighbor_query<Kernel, Polyline_3>;
using Region_type_3 = CGAL::Shape_detection::Polyline::Least_squares_line_fit_region<Kernel, Polyline_3, Point_map_3>;
using Region_growing_3 = CGAL::Shape_detection::Region_growing<Neighbor_query_3, Region_type_3>;
int main(int argc, char *argv[]) {
// Load polyline data either from a local folder or a user-provided file.
const bool is_default_input = argc > 1 ? false : true;
std::ifstream in(is_default_input ? CGAL::data_file_path("polylines_3/wavy_circle.polylines.txt") : argv[1]);
CGAL::IO::set_ascii_mode(in);
if (!in) {
std::cerr << "ERROR: cannot read the input file!" << std::endl;
return EXIT_FAILURE;
}
Polyline_3 polyline_3;
std::size_t n = std::size_t(-1);
in >> n;
polyline_3.reserve(n);
while (n--) {
Point_3 point; in >> point;
polyline_3.push_back(point);
if (!in.good()) {
std::cout << "ERROR: cannot load a polyline!" << std::endl;
return EXIT_FAILURE;
}
}
in.close();
std::cout << "* number of input vertices: " << polyline_3.size() << std::endl;
assert(is_default_input && polyline_3.size() == 249);
// Default parameter values for the data file wavy_circle.polylines.txt.
const FT max_distance = FT(45) / FT(10);
const FT max_angle = FT(45);
// Setting up the 3D polyline algorithm.
Neighbor_query_3 neighbor_query_3(polyline_3);
Region_type_3 region_type_3(
polyline_3,
CGAL::parameters::
maximum_distance(max_distance).
maximum_angle(max_angle));
Region_growing_3 region_growing_3(
polyline_3, neighbor_query_3, region_type_3);
// Run the algorithm on a 3D polyline.
std::vector<typename Region_growing_3::Primitive_and_region> regions;
region_growing_3.detect(std::back_inserter(regions));
std::cout << "* number of found 3D regions: " << regions.size() << std::endl;
assert(is_default_input && regions.size() == 17);
// Save 3D regions to a file.
std::string fullpath = (argc > 2 ? argv[2] : "regions_polyline_3.ply");
utils::save_point_regions_3<Kernel, std::vector<typename Region_growing_3::Primitive_and_region>, Point_map_3>(
regions, fullpath);
// Create the 2D polyline.
Plane_3 plane; Point_3 centroid;
CGAL::linear_least_squares_fitting_3(
polyline_3.begin(), polyline_3.end(), plane, centroid,
CGAL::Dimension_tag<0>(), Kernel(),
CGAL::Eigen_diagonalize_traits<FT, 3>());
Polyline_2 polyline_2;
polyline_2.reserve(polyline_3.size());
for (const auto& point : polyline_3) {
const auto p3 = plane.projection(point);
const auto p2 = plane.to_2d(p3);
polyline_2.push_back(p2);
}
assert(is_default_input && polyline_2.size() == polyline_3.size());
// Setting up the 2D polyline algorithm.
Neighbor_query_2 neighbor_query_2(polyline_2);
Region_type_2 region_type_2(
polyline_2,
CGAL::parameters::
maximum_distance(max_distance).
maximum_angle(max_angle));
Region_growing_2 region_growing_2(
polyline_2, neighbor_query_2, region_type_2);
// Run the algorithm on a 2D polyline.
std::vector<typename Region_growing_2::Primitive_and_region> regions2;
region_growing_2.detect(std::back_inserter(regions2));
std::cout << "* number of found 2D regions: " << regions2.size() << std::endl;
assert(is_default_input && regions2.size() == 5);
// Save 2D regions to a file.
polyline_3.clear();
for (const auto& p2 : polyline_2) {
polyline_3.push_back(plane.to_3d(p2));
}
fullpath = (argc > 2 ? argv[2] : "regions_polyline_2.ply");
utils::save_point_regions_2<Kernel, std::vector<typename Region_growing_2::Primitive_and_region>, Point_map_2>(
regions2, fullpath);
return EXIT_SUCCESS;
}

View File

@ -28,6 +28,5 @@
#include <CGAL/Shape_detection/Region_growing/Point_set.h>
#include <CGAL/Shape_detection/Region_growing/Segment_set.h>
#include <CGAL/Shape_detection/Region_growing/Polygon_mesh.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
#endif // CGAL_SHAPE_DETECTION_REGION_GROWING_HEADERS_H

View File

@ -1,31 +0,0 @@
// Copyright (c) 2020 GeometryFactory SARL (France).
// All rights reserved.
//
// This file is part of CGAL (www.cgal.org).
//
// $URL$
// $Id$
// SPDX-License-Identifier: GPL-3.0-or-later OR LicenseRef-Commercial
//
//
// Author(s) : Dmitry Anisimov
//
#ifndef CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_H
#define CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_H
/// \cond SKIP_IN_MANUAL
#include <CGAL/license/Shape_detection.h>
/// \endcond
/**
* \ingroup PkgShapeDetectionRef
* \file CGAL/Shape_detection/Region_growing/Polyline.h
* A convenience header that includes all classes related to the region growing algorithm on a polyline.
*/
#include <CGAL/Shape_detection/Region_growing/Polyline/One_ring_neighbor_query.h>
#include <CGAL/Shape_detection/Region_growing/Polyline/Least_squares_line_fit_region.h>
#include <CGAL/Shape_detection/Region_growing/Polyline/Least_squares_line_fit_sorting.h>
#endif // CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_H

View File

@ -1,369 +0,0 @@
// Copyright (c) 2020 GeometryFactory SARL (France).
// All rights reserved.
//
// This file is part of CGAL (www.cgal.org).
//
// $URL$
// $Id$
// SPDX-License-Identifier: GPL-3.0-or-later OR LicenseRef-Commercial
//
//
// Author(s) : Dmitry Anisimov
//
#ifndef CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_REGION_H
#define CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_REGION_H
#include <CGAL/license/Shape_detection.h>
// Boost includes.
#include <boost/unordered_map.hpp>
// Internal includes.
#include <CGAL/Shape_detection/Region_growing/internal/region_growing_traits.h>
#include <CGAL/use.h>
namespace CGAL {
namespace Shape_detection {
namespace Polyline {
/*!
\ingroup PkgShapeDetectionRGOnPolyline
\brief Region type based on the quality of the least squares line
fit applied to the vertices of a polyline.
This class fits a line, using \ref PkgPrincipalComponentAnalysisDRef "PCA",
to chunks of polyline vertices and controls the quality of this fit.
If all quality conditions are satisfied, the chunk is accepted as a valid region,
otherwise rejected.
\tparam GeomTraits
a model of `Kernel`
\tparam InputRange
a model of `ConstRange` whose iterator type is `RandomAccessIterator`
\tparam PointMap
a model of `ReadablePropertyMap` whose key type is the value type of the input
range and value type is `Kernel::Point_2` or `Kernel::Point_3`
\cgalModels `RegionType`
*/
template<
typename GeomTraits,
typename InputRange,
typename PointMap>
class Least_squares_line_fit_region {
private:
using Polyline_traits = typename std::conditional<
std::is_same<typename GeomTraits::Point_2, typename PointMap::value_type>::value,
internal::Region_growing_traits_2<GeomTraits>,
internal::Region_growing_traits_3<GeomTraits> >::type;
public:
/// \name Types
/// @{
/// \cond SKIP_IN_MANUAL
using Traits = GeomTraits;
using Input_range = InputRange;
using Point_map = PointMap;
using Point_type = typename Point_map::value_type;
/// \endcond
/// Item type.
using Item = typename InputRange::const_iterator;
using Region = std::vector<Item>;
/// Number type.
typedef typename GeomTraits::FT FT;
/// Primitive type depends on the dimension of the input data.
#ifdef DOXYGEN_RUNNING
using Primitive = typename GeomTraits::Line_2 or typename GeomTraits::Line_3
#else
using Primitive = typename Polyline_traits::Line;
#endif
/// Region map
using Region_unordered_map = boost::unordered_map<Item, std::size_t, internal::hash_item<Item> >;
using Region_index_map = boost::associative_property_map<Region_unordered_map>;
/// @}
private:
using Point = typename Polyline_traits::Point;
using Vector = typename Polyline_traits::Vector;
using Line = typename Polyline_traits::Line;
using Squared_length = typename Polyline_traits::Compute_squared_length;
using Squared_distance = typename Polyline_traits::Compute_squared_distance;
using Scalar_product = typename Polyline_traits::Compute_scalar_product;
public:
/// \name Initialization
/// @{
/*!
\brief initializes all internal data structures.
\tparam NamedParameters
a sequence of \ref bgl_namedparameters "Named Parameters"
\param input_range
an instance of `InputRange` with polyline vertices
\param np
a sequence of \ref bgl_namedparameters "Named Parameters"
among the ones listed below
\cgalNamedParamsBegin
\cgalParamNBegin{maximum_distance}
\cgalParamDescription{the maximum distance from a vertex to a line}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{1}
\cgalParamNEnd
\cgalParamNBegin{maximum_angle}
\cgalParamDescription{the maximum angle in degrees between
the direction of a polyline edge and the direction of a line}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{25 degrees}
\cgalParamNEnd
\cgalParamNBegin{cosine_value}
\cgalParamDescription{the cos value computed as `cos(maximum_angle * PI / 180)`,
this parameter can be used instead of the `maximum_angle`}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{`cos(25 * PI / 180)`}
\cgalParamNEnd
\cgalParamNBegin{minimum_region_size}
\cgalParamDescription{the minimum number of vertices a region must have}
\cgalParamType{`std::size_t`}
\cgalParamDefault{2}
\cgalParamNEnd
\cgalParamNBegin{point_map}
\cgalParamDescription{an instance of `PointMap` that maps an item from `input_range`
to `Kernel::Point_2` or `Kernel::Point_3`}
\cgalParamDefault{`PointMap()`}
\cgalParamNEnd
\cgalParamNBegin{geom_traits}
\cgalParamDescription{an instance of `GeomTraits`}
\cgalParamDefault{`GeomTraits()`}
\cgalParamNEnd
\cgalNamedParamsEnd
\pre `input_range.size() > 0`
\pre `maximum_distance >= 0`
\pre `maximum_angle >= 0 && maximum_angle <= 90`
\pre `cosine_value >= 0 && cosine_value <= 1`
\pre `minimum_region_size > 0`
*/
template<typename NamedParameters = parameters::Default_named_parameters>
Least_squares_line_fit_region(
const InputRange& input_range,
const NamedParameters& np = parameters::default_values()) :
m_point_map(parameters::choose_parameter(parameters::get_parameter(
np, internal_np::point_map), PointMap())),
m_traits(parameters::choose_parameter(parameters::get_parameter(
np, internal_np::geom_traits), GeomTraits())),
m_polyline_traits(m_traits),
m_squared_length(m_polyline_traits.compute_squared_length_object()),
m_squared_distance(m_polyline_traits.compute_squared_distance_object()),
m_scalar_product(m_polyline_traits.compute_scalar_product_object()) {
CGAL_precondition(input_range.size() > 0);
const FT max_distance = parameters::choose_parameter(
parameters::get_parameter(np, internal_np::maximum_distance), FT(1));
CGAL_precondition(max_distance >= FT(0));
m_distance_threshold = max_distance;
const FT max_angle = parameters::choose_parameter(
parameters::get_parameter(np, internal_np::maximum_angle), FT(25));
CGAL_precondition(max_angle >= FT(0) && max_angle <= FT(90));
m_min_region_size = parameters::choose_parameter(
parameters::get_parameter(np, internal_np::minimum_region_size), 2);
CGAL_precondition(m_min_region_size > 0);
const FT default_cos_value = static_cast<FT>(std::cos(CGAL::to_double(
(max_angle * static_cast<FT>(CGAL_PI)) / FT(180))));
const FT cos_value = parameters::choose_parameter(
parameters::get_parameter(np, internal_np::cosine_value), default_cos_value);
CGAL_precondition(cos_value >= FT(0) && cos_value <= FT(1));
m_cos_value_threshold = cos_value;
}
/// @}
/// \name Access
/// @{
/*!
\brief implements `RegionType::region_index_map()`.
This function creates an empty property map that maps iterators on the input range `Item` to std::size_t
*/
Region_index_map region_index_map() {
return Region_index_map(m_region_map);
}
/*!
\brief implements `RegionType::primitive()`.
This function provides the last primitive that has been fitted with the region.
\return Primitive parameters that fits the region
\pre `successful fitted primitive via successful call of update(region) with a sufficient large region`
*/
Primitive primitive() const {
return m_line_of_best_fit;
}
/*!
\brief implements `RegionType::is_part_of_region()`.
This function controls if a vertex with the item `query` is within
the `maximum_distance` from the corresponding line and if the angle between the
direction of the inward edge and the line's direction is within the `maximum_angle`.
If both conditions are satisfied, it returns `true`, otherwise `false`.
\param previous
`Item` of the previous vertex
\param query
`Item` of the query vertex
\return Boolean `true` or `false`
\pre `region.size() > 0`
\pre `previous` is a valid const_iterator of the input_range.
\pre `query` is a valid const_iterator of the input_range.
*/
bool is_part_of_region(
const Item previous, const Item query,
const Region&) {
const Point& input_point = get(m_point_map, *previous);
const Point& query_point = get(m_point_map, *query);
// Update new reference line and direction.
if (m_direction_of_best_fit == CGAL::NULL_VECTOR) {
if (input_point == query_point) return true;
CGAL_precondition(input_point != query_point);
m_line_of_best_fit = Line(input_point, query_point);
m_direction_of_best_fit = m_line_of_best_fit.to_vector();
return true;
}
CGAL_precondition(m_direction_of_best_fit != CGAL::NULL_VECTOR);
// Add equal points to the previously defined region.
if (input_point == query_point) return true;
CGAL_precondition(input_point != query_point);
const Vector query_direction(input_point, query_point);
// Check real conditions.
const FT squared_distance_to_fitted_line =
m_squared_distance(query_point, m_line_of_best_fit);
const FT squared_distance_threshold =
m_distance_threshold * m_distance_threshold;
const FT cos_value =
m_scalar_product(query_direction, m_direction_of_best_fit);
const FT squared_cos_value = cos_value * cos_value;
FT squared_cos_value_threshold =
m_cos_value_threshold * m_cos_value_threshold;
squared_cos_value_threshold *= m_squared_length(query_direction);
squared_cos_value_threshold *= m_squared_length(m_direction_of_best_fit);
return (
( squared_distance_to_fitted_line <= squared_distance_threshold ) &&
( squared_cos_value >= squared_cos_value_threshold ));
}
/*!
\brief implements `RegionType::is_valid_region()`.
This function controls if the `region` contains at least `minimum_region_size` vertices.
\param region
Vertices of the region represented as `Items`.
\return Boolean `true` or `false`
*/
inline bool is_valid_region(const Region& region) const {
if (m_direction_of_best_fit == CGAL::NULL_VECTOR)
return false; // all points are equal
return (region.size() >= m_min_region_size);
}
/*!
\brief implements `RegionType::update()`.
This function fits the least squares line to all vertices from the `region`.
\param region
Vertices of the region represented as `Items`.
\return Boolean `true` if the line fitting succeeded and `false` otherwise
\pre `region.size() > 0`
*/
bool update(const Region& region) {
CGAL_precondition(region.size() > 0);
if (region.size() == 1) { // create new reference line and direction
m_direction_of_best_fit = CGAL::NULL_VECTOR;
} else { // update reference line and direction
if (m_direction_of_best_fit == CGAL::NULL_VECTOR)
return false; // all points are equal
CGAL_precondition(region.size() >= 2);
std::tie(m_line_of_best_fit, m_direction_of_best_fit) =
get_line_and_direction(region);
}
return true;
}
/// @}
/// \cond SKIP_IN_MANUAL
std::pair<Line, Vector> get_line_and_direction(
const Region& region) const {
// The best fit line will be a line fitted to all region points with
// its direction being the line's direction.
CGAL_precondition(region.size() > 0);
const Line line_of_best_fit =
m_polyline_traits.create_line(
region, m_point_map).first;
const Vector direction_of_best_fit =
line_of_best_fit.to_vector();
return std::make_pair(line_of_best_fit, direction_of_best_fit);
}
/// \endcond
private:
const Point_map m_point_map;
const Traits m_traits;
const Polyline_traits m_polyline_traits;
Region_unordered_map m_region_map;
FT m_distance_threshold;
FT m_cos_value_threshold;
std::size_t m_min_region_size;
const Squared_length m_squared_length;
const Squared_distance m_squared_distance;
const Scalar_product m_scalar_product;
Line m_line_of_best_fit;
Vector m_direction_of_best_fit;
};
} // namespace Polyline
} // namespace Shape_detection
} // namespace CGAL
#endif // CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_REGION_H

View File

@ -1,205 +0,0 @@
// Copyright (c) 2020 GeometryFactory SARL (France).
// All rights reserved.
//
// This file is part of CGAL (www.cgal.org).
//
// $URL$
// $Id$
// SPDX-License-Identifier: GPL-3.0-or-later OR LicenseRef-Commercial
//
//
// Author(s) : Dmitry Anisimov
//
#ifndef CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_SORTING_H
#define CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_SORTING_H
#include <CGAL/license/Shape_detection.h>
// Internal includes.
#include <CGAL/Shape_detection/Region_growing/internal/property_map.h>
namespace CGAL {
namespace Shape_detection {
namespace Polyline {
/*!
\ingroup PkgShapeDetectionRGOnPolyline
\brief Sorting of polyline vertices with respect to the local line fit quality.
`Items` of input vertices are sorted with respect to the quality of the
least squares line fit applied to the incident vertices of each vertex.
\tparam GeomTraits
a model of `Kernel`
\tparam InputRange
a model of `ConstRange` whose iterator type is `RandomAccessIterator`
\tparam NeighborQuery
a model of `NeighborQuery`
\tparam PointMap
a model of `ReadablePropertyMap` whose key type is the value type of the input
range and value type is `Kernel::Point_2` or `Kernel::Point_3`
*/
template<
typename GeomTraits,
typename InputRange,
typename NeighborQuery,
typename PointMap>
class Least_squares_line_fit_sorting {
public:
/// \name Types
/// @{
/// \cond SKIP_IN_MANUAL
using Input_range = InputRange;
using Neighbor_query = NeighborQuery;
using Point_map = PointMap;
using Point_type = typename Point_map::value_type;
/// \endcond
/// Item type.
using Item = typename InputRange::const_iterator;
/// Seed range.
using Seed_range = std::vector<Item>;
/// @}
private:
using FT = typename GeomTraits::FT;
using Polyline_traits = typename std::conditional<
std::is_same<typename GeomTraits::Point_2, Point_type>::value,
internal::Region_growing_traits_2<GeomTraits>,
internal::Region_growing_traits_3<GeomTraits> >::type;
using Compare_scores = internal::Compare_scores<FT>;
using Dereference_pmap = internal::Dereference_property_map_adaptor<Item, PointMap>;
public:
/// \name Initialization
/// @{
/*!
\brief initializes all internal data structures.
\tparam NamedParameters
a sequence of \ref bgl_namedparameters "Named Parameters"
\param input_range
an instance of `InputRange` with polyline vertices
\param neighbor_query
an instance of `NeighborQuery` that is used internally to
access vertex's neighbors
\param np
a sequence of \ref bgl_namedparameters "Named Parameters"
among the ones listed below
\cgalNamedParamsBegin
\cgalParamNBegin{point_map}
\cgalParamDescription{an instance of `PointMap` that maps a vertex from `input_range`
to `Kernel::Point_2` or `Kernel::Point_3`}
\cgalParamDefault{`PointMap()`}
\cgalParamNEnd
\cgalParamNBegin{geom_traits}
\cgalParamDescription{an instance of `GeomTraits`}
\cgalParamDefault{`GeomTraits()`}
\cgalParamNEnd
\cgalNamedParamsEnd
\pre `input_range.size() > 0`
*/
template<typename NamedParameters = parameters::Default_named_parameters>
Least_squares_line_fit_sorting(
const InputRange& input_range,
NeighborQuery& neighbor_query,
const NamedParameters& np = parameters::default_values()) :
m_neighbor_query(neighbor_query),
m_point_map(parameters::choose_parameter(parameters::get_parameter(
np, internal_np::point_map), PointMap())),
m_deref_pmap(m_point_map),
m_traits(parameters::choose_parameter(parameters::get_parameter(
np, internal_np::geom_traits), GeomTraits())),
m_polyline_traits(m_traits) {
CGAL_precondition(input_range.size() > 0);
m_ordered.resize(input_range.size());
std::size_t index = 0;
for (auto it = input_range.begin(); it != input_range.end(); it++)
m_ordered[index++] = it;
m_scores.resize(input_range.size());
}
/// @}
/// \name Sorting
/// @{
/*!
\brief sorts `Items` of input vertices.
*/
void sort() {
compute_scores();
CGAL_precondition(m_scores.size() > 0);
Compare_scores cmp(m_scores);
std::vector<std::size_t> order(m_ordered.size());
std::iota(order.begin(), order.end(), 0);
std::sort(order.begin(), order.end(), cmp);
std::vector<Item> tmp(m_ordered.size());
for (std::size_t i = 0; i < m_ordered.size(); i++)
tmp[i] = m_ordered[order[i]];
m_ordered.swap(tmp);
}
/// @}
/// \name Access
/// @{
/*!
\brief returns an instance of `Seed_range` to access the ordered `Items`
of input points.
*/
const Seed_range& ordered() {
return m_ordered;
}
/// @}
private:
Neighbor_query& m_neighbor_query;
const Point_map m_point_map;
Dereference_pmap m_deref_pmap;
const GeomTraits m_traits;
const Polyline_traits m_polyline_traits;
Seed_range m_ordered;
std::vector<FT> m_scores;
void compute_scores() {
std::vector<Item> neighbors;
std::size_t idx = 0;
for (const Item& item : m_ordered) {
neighbors.clear();
m_neighbor_query(item, neighbors);
neighbors.push_back(item);
m_scores[idx++] = m_polyline_traits.create_line(
neighbors, m_point_map).second;
}
}
};
} // namespace Polyline
} // namespace Shape_detection
} // namespace CGAL
#endif // #define CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_LEAST_SQUARES_LINE_FIT_SORTING_H

View File

@ -1,130 +0,0 @@
// Copyright (c) 2020 GeometryFactory SARL (France).
// All rights reserved.
//
// This file is part of CGAL (www.cgal.org).
//
// $URL$
// $Id$
// SPDX-License-Identifier: GPL-3.0-or-later OR LicenseRef-Commercial
//
//
// Author(s) : Dmitry Anisimov
//
#ifndef CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_ONE_RING_NEIGHBOR_QUERY_H
#define CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_ONE_RING_NEIGHBOR_QUERY_H
#include <CGAL/license/Shape_detection.h>
// STL includes.
#include <vector>
// CGAL includes.
#include <CGAL/assertions.h>
namespace CGAL {
namespace Shape_detection {
namespace Polyline {
/*!
\ingroup PkgShapeDetectionRGOnPolyline
\brief Direct neighbors connectivity in a polyline.
This class returns `Items` of the previous and next vertex
in a polyline given as `InputRange.`
\tparam GeomTraits
a model of `Kernel`
\tparam InputRange
a model of `ConstRange` whose iterator type is `RandomAccessIterator`
\cgalModels `NeighborQuery`
*/
template<
typename GeomTraits,
typename InputRange>
class One_ring_neighbor_query {
public:
/// \cond SKIP_IN_MANUAL
using Traits = GeomTraits;
using Input_range = InputRange;
/// \endcond
/// Item type.
using Item = typename InputRange::const_iterator;
using Region = std::vector<Item>;
/// \name Initialization
/// @{
/*!
\brief initializes all internal data structures.
\param input_range
an instance of `InputRange` with polyline vertices
\pre `input_range.size() > 0`
*/
One_ring_neighbor_query(
const InputRange& input_range) :
m_begin(input_range.begin()) ,
m_end(input_range.end())
{
CGAL_precondition(input_range.size() > 0);
}
/// @}
/// \name Access
/// @{
/*!
\brief implements `NeighborQuery::operator()()`.
This operator retrieves the previous and next vertex in a polyline
with respect to the vertex `query`.
The `Items` are returned in `neighbors`.
\param query
`Item` of the query point
\param neighbors
`Items` of vertices, which are direct neighbors of the query point
\pre `query_index < input_range.size()`
*/
void operator()(
const Item query,
std::vector<Item>& neighbors) const {
neighbors.clear();
Item before;
if (query == m_begin)
before = std::prev(m_end);
else
before = query - 1;
Item after = query + 1;
if (after == m_end)
after = m_begin;
neighbors.push_back(before);
neighbors.push_back(after);
}
/// @}
private:
Item m_begin, m_end;
};
} // namespace Polyline
} // namespace Shape_detection
} // namespace CGAL
#endif // CGAL_SHAPE_DETECTION_REGION_GROWING_POLYLINE_ONE_RING_NEIGHBOR_QUERY_H

View File

@ -19,7 +19,6 @@
#include <CGAL/Shape_detection/Region_growing/Region_growing.h>
#include <CGAL/Shape_detection/Region_growing/Point_set.h>
#include <CGAL/Shape_detection/Region_growing/Polygon_mesh.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
#include <CGAL/Shape_detection/Region_growing/Segment_set.h>
namespace CGAL {
@ -276,82 +275,6 @@ OutputIterator region_growing_planes_polygon_mesh(
return regions;
}
/*!
\ingroup PkgShapeDetectionRG
helper function to facilitate region growing for line detection on point sets.
@tparam InputRange
a model of `ConstRange` representing a polyline.
@tparam OutputIterator a model of `OutputIterator` accepting a `std::pair<Kernel::Line_2, std::vector<InputRange::const_iterator> >` or `std::pair<Kernel::Line_3, std::vector<InputRange::const_iterator> >`.
@tparam NamedParameters a sequence of \ref bgl_namedparameters "Named Parameters"
@param polyline input point range for region growing.
@param regions output iterator to store the detected regions and fitted lines.
@param np an optional sequence of \ref bgl_namedparameters "Named Parameters" among the ones listed below
\cgalNamedParamsBegin
\cgalParamNBegin{maximum_distance}
\cgalParamDescription{the maximum distance from a vertex to a line}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{1}
\cgalParamNEnd
\cgalParamNBegin{maximum_angle}
\cgalParamDescription{the maximum angle in degrees between
the direction of a polyline edge and the direction of a line}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{25 degrees}
\cgalParamNEnd
\cgalParamNBegin{cosine_value}
\cgalParamDescription{the cos value computed as `cos(maximum_angle * PI / 180)`,
this parameter can be used instead of the `maximum_angle`}
\cgalParamType{`GeomTraits::FT`}
\cgalParamDefault{`cos(25 * PI / 180)`}
\cgalParamNEnd
\cgalParamNBegin{minimum_region_size}
\cgalParamDescription{the minimum number of vertices a region must have}
\cgalParamType{`std::size_t`}
\cgalParamDefault{2}
\cgalParamNEnd
\cgalParamNBegin{point_map}
\cgalParamDescription{an instance of `PointMap` that maps an item from `input_range`
to `Kernel::Point_2` or `Kernel::Point_3`}
\cgalParamDefault{`PointMap()`}
\cgalParamNEnd
\cgalParamNBegin{geom_traits}
\cgalParamDescription{an instance of `GeomTraits`}
\cgalParamDefault{`GeomTraits()`}
\cgalParamNEnd
\cgalNamedParamsEnd
*/
template<
typename InputRange,
typename OutputIterator,
typename CGAL_NP_TEMPLATE_PARAMETERS>
OutputIterator region_growing_polylines(
const InputRange& polyline, OutputIterator regions, const CGAL_NP_CLASS& np = parameters::default_values()) {
using Point_type = typename InputRange::value_type;
using Kernel = typename Kernel_traits<Point_type>::Kernel;
using Point_map = CGAL::Identity_property_map<Point_type>;
using Neighbor_query = Polyline::One_ring_neighbor_query<Kernel, InputRange>;
using Region_type = Polyline::Least_squares_line_fit_region<Kernel, InputRange, Point_map>;
using Sorting = Polyline::Least_squares_line_fit_sorting<Kernel, InputRange, Neighbor_query, Point_map>;
using Region_growing = Region_growing<Neighbor_query, Region_type>;
Neighbor_query neighbor_query(polyline);
Region_type region_type(polyline, np);
Sorting sorting(polyline, neighbor_query, np);
sorting.sort();
Region_growing region_growing(
polyline, neighbor_query, region_type, sorting.ordered());
region_growing.detect(regions);
return regions;
}
} // namespace Shape_detection
} // namespace CGAL

View File

@ -23,24 +23,6 @@ namespace CGAL {
namespace Shape_detection {
namespace internal {
template<typename GeomTraits>
struct Polyline_graph_traits_2 {
using Segment = typename GeomTraits::Segment_2;
using Construct_segment = typename GeomTraits::Construct_segment_2;
decltype(auto) construct_segment_object() const {
return GeomTraits().construct_segment_2_object();
}
};
template<typename GeomTraits>
struct Polyline_graph_traits_3 {
using Segment = typename GeomTraits::Segment_3;
using Construct_segment = typename GeomTraits::Construct_segment_3;
decltype(auto) construct_segment_object() const {
return GeomTraits().construct_segment_3_object();
}
};
template<typename GeomTraits>
struct Region_growing_traits_2 {
using Point = typename GeomTraits::Point_2;

View File

@ -18,11 +18,9 @@ if(EIGEN3_FOUND)
create_single_source_cgal_program("test_region_growing_on_point_set_2.cpp")
create_single_source_cgal_program("test_region_growing_on_point_set_3.cpp")
create_single_source_cgal_program("test_region_growing_on_polygon_mesh.cpp")
create_single_source_cgal_program("test_region_growing_on_polyline.cpp")
create_single_source_cgal_program("test_region_growing_on_point_set_2_with_sorting.cpp")
create_single_source_cgal_program("test_region_growing_on_point_set_3_with_sorting.cpp")
create_single_source_cgal_program("test_region_growing_on_polygon_mesh_with_sorting.cpp")
create_single_source_cgal_program("test_region_growing_on_polyline_with_sorting.cpp")
create_single_source_cgal_program("test_region_growing_on_degenerated_mesh.cpp")
foreach(
target
@ -32,11 +30,9 @@ if(EIGEN3_FOUND)
test_region_growing_on_point_set_2
test_region_growing_on_point_set_3
test_region_growing_on_polygon_mesh
test_region_growing_on_polyline
test_region_growing_on_point_set_2_with_sorting
test_region_growing_on_point_set_3_with_sorting
test_region_growing_on_polygon_mesh_with_sorting
test_region_growing_on_polyline_with_sorting
test_region_growing_on_degenerated_mesh)
target_link_libraries(${target} PUBLIC CGAL::Eigen3_support)
endforeach()

View File

@ -1,158 +0,0 @@
// STL includes.
#include <string>
#include <vector>
#include <utility>
#include <fstream>
#include <iostream>
#include <iterator>
#include <cassert>
// CGAL includes.
#include <CGAL/assertions.h>
#include <CGAL/property_map.h>
#include <CGAL/Simple_cartesian.h>
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
#include <CGAL/Exact_predicates_exact_constructions_kernel.h>
#include <CGAL/Shape_detection/Region_growing/Region_growing.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
namespace SD = CGAL::Shape_detection;
template<class Kernel>
bool test_region_growing_on_polyline(int argc, char *argv[]) {
using FT = typename Kernel::FT;
using Point_2 = typename Kernel::Point_2;
using Point_3 = typename Kernel::Point_3;
using Polyline_2 = std::vector<Point_2>;
using Polyline_3 = std::vector<Point_3>;
using Point_map_2 = CGAL::Identity_property_map<Point_2>;
using Point_map_3 = CGAL::Identity_property_map<Point_3>;
using Neighbor_query_2 = SD::Polyline::One_ring_neighbor_query<Kernel, Polyline_2>;
using Region_type_2 = SD::Polyline::Least_squares_line_fit_region<Kernel, Polyline_2, Point_map_2>;
using Region_growing_2 = SD::Region_growing<Neighbor_query_2, Region_type_2>;
using Neighbor_query_3 = SD::Polyline::One_ring_neighbor_query<Kernel, Polyline_3>;
using Region_type_3 = SD::Polyline::Least_squares_line_fit_region<Kernel, Polyline_3, Point_map_3>;
using Region_growing_3 = SD::Region_growing<Neighbor_query_3, Region_type_3>;
// Default parameter values.
const FT distance_threshold = FT(45) / FT(10);
const FT angle_threshold = FT(45);
// Load data.
std::ifstream in(argc > 1 ? argv[1] : CGAL::data_file_path("polylines_3/wavy_circle.polylines.txt"));
CGAL::IO::set_ascii_mode(in);
assert(in);
// Create 3D polyline.
Polyline_3 polyline_3;
std::size_t n = std::size_t(-1);
in >> n;
polyline_3.reserve(n);
while (n--) {
Point_3 point; in >> point;
polyline_3.push_back(point);
assert(in.good());
}
in.close();
assert(polyline_3.size() == 249);
// Create 3D parameter classes.
Neighbor_query_3 neighbor_query_3(polyline_3);
Region_type_3 region_type_3(
polyline_3,
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
// Run 3D region growing.
Region_growing_3 region_growing_3(
polyline_3, neighbor_query_3, region_type_3);
std::vector<typename Region_growing_3::Primitive_and_region> regions_3;
region_growing_3.detect(std::back_inserter(regions_3));
assert(regions_3.size() == 17);
for (const auto& region : regions_3)
assert(region_type_3.is_valid_region(region.second));
std::vector<typename Region_growing_3::Item> unassigned_points;
region_growing_3.unassigned_items(polyline_3, std::back_inserter(unassigned_points));
assert(unassigned_points.size() == 0);
// Create 2D polyline.
std::vector<std::size_t> indices(polyline_3.size());
std::iota(indices.begin(), indices.end(), 0);
const auto plane = SD::internal::create_plane(
polyline_3, Point_map_3(), indices, Kernel()).first;
Polyline_2 polyline_2;
polyline_2.reserve(polyline_3.size());
for (const auto& point : polyline_3) {
const auto p3 = plane.projection(point);
const auto p2 = plane.to_2d(p3);
polyline_2.push_back(p2);
}
assert(polyline_2.size() == polyline_3.size());
// Create 2D parameter classes.
Neighbor_query_2 neighbor_query_2(polyline_2);
Region_type_2 region_type_2(
polyline_2,
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
// Run 2D region growing.
Region_growing_2 region_growing_2(
polyline_2, neighbor_query_2, region_type_2);
std::vector<typename Region_growing_2::Primitive_and_region> regions_2;
region_growing_2.detect(std::back_inserter(regions_2));
assert(regions_2.size() == 5);
for (const auto& region : regions_2)
assert(region_type_2.is_valid_region(region.second));
std::vector<typename Region_growing_2::Item> unassigned_points2;
region_growing_2.unassigned_items(polyline_2, std::back_inserter(unassigned_points2));
assert(unassigned_points2.size() == 0);
return true;
}
int main(int argc, char *argv[]) {
using SC = CGAL::Simple_cartesian<double>;
using EPICK = CGAL::Exact_predicates_inexact_constructions_kernel;
using EPECK = CGAL::Exact_predicates_exact_constructions_kernel;
// ------>
bool sc_test_success = true;
if (!test_region_growing_on_polyline<SC>(argc, argv))
sc_test_success = false;
std::cout << "rg_poly, sc_test_success: " << sc_test_success << std::endl;
assert(sc_test_success);
// ------>
bool epick_test_success = true;
if (!test_region_growing_on_polyline<EPICK>(argc, argv))
epick_test_success = false;
std::cout << "rg_poly, epick_test_success: " << epick_test_success << std::endl;
assert(epick_test_success);
// ------>
bool epeck_test_success = true;
if (!test_region_growing_on_polyline<EPECK>(argc, argv))
epeck_test_success = false;
std::cout << "rg_poly, epeck_test_success: " << epeck_test_success << std::endl;
assert(epeck_test_success);
const bool success = sc_test_success && epick_test_success && epeck_test_success;
return (success) ? EXIT_SUCCESS : EXIT_FAILURE;
}

View File

@ -1,175 +0,0 @@
// STL includes.
#include <string>
#include <vector>
#include <utility>
#include <cstdlib>
#include <fstream>
#include <iostream>
#include <iterator>
#include <cassert>
// CGAL includes.
#include <CGAL/assertions.h>
#include <CGAL/property_map.h>
#include <CGAL/Simple_cartesian.h>
#include <CGAL/Shape_detection/Region_growing/Region_growing.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
#include <CGAL/Shape_detection/Region_growing/free_functions.h>
namespace SD = CGAL::Shape_detection;
using Kernel = CGAL::Simple_cartesian<double>;
using FT = typename Kernel::FT;
using Point_2 = typename Kernel::Point_2;
using Point_3 = typename Kernel::Point_3;
using Polyline_2 = std::vector<Point_2>;
using Polyline_3 = std::vector<Point_3>;
using Point_map_2 = CGAL::Identity_property_map<Point_2>;
using Point_map_3 = CGAL::Identity_property_map<Point_3>;
using Neighbor_query_2 = SD::Polyline::One_ring_neighbor_query<Kernel, Polyline_2>;
using Region_type_2 = SD::Polyline::Least_squares_line_fit_region<Kernel, Polyline_2, Point_map_2>;
using Sorting_2 = SD::Polyline::Least_squares_line_fit_sorting<Kernel, Polyline_2, Neighbor_query_2, Point_map_2>;
using Region_growing_2 = SD::Region_growing<Neighbor_query_2, Region_type_2>;
using Neighbor_query_3 = SD::Polyline::One_ring_neighbor_query<Kernel, Polyline_3>;
using Region_type_3 = SD::Polyline::Least_squares_line_fit_region<Kernel, Polyline_3, Point_map_3>;
using Sorting_3 = SD::Polyline::Least_squares_line_fit_sorting<Kernel, Polyline_3, Neighbor_query_3, Point_map_3>;
using Region_growing_3 = SD::Region_growing<Neighbor_query_3, Region_type_3>;
int main(int argc, char *argv[]) {
// Default parameter values.
const FT distance_threshold = FT(45) / FT(10);
const FT angle_threshold = FT(45);
// Load data.
std::ifstream in(argc > 1 ? argv[1] : CGAL::data_file_path("polylines_3/wavy_circle.polylines.txt"));
CGAL::IO::set_ascii_mode(in);
assert(in);
// Create 3D polyline.
Polyline_3 polyline_3;
std::size_t n = std::size_t(-1);
in >> n;
polyline_3.reserve(n);
while (n--) {
Point_3 point; in >> point;
polyline_3.push_back(point);
assert(in.good());
}
in.close();
assert(polyline_3.size() == 249);
// Create 3D parameter classes.
Neighbor_query_3 neighbor_query_3(polyline_3);
Region_type_3 region_type_3(
polyline_3,
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
// Sort indices.
Sorting_3 sorting_3(polyline_3, neighbor_query_3);
sorting_3.sort();
// Run 3D region growing.
Region_growing_3 region_growing_3(
polyline_3, neighbor_query_3, region_type_3, sorting_3.ordered());
std::vector<Region_growing_3::Primitive_and_region> regions3;
region_growing_3.detect(std::back_inserter(regions3));
assert(regions3.size() == 16);
std::vector<Region_growing_3::Item> unassigned_points;
region_growing_3.unassigned_items(polyline_3, std::back_inserter(unassigned_points));
assert(unassigned_points.size() == 1);
// Test free functions and stability.
for (std::size_t k = 0; k < 3; ++k) {
regions3.clear();
SD::region_growing_polylines(
polyline_3, std::back_inserter(regions3),
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
assert(regions3.size() == 16);
}
// Create 2D polyline.
std::vector<std::size_t> indices(polyline_3.size());
std::iota(indices.begin(), indices.end(), 0);
const auto plane = SD::internal::create_plane(
polyline_3, Point_map_3(), indices, Kernel()).first;
Polyline_2 polyline_2;
polyline_2.reserve(polyline_3.size());
for (const auto& point : polyline_3) {
const auto p3 = plane.projection(point);
const auto p2 = plane.to_2d(p3);
polyline_2.push_back(p2);
}
assert(polyline_2.size() == polyline_3.size());
// Create 2D parameter classes.
Neighbor_query_2 neighbor_query_2(polyline_2);
Region_type_2 region_type_2(
polyline_2,
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
// Sort indices.
Sorting_2 sorting_2(polyline_2, neighbor_query_2);
sorting_2.sort();
// Run 2D region growing.
Region_growing_2 region_growing_2(
polyline_2, neighbor_query_2, region_type_2, sorting_2.ordered());
std::vector<typename Region_growing_2::Primitive_and_region> regions2;
region_growing_2.detect(std::back_inserter(regions2));
assert(regions2.size() == 5);
for (const auto& region : regions2)
assert(region_type_2.is_valid_region(region.second));
Region_growing_2::Region_map map = region_growing_2.region_map();
for (std::size_t i = 0; i < regions2.size(); i++)
for (auto& item : regions2[i].second) {
if (i != get(map, CGAL::Shape_detection::internal::conditional_deref<Region_growing_2::Item, typename Region_growing_2::Region_map::key_type>()(item))) {
std::cout << "Region map incorrect" << std::endl;
assert(false);
}
}
std::vector<Region_growing_2::Item> unassigned;
region_growing_2.unassigned_items(polyline_2, std::back_inserter(unassigned));
for (auto& item : unassigned) {
if (std::size_t(-1) != get(map, CGAL::Shape_detection::internal::conditional_deref<Region_growing_2::Item, typename Region_growing_2::Region_map::key_type>()(item))) {
std::cout << "Region map for unassigned incorrect" << std::endl;
assert(false);
}
}
std::vector<Region_growing_2::Item> unassigned2;
region_growing_2.unassigned_items(polyline_2, std::back_inserter(unassigned2));
assert(unassigned2.size() == 0);
// Test free functions and stability.
for (std::size_t k = 0; k < 3; ++k) {
regions2.clear();
SD::region_growing_polylines(
polyline_2, std::back_inserter(regions2),
CGAL::parameters::
maximum_distance(distance_threshold).
maximum_angle(angle_threshold));
assert(regions2.size() == 5);
}
std::cout << "rg_sortpoly, sc_test_success: " << true << std::endl;
return EXIT_SUCCESS;
}

View File

@ -23,7 +23,6 @@
#include <CGAL/Shape_detection/Region_growing/Region_growing.h>
#include <CGAL/Shape_detection/Region_growing/Point_set.h>
#include <CGAL/Shape_detection/Region_growing/Polygon_mesh.h>
#include <CGAL/Shape_detection/Region_growing/Polyline.h>
#include <CGAL/Shape_detection/Region_growing/Segment_set.h>
#include <CGAL/Shape_detection/Region_growing/free_functions.h>
@ -60,73 +59,6 @@ bool test_lines_points_with_normals() {
return true;
}
template<class Kernel>
bool test_lines_polylines_2() {
using Point_2 = typename Kernel::Point_2;
using Item = typename std::vector<Point_2>::const_iterator;
const std::vector<Point_2> polyline_2 = {
Point_2(0.10, 0.00), Point_2(0.50, 0.00), Point_2(0.90, 0.00),
Point_2(0.13, 0.00), Point_2(0.17, 0.00), Point_2(0.21, 0.00),
Point_2(0.21, 2.10), Point_2(0.21, 2.50), Point_2(0.21, 2.90),
Point_2(0.21, 2.13), Point_2(0.21, 2.17), Point_2(0.21, 2.21)
};
assert(polyline_2.size() == 12);
std::vector< std::pair< typename Kernel::Line_2, std::vector<Item> > > regions;
CGAL::Shape_detection::region_growing_polylines(
polyline_2, std::back_inserter(regions));
assert(regions.size() == 2);
assert(regions[0].second.size() == 6);
assert(regions[1].second.size() == 6);
return true;
}
template<class Kernel>
bool test_lines_polylines_3() {
using Point_3 = typename Kernel::Point_3;
using Item = typename std::vector<Point_3>::const_iterator;
const std::vector<Point_3> polyline_3 = {
Point_3(0.10, 0.0, 1.0), Point_3(0.50, 0.0, 1.0), Point_3(0.90, 0.0, 1.0),
Point_3(0.13, 0.0, 1.0), Point_3(0.17, 0.0, 1.0), Point_3(0.21, 0.0, 1.0)
};
assert(polyline_3.size() == 6);
std::vector< std::pair< typename Kernel::Line_3, std::vector<Item> > > regions;
CGAL::Shape_detection::region_growing_polylines(
polyline_3, std::back_inserter(regions));
assert(regions.size() == 1);
assert(regions[0].second.size() == 6);
return true;
}
template<class Kernel>
bool test_polylines_equal_points() {
using Point_2 = typename Kernel::Point_2;
using Item = typename std::vector<Point_2>::const_iterator;
const std::vector<Point_2> polyline_2 = {
Point_2(0, 0), Point_2(1, 0), Point_2(2, 0), Point_2(3, 0),
Point_2(7, 1), Point_2(8, 1), Point_2(9, 1), Point_2(10, 1),
Point_2(14, 2), Point_2(15, 2), Point_2(16, 2), Point_2(17, 2),
Point_2(19, 3), Point_2(20, 3), Point_2(21, 3), Point_2(22, 3)
};
assert(polyline_2.size() == 16);
std::vector< std::pair< typename Kernel::Line_2, std::vector<Item> > > regions;
CGAL::Shape_detection::region_growing_polylines(
polyline_2, std::back_inserter(regions), CGAL::parameters::maximum_distance(0.01));
assert(regions.size() == 4);
assert(regions[0].second.size() == 4);
assert(regions[1].second.size() == 4);
assert(regions[2].second.size() == 4);
assert(regions[3].second.size() == 4);
return true;
}
template<class Kernel>
bool test_lines_segment_set_2() {
@ -323,9 +255,6 @@ bool test_lines_segment_set_3() {
template<class Kernel>
bool test_region_growing_lines() {
assert(test_lines_points_with_normals<Kernel>());
assert(test_lines_polylines_2<Kernel>());
assert(test_lines_polylines_3<Kernel>());
assert(test_polylines_equal_points<Kernel>());
assert(test_lines_segment_set_2<Kernel>());
assert(test_lines_segment_set_2_sorting<Kernel>());
assert(test_lines_segment_set_3<Kernel>());