Reworked the ClipperLib / Polygon types to use

the tbb::scallable_allocator to better scale on multiple threads.
This commit is contained in:
Vojtech Bubnik 2023-04-20 11:31:44 +02:00
parent b0cc0e98fa
commit 9cde96993e
38 changed files with 261 additions and 241 deletions

View File

@ -406,6 +406,7 @@ endif()
set(TBB_DEBUG 1)
find_package(TBB REQUIRED)
slic3r_remap_configs(TBB::tbb RelWithDebInfo Release)
slic3r_remap_configs(TBB::tbbmalloc RelWithDebInfo Release)
# include_directories(${TBB_INCLUDE_DIRS})
# add_definitions(${TBB_DEFINITIONS})
# if(MSVC)

View File

@ -8,3 +8,5 @@ add_library(clipper STATIC
clipper_z.cpp
clipper_z.hpp
)
target_link_libraries(clipper TBB::tbb TBB::tbbmalloc)

View File

@ -784,7 +784,7 @@ bool ClipperBase::AddPath(const Path &pg, PolyType PolyTyp, bool Closed)
return false;
// Allocate a new edge array.
std::vector<TEdge> edges(highI + 1);
Edges edges(highI + 1);
// Fill in the edge array.
bool result = AddPathInternal(pg, highI, PolyTyp, Closed, edges.data());
if (result)
@ -1079,7 +1079,7 @@ Clipper::Clipper(int initOptions) :
void Clipper::Reset()
{
ClipperBase::Reset();
m_Scanbeam = std::priority_queue<cInt>();
m_Scanbeam = std::priority_queue<cInt, cInts>{};
m_Maxima.clear();
m_ActiveEdges = 0;
m_SortedEdges = 0;
@ -2226,8 +2226,8 @@ void Clipper::ProcessHorizontal(TEdge *horzEdge)
if (!eLastHorz->NextInLML)
eMaxPair = GetMaximaPair(eLastHorz);
std::vector<cInt>::const_iterator maxIt;
std::vector<cInt>::const_reverse_iterator maxRit;
cInts::const_iterator maxIt;
cInts::const_reverse_iterator maxRit;
if (!m_Maxima.empty())
{
//get the first maxima in range (X) ...
@ -3941,7 +3941,7 @@ void CleanPolygon(const Path& in_poly, Path& out_poly, double distance)
return;
}
std::vector<OutPt> outPts(size);
OutPts outPts(size);
for (size_t i = 0; i < size; ++i)
{
outPts[i].Pt = in_poly[i];

View File

@ -39,6 +39,8 @@
#include <Eigen/Geometry>
#include <oneapi/tbb/scalable_allocator.h>
#define CLIPPER_VERSION "6.2.6"
//CLIPPERLIB_USE_XYZ: adds a Z member to IntPoint. Adds a minor cost to perfomance.
@ -112,8 +114,10 @@ using DoublePoint = Eigen::Matrix<double, 2, 1, Eigen::DontAlign>;
//------------------------------------------------------------------------------
typedef std::vector<IntPoint> Path;
typedef std::vector<Path> Paths;
template<typename BaseType>
using Allocator = tbb::scalable_allocator<BaseType>;
using Path = std::vector<IntPoint, Allocator<IntPoint>>;
using Paths = std::vector<Path, Allocator<Path>>;
inline Path& operator <<(Path& poly, const IntPoint& p) {poly.push_back(p); return poly;}
inline Paths& operator <<(Paths& polys, const Path& p) {polys.push_back(p); return polys;}
@ -133,7 +137,7 @@ enum JoinType {jtSquare, jtRound, jtMiter};
enum EndType {etClosedPolygon, etClosedLine, etOpenButt, etOpenSquare, etOpenRound};
class PolyNode;
typedef std::vector< PolyNode* > PolyNodes;
typedef std::vector<PolyNode*, Allocator<PolyNode*>> PolyNodes;
class PolyNode
{
@ -186,7 +190,7 @@ public:
private:
PolyTree(const PolyTree &src) = delete;
PolyTree& operator=(const PolyTree &src) = delete;
std::vector<PolyNode> AllNodes;
std::vector<PolyNode, Allocator<PolyNode>> AllNodes;
friend class Clipper; //to access AllNodes
};
@ -277,6 +281,8 @@ enum EdgeSide { esLeft = 1, esRight = 2};
OutPt *Prev;
};
using OutPts = std::vector<OutPt, tbb::scalable_allocator<OutPt>>;
struct OutRec;
struct Join {
Join(OutPt *OutPt1, OutPt *OutPt2, IntPoint OffPt) :
@ -312,7 +318,7 @@ public:
if (num_paths == 1)
return AddPath(*paths_provider.begin(), PolyTyp, Closed);
std::vector<int> num_edges(num_paths, 0);
std::vector<int, Allocator<int>> num_edges(num_paths, 0);
int num_edges_total = 0;
size_t i = 0;
for (const Path &pg : paths_provider) {
@ -333,7 +339,7 @@ public:
return false;
// Allocate a new edge array.
std::vector<TEdge> edges(num_edges_total);
std::vector<TEdge, Allocator<TEdge>> edges(num_edges_total);
// Fill in the edge array.
bool result = false;
TEdge *p_edge = edges.data();
@ -369,7 +375,7 @@ protected:
void AscendToMax(TEdge *&E, bool Appending, bool IsClosed);
// Local minima (Y, left edge, right edge) sorted by ascending Y.
std::vector<LocalMinimum> m_MinimaList;
std::vector<LocalMinimum, Allocator<LocalMinimum>> m_MinimaList;
#ifdef CLIPPERLIB_INT32
static constexpr const bool m_UseFullRange = false;
@ -380,7 +386,8 @@ protected:
#endif // CLIPPERLIB_INT32
// A vector of edges per each input path.
std::vector<std::vector<TEdge>> m_edges;
using Edges = std::vector<TEdge, Allocator<TEdge>>;
std::vector<Edges, Allocator<Edges>> m_edges;
// Don't remove intermediate vertices of a collinear sequence of points.
bool m_PreserveCollinear;
// Is any of the paths inserted by AddPath() or AddPaths() open?
@ -424,22 +431,23 @@ protected:
private:
// Output polygons.
std::vector<OutRec*> m_PolyOuts;
std::vector<OutRec*, Allocator<OutRec*>> m_PolyOuts;
// Output points, allocated by a continuous sets of m_OutPtsChunkSize.
std::vector<OutPt*> m_OutPts;
std::vector<OutPt*, Allocator<OutPt*>> m_OutPts;
// List of free output points, to be used before taking a point from m_OutPts or allocating a new chunk.
OutPt *m_OutPtsFree;
size_t m_OutPtsChunkSize;
size_t m_OutPtsChunkLast;
std::vector<Join> m_Joins;
std::vector<Join> m_GhostJoins;
std::vector<IntersectNode> m_IntersectList;
std::vector<Join, Allocator<Join>> m_Joins;
std::vector<Join, Allocator<Join>> m_GhostJoins;
std::vector<IntersectNode, Allocator<IntersectNode>> m_IntersectList;
ClipType m_ClipType;
// A priority queue (a binary heap) of Y coordinates.
std::priority_queue<cInt> m_Scanbeam;
using cInts = std::vector<cInt, Allocator<cInt>>;
std::priority_queue<cInt, cInts> m_Scanbeam;
// Maxima are collected by ProcessEdgesAtTopOfScanbeam(), consumed by ProcessHorizontal().
std::vector<cInt> m_Maxima;
cInts m_Maxima;
TEdge *m_ActiveEdges;
TEdge *m_SortedEdges;
PolyFillType m_ClipFillType;
@ -530,7 +538,7 @@ private:
Paths m_destPolys;
Path m_srcPoly;
Path m_destPoly;
std::vector<DoublePoint> m_normals;
std::vector<DoublePoint, Allocator<DoublePoint>> m_normals;
double m_delta, m_sinA, m_sin, m_cos;
double m_miterLim, m_StepsPerRad;
// x: index of the lowest contour in m_polyNodes

View File

@ -24,5 +24,5 @@ set(LIBNEST2D_SRCFILES
add_library(libnest2d STATIC ${LIBNEST2D_SRCFILES})
target_include_directories(libnest2d PUBLIC ${CMAKE_CURRENT_LIST_DIR}/include)
target_link_libraries(libnest2d PUBLIC NLopt::nlopt TBB::tbb Boost::boost libslic3r)
target_link_libraries(libnest2d PUBLIC NLopt::nlopt TBB::tbb TBB::tbbmalloc Boost::boost libslic3r)
target_compile_definitions(libnest2d PUBLIC LIBNEST2D_THREADING_tbb LIBNEST2D_STATIC LIBNEST2D_OPTIMIZER_nlopt LIBNEST2D_GEOMETRIES_libslic3r)

View File

@ -181,7 +181,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, vd_t::edge_type&
}
else
{
std::vector<Point> discretized = discretize(vd_edge, segments);
Points discretized = discretize(vd_edge, segments);
assert(discretized.size() >= 2);
if(discretized.size() < 2)
{
@ -236,7 +236,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, vd_t::edge_type&
}
}
std::vector<Point> SkeletalTrapezoidation::discretize(const vd_t::edge_type& vd_edge, const std::vector<Segment>& segments)
Points SkeletalTrapezoidation::discretize(const vd_t::edge_type& vd_edge, const std::vector<Segment>& segments)
{
/*Terminology in this function assumes that the edge moves horizontally from
left to right. This is not necessarily the case; the edge can go in any
@ -257,7 +257,7 @@ std::vector<Point> SkeletalTrapezoidation::discretize(const vd_t::edge_type& vd_
bool point_right = right_cell->contains_point();
if ((!point_left && !point_right) || vd_edge.is_secondary()) // Source vert is directly connected to source segment
{
return std::vector<Point>({ start, end });
return Points({ start, end });
}
else if (point_left != point_right) //This is a parabolic edge between a point and a line.
{
@ -311,7 +311,7 @@ std::vector<Point> SkeletalTrapezoidation::discretize(const vd_t::edge_type& vd_
//Start generating points along the edge.
Point a = start;
Point b = end;
std::vector<Point> ret;
Points ret;
ret.emplace_back(a);
//Introduce an extra edge at the borders of the markings?

View File

@ -204,7 +204,7 @@ protected:
* \return A number of coordinates along the edge where the edge is broken
* up into discrete pieces.
*/
std::vector<Point> discretize(const vd_t::edge_type& segment, const std::vector<Segment>& segments);
Points discretize(const vd_t::edge_type& segment, const std::vector<Segment>& segments);
/*!
* Compute the range of line segments that surround a cell of the skeletal

View File

@ -138,9 +138,9 @@ public:
return Point(coord_t(p.x() * matrix[0] + p.y() * matrix[2]), coord_t(p.x() * matrix[1] + p.y() * matrix[3]));
}
};
std::vector<Point> VoronoiUtils::discretizeParabola(const Point& p, const Segment& segment, Point s, Point e, coord_t approximate_step_size, float transitioning_angle)
Points VoronoiUtils::discretizeParabola(const Point& p, const Segment& segment, Point s, Point e, coord_t approximate_step_size, float transitioning_angle)
{
std::vector<Point> discretized;
Points discretized;
// x is distance of point projected on the segment ab
// xx is point projected on the segment ab
const Point a = segment.from();

View File

@ -34,7 +34,7 @@ public:
* Discretize a parabola based on (approximate) step size.
* The \p approximate_step_size is measured parallel to the \p source_segment, not along the parabola.
*/
static std::vector<Point> discretizeParabola(const Point &source_point, const Segment &source_segment, Point start, Point end, coord_t approximate_step_size, float transitioning_angle);
static Points discretizeParabola(const Point &source_point, const Segment &source_segment, Point start, Point end, coord_t approximate_step_size, float transitioning_angle);
static inline bool is_finite(const VoronoiUtils::vd_t::vertex_type &vertex)
{

View File

@ -6,23 +6,19 @@
namespace Slic3r {
template BoundingBoxBase<Point>::BoundingBoxBase(const std::vector<Point> &points);
template BoundingBoxBase<Point, Points>::BoundingBoxBase(const Points &points);
template BoundingBoxBase<Vec2d>::BoundingBoxBase(const std::vector<Vec2d> &points);
template BoundingBox3Base<Vec3d>::BoundingBox3Base(const std::vector<Vec3d> &points);
void BoundingBox::polygon(Polygon* polygon) const
{
polygon->points.clear();
polygon->points.resize(4);
polygon->points[0](0) = this->min(0);
polygon->points[0](1) = this->min(1);
polygon->points[1](0) = this->max(0);
polygon->points[1](1) = this->min(1);
polygon->points[2](0) = this->max(0);
polygon->points[2](1) = this->max(1);
polygon->points[3](0) = this->min(0);
polygon->points[3](1) = this->max(1);
polygon->points = {
this->min,
{ this->max.x(), this->min.y() },
this->max,
{ this->min.x(), this->max.y() }
};
}
Polygon BoundingBox::polygon() const
@ -37,8 +33,8 @@ BoundingBox BoundingBox::rotated(double angle) const
BoundingBox out;
out.merge(this->min.rotated(angle));
out.merge(this->max.rotated(angle));
out.merge(Point(this->min(0), this->max(1)).rotated(angle));
out.merge(Point(this->max(0), this->min(1)).rotated(angle));
out.merge(Point(this->min.x(), this->max.y()).rotated(angle));
out.merge(Point(this->max.x(), this->min.y()).rotated(angle));
return out;
}
@ -47,23 +43,23 @@ BoundingBox BoundingBox::rotated(double angle, const Point &center) const
BoundingBox out;
out.merge(this->min.rotated(angle, center));
out.merge(this->max.rotated(angle, center));
out.merge(Point(this->min(0), this->max(1)).rotated(angle, center));
out.merge(Point(this->max(0), this->min(1)).rotated(angle, center));
out.merge(Point(this->min.x(), this->max.y()).rotated(angle, center));
out.merge(Point(this->max.x(), this->min.y()).rotated(angle, center));
return out;
}
template <class PointClass> void
BoundingBoxBase<PointClass>::scale(double factor)
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::scale(double factor)
{
this->min *= factor;
this->max *= factor;
}
template void BoundingBoxBase<Point>::scale(double factor);
template void BoundingBoxBase<Point, Points>::scale(double factor);
template void BoundingBoxBase<Vec2d>::scale(double factor);
template void BoundingBoxBase<Vec3d>::scale(double factor);
template <class PointClass> void
BoundingBoxBase<PointClass>::merge(const PointClass &point)
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::merge(const PointType &point)
{
if (this->defined) {
this->min = this->min.cwiseMin(point);
@ -74,22 +70,22 @@ BoundingBoxBase<PointClass>::merge(const PointClass &point)
this->defined = true;
}
}
template void BoundingBoxBase<Point>::merge(const Point &point);
template void BoundingBoxBase<Point, Points>::merge(const Point &point);
template void BoundingBoxBase<Vec2f>::merge(const Vec2f &point);
template void BoundingBoxBase<Vec2d>::merge(const Vec2d &point);
template <class PointClass> void
BoundingBoxBase<PointClass>::merge(const std::vector<PointClass> &points)
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::merge(const PointsType &points)
{
this->merge(BoundingBoxBase(points));
}
template void BoundingBoxBase<Point>::merge(const Points &points);
template void BoundingBoxBase<Point, Points>::merge(const Points &points);
template void BoundingBoxBase<Vec2d>::merge(const Pointfs &points);
template <class PointClass> void
BoundingBoxBase<PointClass>::merge(const BoundingBoxBase<PointClass> &bb)
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::merge(const BoundingBoxBase<PointType, PointsType> &bb)
{
assert(bb.defined || bb.min(0) >= bb.max(0) || bb.min(1) >= bb.max(1));
assert(bb.defined || bb.min.x() >= bb.max.x() || bb.min.y() >= bb.max.y());
if (bb.defined) {
if (this->defined) {
this->min = this->min.cwiseMin(bb.min);
@ -101,12 +97,12 @@ BoundingBoxBase<PointClass>::merge(const BoundingBoxBase<PointClass> &bb)
}
}
}
template void BoundingBoxBase<Point>::merge(const BoundingBoxBase<Point> &bb);
template void BoundingBoxBase<Point, Points>::merge(const BoundingBoxBase<Point, Points> &bb);
template void BoundingBoxBase<Vec2f>::merge(const BoundingBoxBase<Vec2f> &bb);
template void BoundingBoxBase<Vec2d>::merge(const BoundingBoxBase<Vec2d> &bb);
template <class PointClass> void
BoundingBox3Base<PointClass>::merge(const PointClass &point)
template <class PointType> void
BoundingBox3Base<PointType>::merge(const PointType &point)
{
if (this->defined) {
this->min = this->min.cwiseMin(point);
@ -120,17 +116,17 @@ BoundingBox3Base<PointClass>::merge(const PointClass &point)
template void BoundingBox3Base<Vec3f>::merge(const Vec3f &point);
template void BoundingBox3Base<Vec3d>::merge(const Vec3d &point);
template <class PointClass> void
BoundingBox3Base<PointClass>::merge(const std::vector<PointClass> &points)
template <class PointType> void
BoundingBox3Base<PointType>::merge(const PointsType &points)
{
this->merge(BoundingBox3Base(points));
}
template void BoundingBox3Base<Vec3d>::merge(const Pointf3s &points);
template <class PointClass> void
BoundingBox3Base<PointClass>::merge(const BoundingBox3Base<PointClass> &bb)
template <class PointType> void
BoundingBox3Base<PointType>::merge(const BoundingBox3Base<PointType> &bb)
{
assert(bb.defined || bb.min(0) >= bb.max(0) || bb.min(1) >= bb.max(1) || bb.min(2) >= bb.max(2));
assert(bb.defined || bb.min.x() >= bb.max.x() || bb.min.y() >= bb.max.y() || bb.min.z() >= bb.max.z());
if (bb.defined) {
if (this->defined) {
this->min = this->min.cwiseMin(bb.min);
@ -144,83 +140,78 @@ BoundingBox3Base<PointClass>::merge(const BoundingBox3Base<PointClass> &bb)
}
template void BoundingBox3Base<Vec3d>::merge(const BoundingBox3Base<Vec3d> &bb);
template <class PointClass> PointClass
BoundingBoxBase<PointClass>::size() const
template <class PointType, typename APointsType> PointType
BoundingBoxBase<PointType, APointsType>::size() const
{
return PointClass(this->max(0) - this->min(0), this->max(1) - this->min(1));
return this->max - this->min;
}
template Point BoundingBoxBase<Point>::size() const;
template Point BoundingBoxBase<Point, Points>::size() const;
template Vec2f BoundingBoxBase<Vec2f>::size() const;
template Vec2d BoundingBoxBase<Vec2d>::size() const;
template <class PointClass> PointClass
BoundingBox3Base<PointClass>::size() const
template <class PointType> PointType
BoundingBox3Base<PointType>::size() const
{
return PointClass(this->max(0) - this->min(0), this->max(1) - this->min(1), this->max(2) - this->min(2));
return this->max - this->min;
}
template Vec3f BoundingBox3Base<Vec3f>::size() const;
template Vec3d BoundingBox3Base<Vec3d>::size() const;
template <class PointClass> double BoundingBoxBase<PointClass>::radius() const
template <class PointType, typename APointsType> double BoundingBoxBase<PointType, APointsType>::radius() const
{
assert(this->defined);
double x = this->max(0) - this->min(0);
double y = this->max(1) - this->min(1);
return 0.5 * sqrt(x*x+y*y);
return 0.5 * (this->max - this->min).cast<double>().norm();
}
template double BoundingBoxBase<Point>::radius() const;
template double BoundingBoxBase<Point, Points>::radius() const;
template double BoundingBoxBase<Vec2d>::radius() const;
template <class PointClass> double BoundingBox3Base<PointClass>::radius() const
template <class PointType> double BoundingBox3Base<PointType>::radius() const
{
double x = this->max(0) - this->min(0);
double y = this->max(1) - this->min(1);
double z = this->max(2) - this->min(2);
return 0.5 * sqrt(x*x+y*y+z*z);
return 0.5 * (this->max - this->min).cast<double>().norm();
}
template double BoundingBox3Base<Vec3d>::radius() const;
template <class PointClass> void
BoundingBoxBase<PointClass>::offset(coordf_t delta)
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::offset(coordf_t delta)
{
PointClass v(delta, delta);
PointType v(delta, delta);
this->min -= v;
this->max += v;
}
template void BoundingBoxBase<Point>::offset(coordf_t delta);
template void BoundingBoxBase<Point, Points>::offset(coordf_t delta);
template void BoundingBoxBase<Vec2d>::offset(coordf_t delta);
template <class PointClass> void
BoundingBox3Base<PointClass>::offset(coordf_t delta)
template <class PointType> void
BoundingBox3Base<PointType>::offset(coordf_t delta)
{
PointClass v(delta, delta, delta);
PointType v(delta, delta, delta);
this->min -= v;
this->max += v;
}
template void BoundingBox3Base<Vec3d>::offset(coordf_t delta);
template <class PointClass> PointClass
BoundingBoxBase<PointClass>::center() const
template <class PointType, typename APointsType> PointType
BoundingBoxBase<PointType, APointsType>::center() const
{
return (this->min + this->max) / 2;
}
template Point BoundingBoxBase<Point>::center() const;
template Point BoundingBoxBase<Point, Points>::center() const;
template Vec2f BoundingBoxBase<Vec2f>::center() const;
template Vec2d BoundingBoxBase<Vec2d>::center() const;
template <class PointClass> PointClass
BoundingBox3Base<PointClass>::center() const
template <class PointType> PointType
BoundingBox3Base<PointType>::center() const
{
return (this->min + this->max) / 2;
}
template Vec3f BoundingBox3Base<Vec3f>::center() const;
template Vec3d BoundingBox3Base<Vec3d>::center() const;
template <class PointClass> coordf_t
BoundingBox3Base<PointClass>::max_size() const
template <class PointType> coordf_t
BoundingBox3Base<PointType>::max_size() const
{
PointClass s = size();
return std::max(s(0), std::max(s(1), s(2)));
PointType s = size();
return std::max(s.x(), std::max(s.y(), s.z()));
}
template coordf_t BoundingBox3Base<Vec3f>::max_size() const;
template coordf_t BoundingBox3Base<Vec3d>::max_size() const;
@ -228,8 +219,8 @@ template coordf_t BoundingBox3Base<Vec3d>::max_size() const;
void BoundingBox::align_to_grid(const coord_t cell_size)
{
if (this->defined) {
min(0) = Slic3r::align_to_grid(min(0), cell_size);
min(1) = Slic3r::align_to_grid(min(1), cell_size);
min.x() = Slic3r::align_to_grid(min.x(), cell_size);
min.y() = Slic3r::align_to_grid(min.y(), cell_size);
}
}
@ -238,14 +229,14 @@ BoundingBoxf3 BoundingBoxf3::transformed(const Transform3d& matrix) const
typedef Eigen::Matrix<double, 3, 8, Eigen::DontAlign> Vertices;
Vertices src_vertices;
src_vertices(0, 0) = min(0); src_vertices(1, 0) = min(1); src_vertices(2, 0) = min(2);
src_vertices(0, 1) = max(0); src_vertices(1, 1) = min(1); src_vertices(2, 1) = min(2);
src_vertices(0, 2) = max(0); src_vertices(1, 2) = max(1); src_vertices(2, 2) = min(2);
src_vertices(0, 3) = min(0); src_vertices(1, 3) = max(1); src_vertices(2, 3) = min(2);
src_vertices(0, 4) = min(0); src_vertices(1, 4) = min(1); src_vertices(2, 4) = max(2);
src_vertices(0, 5) = max(0); src_vertices(1, 5) = min(1); src_vertices(2, 5) = max(2);
src_vertices(0, 6) = max(0); src_vertices(1, 6) = max(1); src_vertices(2, 6) = max(2);
src_vertices(0, 7) = min(0); src_vertices(1, 7) = max(1); src_vertices(2, 7) = max(2);
src_vertices(0, 0) = min.x(); src_vertices(1, 0) = min.y(); src_vertices(2, 0) = min.z();
src_vertices(0, 1) = max.x(); src_vertices(1, 1) = min.y(); src_vertices(2, 1) = min.z();
src_vertices(0, 2) = max.x(); src_vertices(1, 2) = max.y(); src_vertices(2, 2) = min.z();
src_vertices(0, 3) = min.x(); src_vertices(1, 3) = max.y(); src_vertices(2, 3) = min.z();
src_vertices(0, 4) = min.x(); src_vertices(1, 4) = min.y(); src_vertices(2, 4) = max.z();
src_vertices(0, 5) = max.x(); src_vertices(1, 5) = min.y(); src_vertices(2, 5) = max.z();
src_vertices(0, 6) = max.x(); src_vertices(1, 6) = max.y(); src_vertices(2, 6) = max.z();
src_vertices(0, 7) = min.x(); src_vertices(1, 7) = max.y(); src_vertices(2, 7) = max.z();
Vertices dst_vertices = matrix * src_vertices.colwise().homogeneous();

View File

@ -8,53 +8,54 @@
namespace Slic3r {
template <class PointClass>
template <typename PointType, typename APointsType = std::vector<PointType>>
class BoundingBoxBase
{
public:
PointClass min;
PointClass max;
using PointsType = APointsType;
PointType min;
PointType max;
bool defined;
BoundingBoxBase() : min(PointClass::Zero()), max(PointClass::Zero()), defined(false) {}
BoundingBoxBase(const PointClass &pmin, const PointClass &pmax) :
BoundingBoxBase() : min(PointType::Zero()), max(PointType::Zero()), defined(false) {}
BoundingBoxBase(const PointType &pmin, const PointType &pmax) :
min(pmin), max(pmax), defined(pmin.x() < pmax.x() && pmin.y() < pmax.y()) {}
BoundingBoxBase(const PointClass &p1, const PointClass &p2, const PointClass &p3) :
BoundingBoxBase(const PointType &p1, const PointType &p2, const PointType &p3) :
min(p1), max(p1), defined(false) { merge(p2); merge(p3); }
template<class It, class = IteratorOnly<It>>
BoundingBoxBase(It from, It to)
{ construct(*this, from, to); }
BoundingBoxBase(const std::vector<PointClass> &points)
BoundingBoxBase(const PointsType &points)
: BoundingBoxBase(points.begin(), points.end())
{}
void reset() { this->defined = false; this->min = PointClass::Zero(); this->max = PointClass::Zero(); }
void merge(const PointClass &point);
void merge(const std::vector<PointClass> &points);
void merge(const BoundingBoxBase<PointClass> &bb);
void reset() { this->defined = false; this->min = PointType::Zero(); this->max = PointType::Zero(); }
void merge(const PointType &point);
void merge(const PointsType &points);
void merge(const BoundingBoxBase<PointType, PointsType> &bb);
void scale(double factor);
PointClass size() const;
PointType size() const;
double radius() const;
void translate(coordf_t x, coordf_t y) { assert(this->defined); PointClass v(x, y); this->min += v; this->max += v; }
void translate(const PointClass &v) { this->min += v; this->max += v; }
void translate(coordf_t x, coordf_t y) { assert(this->defined); PointType v(x, y); this->min += v; this->max += v; }
void translate(const PointType &v) { this->min += v; this->max += v; }
void offset(coordf_t delta);
BoundingBoxBase<PointClass> inflated(coordf_t delta) const throw() { BoundingBoxBase<PointClass> out(*this); out.offset(delta); return out; }
PointClass center() const;
bool contains(const PointClass &point) const {
BoundingBoxBase<PointType, PointsType> inflated(coordf_t delta) const throw() { BoundingBoxBase<PointType, PointsType> out(*this); out.offset(delta); return out; }
PointType center() const;
bool contains(const PointType &point) const {
return point.x() >= this->min.x() && point.x() <= this->max.x()
&& point.y() >= this->min.y() && point.y() <= this->max.y();
}
bool contains(const BoundingBoxBase<PointClass> &other) const {
bool contains(const BoundingBoxBase<PointType, PointsType> &other) const {
return contains(other.min) && contains(other.max);
}
bool overlap(const BoundingBoxBase<PointClass> &other) const {
bool overlap(const BoundingBoxBase<PointType, PointsType> &other) const {
return ! (this->max.x() < other.min.x() || this->min.x() > other.max.x() ||
this->max.y() < other.min.y() || this->min.y() > other.max.y());
}
bool operator==(const BoundingBoxBase<PointClass> &rhs) { return this->min == rhs.min && this->max == rhs.max; }
bool operator!=(const BoundingBoxBase<PointClass> &rhs) { return ! (*this == rhs); }
bool operator==(const BoundingBoxBase<PointType, PointsType> &rhs) { return this->min == rhs.min && this->max == rhs.max; }
bool operator!=(const BoundingBoxBase<PointType, PointsType> &rhs) { return ! (*this == rhs); }
private:
// to access construct()
@ -69,10 +70,10 @@ private:
{
if (from != to) {
auto it = from;
out.min = it->template cast<typename PointClass::Scalar>();
out.min = it->template cast<typename PointType::Scalar>();
out.max = out.min;
for (++ it; it != to; ++ it) {
auto vec = it->template cast<typename PointClass::Scalar>();
auto vec = it->template cast<typename PointType::Scalar>();
out.min = out.min.cwiseMin(vec);
out.max = out.max.cwiseMax(vec);
}
@ -81,16 +82,18 @@ private:
}
};
template <class PointClass>
class BoundingBox3Base : public BoundingBoxBase<PointClass>
template <class PointType>
class BoundingBox3Base : public BoundingBoxBase<PointType, std::vector<PointType>>
{
public:
BoundingBox3Base() : BoundingBoxBase<PointClass>() {}
BoundingBox3Base(const PointClass &pmin, const PointClass &pmax) :
BoundingBoxBase<PointClass>(pmin, pmax)
{ if (pmin.z() >= pmax.z()) BoundingBoxBase<PointClass>::defined = false; }
BoundingBox3Base(const PointClass &p1, const PointClass &p2, const PointClass &p3) :
BoundingBoxBase<PointClass>(p1, p1) { merge(p2); merge(p3); }
using PointsType = std::vector<PointType>;
BoundingBox3Base() : BoundingBoxBase<PointType>() {}
BoundingBox3Base(const PointType &pmin, const PointType &pmax) :
BoundingBoxBase<PointType>(pmin, pmax)
{ if (pmin.z() >= pmax.z()) BoundingBoxBase<PointType>::defined = false; }
BoundingBox3Base(const PointType &p1, const PointType &p2, const PointType &p3) :
BoundingBoxBase<PointType>(p1, p1) { merge(p2); merge(p3); }
template<class It, class = IteratorOnly<It> > BoundingBox3Base(It from, It to)
{
@ -98,67 +101,67 @@ public:
throw Slic3r::InvalidArgument("Empty point set supplied to BoundingBox3Base constructor");
auto it = from;
this->min = it->template cast<typename PointClass::Scalar>();
this->min = it->template cast<typename PointType::Scalar>();
this->max = this->min;
for (++ it; it != to; ++ it) {
auto vec = it->template cast<typename PointClass::Scalar>();
auto vec = it->template cast<typename PointType::Scalar>();
this->min = this->min.cwiseMin(vec);
this->max = this->max.cwiseMax(vec);
}
this->defined = (this->min.x() < this->max.x()) && (this->min.y() < this->max.y()) && (this->min.z() < this->max.z());
}
BoundingBox3Base(const std::vector<PointClass> &points)
BoundingBox3Base(const PointsType &points)
: BoundingBox3Base(points.begin(), points.end())
{}
void merge(const PointClass &point);
void merge(const std::vector<PointClass> &points);
void merge(const BoundingBox3Base<PointClass> &bb);
PointClass size() const;
void merge(const PointType &point);
void merge(const PointsType &points);
void merge(const BoundingBox3Base<PointType> &bb);
PointType size() const;
double radius() const;
void translate(coordf_t x, coordf_t y, coordf_t z) { assert(this->defined); PointClass v(x, y, z); this->min += v; this->max += v; }
void translate(coordf_t x, coordf_t y, coordf_t z) { assert(this->defined); PointType v(x, y, z); this->min += v; this->max += v; }
void translate(const Vec3d &v) { this->min += v; this->max += v; }
void offset(coordf_t delta);
BoundingBox3Base<PointClass> inflated(coordf_t delta) const throw() { BoundingBox3Base<PointClass> out(*this); out.offset(delta); return out; }
PointClass center() const;
BoundingBox3Base<PointType> inflated(coordf_t delta) const throw() { BoundingBox3Base<PointType> out(*this); out.offset(delta); return out; }
PointType center() const;
coordf_t max_size() const;
bool contains(const PointClass &point) const {
return BoundingBoxBase<PointClass>::contains(point) && point.z() >= this->min.z() && point.z() <= this->max.z();
bool contains(const PointType &point) const {
return BoundingBoxBase<PointType>::contains(point) && point.z() >= this->min.z() && point.z() <= this->max.z();
}
bool contains(const BoundingBox3Base<PointClass>& other) const {
bool contains(const BoundingBox3Base<PointType>& other) const {
return contains(other.min) && contains(other.max);
}
// Intersects without boundaries.
bool intersects(const BoundingBox3Base<PointClass>& other) const {
bool intersects(const BoundingBox3Base<PointType>& other) const {
return this->min.x() < other.max.x() && this->max.x() > other.min.x() && this->min.y() < other.max.y() && this->max.y() > other.min.y() &&
this->min.z() < other.max.z() && this->max.z() > other.min.z();
}
};
// Will prevent warnings caused by non existing definition of template in hpp
extern template void BoundingBoxBase<Point>::scale(double factor);
extern template void BoundingBoxBase<Point, Points>::scale(double factor);
extern template void BoundingBoxBase<Vec2d>::scale(double factor);
extern template void BoundingBoxBase<Vec3d>::scale(double factor);
extern template void BoundingBoxBase<Point>::offset(coordf_t delta);
extern template void BoundingBoxBase<Point, Points>::offset(coordf_t delta);
extern template void BoundingBoxBase<Vec2d>::offset(coordf_t delta);
extern template void BoundingBoxBase<Point>::merge(const Point &point);
extern template void BoundingBoxBase<Point, Points>::merge(const Point &point);
extern template void BoundingBoxBase<Vec2f>::merge(const Vec2f &point);
extern template void BoundingBoxBase<Vec2d>::merge(const Vec2d &point);
extern template void BoundingBoxBase<Point>::merge(const Points &points);
extern template void BoundingBoxBase<Point, Points>::merge(const Points &points);
extern template void BoundingBoxBase<Vec2d>::merge(const Pointfs &points);
extern template void BoundingBoxBase<Point>::merge(const BoundingBoxBase<Point> &bb);
extern template void BoundingBoxBase<Point, Points>::merge(const BoundingBoxBase<Point, Points> &bb);
extern template void BoundingBoxBase<Vec2f>::merge(const BoundingBoxBase<Vec2f> &bb);
extern template void BoundingBoxBase<Vec2d>::merge(const BoundingBoxBase<Vec2d> &bb);
extern template Point BoundingBoxBase<Point>::size() const;
extern template Point BoundingBoxBase<Point, Points>::size() const;
extern template Vec2f BoundingBoxBase<Vec2f>::size() const;
extern template Vec2d BoundingBoxBase<Vec2d>::size() const;
extern template double BoundingBoxBase<Point>::radius() const;
extern template double BoundingBoxBase<Point, Points>::radius() const;
extern template double BoundingBoxBase<Vec2d>::radius() const;
extern template Point BoundingBoxBase<Point>::center() const;
extern template Point BoundingBoxBase<Point, Points>::center() const;
extern template Vec2f BoundingBoxBase<Vec2f>::center() const;
extern template Vec2d BoundingBoxBase<Vec2d>::center() const;
extern template void BoundingBox3Base<Vec3f>::merge(const Vec3f &point);
@ -174,7 +177,7 @@ extern template Vec3d BoundingBox3Base<Vec3d>::center() const;
extern template coordf_t BoundingBox3Base<Vec3f>::max_size() const;
extern template coordf_t BoundingBox3Base<Vec3d>::max_size() const;
class BoundingBox : public BoundingBoxBase<Point>
class BoundingBox : public BoundingBoxBase<Point, Points>
{
public:
void polygon(Polygon* polygon) const;
@ -187,9 +190,9 @@ public:
// to encompass the original bounding box.
void align_to_grid(const coord_t cell_size);
BoundingBox() : BoundingBoxBase<Point>() {}
BoundingBox(const Point &pmin, const Point &pmax) : BoundingBoxBase<Point>(pmin, pmax) {}
BoundingBox(const Points &points) : BoundingBoxBase<Point>(points) {}
BoundingBox() : BoundingBoxBase<Point, Points>() {}
BoundingBox(const Point &pmin, const Point &pmax) : BoundingBoxBase<Point, Points>(pmin, pmax) {}
BoundingBox(const Points &points) : BoundingBoxBase<Point, Points>(points) {}
BoundingBox inflated(coordf_t delta) const throw() { BoundingBox out(*this); out.offset(delta); return out; }
@ -222,14 +225,14 @@ public:
BoundingBoxf3 transformed(const Transform3d& matrix) const;
};
template<typename VT>
inline bool empty(const BoundingBoxBase<VT> &bb)
template<typename PointType, typename PointsType>
inline bool empty(const BoundingBoxBase<PointType, PointsType> &bb)
{
return ! bb.defined || bb.min.x() >= bb.max.x() || bb.min.y() >= bb.max.y();
}
template<typename VT>
inline bool empty(const BoundingBox3Base<VT> &bb)
template<typename PointType>
inline bool empty(const BoundingBox3Base<PointType> &bb)
{
return ! bb.defined || bb.min.x() >= bb.max.x() || bb.min.y() >= bb.max.y() || bb.min.z() >= bb.max.z();
}

View File

@ -485,6 +485,7 @@ target_link_libraries(libslic3r
qhull
semver
TBB::tbb
TBB::tbbmalloc
libslic3r_cgal
${CMAKE_DL_LIBS}
PNG::PNG

View File

@ -51,9 +51,11 @@ namespace ClipperUtils {
// Clip source polygon to be used as a clipping polygon with a bouding box around the source (to be clipped) polygon.
// Useful as an optimization for expensive ClipperLib operations, for example when clipping source polygons one by one
// with a set of polygons covering the whole layer below.
template<typename PointType>
inline void clip_clipper_polygon_with_subject_bbox_templ(const std::vector<PointType> &src, const BoundingBox &bbox, std::vector<PointType> &out)
template<typename PointsType>
inline void clip_clipper_polygon_with_subject_bbox_templ(const PointsType &src, const BoundingBox &bbox, PointsType &out)
{
using PointType = typename PointsType::value_type;
out.clear();
const size_t cnt = src.size();
if (cnt < 3)
@ -108,10 +110,10 @@ namespace ClipperUtils {
void clip_clipper_polygon_with_subject_bbox(const ZPoints &src, const BoundingBox &bbox, ZPoints &out)
{ clip_clipper_polygon_with_subject_bbox_templ(src, bbox, out); }
template<typename PointType>
[[nodiscard]] std::vector<PointType> clip_clipper_polygon_with_subject_bbox_templ(const std::vector<PointType> &src, const BoundingBox &bbox)
template<typename PointsType>
[[nodiscard]] PointsType clip_clipper_polygon_with_subject_bbox_templ(const PointsType &src, const BoundingBox &bbox)
{
std::vector<PointType> out;
PointsType out;
clip_clipper_polygon_with_subject_bbox(src, bbox, out);
return out;
}

View File

@ -40,7 +40,7 @@ inline ZPath to_zpath(const Points &path, coord_t z)
// Convert multiple paths to paths with a given Z coordinate.
// If Open, then duplicate the first point of each path at its end.
template<bool Open = false>
inline ZPaths to_zpaths(const std::vector<Points> &paths, coord_t z)
inline ZPaths to_zpaths(const VecOfPoints &paths, coord_t z)
{
ZPaths out;
out.reserve(paths.size());
@ -86,16 +86,16 @@ inline Points from_zpath(const ZPoints &path)
// Convert multiple paths to paths with a given Z coordinate.
// If Open, then duplicate the first point of each path at its end.
template<bool Open = false>
inline void from_zpaths(const ZPaths &paths, std::vector<Points> &out)
inline void from_zpaths(const ZPaths &paths, VecOfPoints &out)
{
out.reserve(out.size() + paths.size());
for (const ZPoints &path : paths)
out.emplace_back(from_zpath<Open>(path));
}
template<bool Open = false>
inline std::vector<Points> from_zpaths(const ZPaths &paths)
inline VecOfPoints from_zpaths(const ZPaths &paths)
{
std::vector<Points> out;
VecOfPoints out;
from_zpaths(paths, out);
return out;
}

View File

@ -17,7 +17,7 @@ public:
Contour() = default;
Contour(const Slic3r::Point *begin, const Slic3r::Point *end, bool open) : m_begin(begin), m_end(end), m_open(open) {}
Contour(const Slic3r::Point *data, size_t size, bool open) : Contour(data, data + size, open) {}
Contour(const std::vector<Slic3r::Point> &pts, bool open) : Contour(pts.data(), pts.size(), open) {}
Contour(const Points &pts, bool open) : Contour(pts.data(), pts.size(), open) {}
const Slic3r::Point *begin() const { return m_begin; }
const Slic3r::Point *end() const { return m_end; }

View File

@ -397,7 +397,7 @@ bool has_duplicate_points(const ExPolygon &expoly)
size_t cnt = expoly.contour.points.size();
for (const Polygon &hole : expoly.holes)
cnt += hole.points.size();
std::vector<Point> allpts;
Points allpts;
allpts.reserve(cnt);
allpts.insert(allpts.begin(), expoly.contour.points.begin(), expoly.contour.points.end());
for (const Polygon &hole : expoly.holes)
@ -420,7 +420,7 @@ bool has_duplicate_points(const ExPolygons &expolys)
// Check globally.
#if 0
// Detect duplicates by sorting with quicksort. It is quite fast, but ankerl::unordered_dense is around 1/4 faster.
std::vector<Point> allpts;
Points allpts;
allpts.reserve(count_points(expolys));
for (const ExPolygon &expoly : expolys) {
allpts.insert(allpts.begin(), expoly.contour.points.begin(), expoly.contour.points.end());

View File

@ -110,12 +110,14 @@ struct ExtendedPoint
float curvature;
};
template<bool SCALED_INPUT, bool ADD_INTERSECTIONS, bool PREV_LAYER_BOUNDARY_OFFSET, bool SIGNED_DISTANCE, typename P, typename L>
std::vector<ExtendedPoint> estimate_points_properties(const std::vector<P> &input_points,
template<bool SCALED_INPUT, bool ADD_INTERSECTIONS, bool PREV_LAYER_BOUNDARY_OFFSET, bool SIGNED_DISTANCE, typename POINTS, typename L>
std::vector<ExtendedPoint> estimate_points_properties(const POINTS &input_points,
const AABBTreeLines::LinesDistancer<L> &unscaled_prev_layer,
float flow_width,
float max_line_length = -1.0f)
{
using P = typename POINTS::value_type;
using AABBScalar = typename AABBTreeLines::LinesDistancer<L>::Scalar;
if (input_points.empty())
return {};

View File

@ -437,7 +437,7 @@ Polygons extract_perimeter_polygons(const Layer *layer, std::vector<const LayerR
if (polygons.empty()) { // If there are no perimeter polygons for whatever reason (disabled perimeters .. ) insert dummy point
// it is easier than checking everywhere if the layer is not emtpy, no seam will be placed to this layer anyway
polygons.emplace_back(std::vector { Point { 0, 0 } });
polygons.emplace_back(Points{ { 0, 0 } });
corresponding_regions_out.push_back(nullptr);
}

View File

@ -12,11 +12,6 @@
namespace Slic3r {
namespace ClipperLib {
class PolyNode;
using PolyNodes = std::vector<PolyNode*>;
}
namespace Geometry {
// Generic result of an orientation predicate.

View File

@ -19,6 +19,8 @@
#include <unordered_map>
#include <vector>
#include <oneapi/tbb/scalable_allocator.h>
//#define DEBUG_FILES
#ifdef DEBUG_FILES
#include "libslic3r/SVG.hpp"
@ -267,7 +269,7 @@ Polyline JPSPathFinder::find_path(const Point &p0, const Point &p1)
using QNode = astar::QNode<JPSTracer<Pixel, decltype(cell_query)>>;
std::unordered_map<size_t, QNode> astar_cache{};
std::vector<Pixel> out_path;
std::vector<Pixel, tbb::scalable_allocator<Pixel>> out_path;
std::vector<decltype(tracer)::Node> out_nodes;
if (!astar::search_route(tracer, {start, {0, 0}}, std::back_inserter(out_nodes), astar_cache)) {
@ -306,7 +308,7 @@ Polyline JPSPathFinder::find_path(const Point &p0, const Point &p1)
svg.draw(scaled_point(start), "green", scale_(0.4));
#endif
std::vector<Pixel> tmp_path;
std::vector<Pixel, tbb::scalable_allocator<Pixel>> tmp_path;
tmp_path.reserve(out_path.size());
// Some path found, reverse and remove points that do not change direction
std::reverse(out_path.begin(), out_path.end());

View File

@ -103,9 +103,9 @@ bool MultiPoint::remove_duplicate_points()
return false;
}
std::vector<Point> MultiPoint::_douglas_peucker(const std::vector<Point>& pts, const double tolerance)
Points MultiPoint::_douglas_peucker(const Points &pts, const double tolerance)
{
std::vector<Point> result_pts;
Points result_pts;
double tolerance_sq = tolerance * tolerance;
if (! pts.empty()) {
const Point *anchor = &pts.front();

View File

@ -110,7 +110,7 @@ public:
};
extern BoundingBox get_extents(const MultiPoint &mp);
extern BoundingBox get_extents_rotated(const std::vector<Point> &points, double angle);
extern BoundingBox get_extents_rotated(const Points &points, double angle);
extern BoundingBox get_extents_rotated(const MultiPoint &mp, double angle);
inline double length(const Points &pts) {

View File

@ -57,7 +57,7 @@ void Point::rotate(double angle, const Point &center)
(*this)(1) = (coord_t)round( (double)center(1) + c * dy + s * dx );
}
bool has_duplicate_points(std::vector<Point> &&pts)
bool has_duplicate_points(Points &&pts)
{
std::sort(pts.begin(), pts.end());
for (size_t i = 1; i < pts.size(); ++ i)
@ -97,15 +97,15 @@ template BoundingBox get_extents<true>(const Points &pts);
// if IncludeBoundary, then a bounding box is defined even for a single point.
// otherwise a bounding box is only defined if it has a positive area.
template<bool IncludeBoundary>
BoundingBox get_extents(const std::vector<Points> &pts)
BoundingBox get_extents(const VecOfPoints &pts)
{
BoundingBox bbox;
for (const Points &p : pts)
bbox.merge(get_extents<IncludeBoundary>(p));
return bbox;
}
template BoundingBox get_extents<false>(const std::vector<Points> &pts);
template BoundingBox get_extents<true>(const std::vector<Points> &pts);
template BoundingBox get_extents<false>(const VecOfPoints &pts);
template BoundingBox get_extents<true>(const VecOfPoints &pts);
BoundingBoxf get_extents(const std::vector<Vec2d> &pts)
{

View File

@ -9,6 +9,9 @@
#include <sstream>
#include <unordered_map>
#include <oneapi/tbb/scalable_allocator.h>
#include <Eigen/Geometry>
#include "LocalesUtils.hpp"
@ -49,7 +52,7 @@ using Vec2d = Eigen::Matrix<double, 2, 1, Eigen::DontAlign>;
using Vec3d = Eigen::Matrix<double, 3, 1, Eigen::DontAlign>;
using Vec4d = Eigen::Matrix<double, 4, 1, Eigen::DontAlign>;
using Points = std::vector<Point>;
using Points = std::vector<Point, tbb::scalable_allocator<Point>>;
using PointPtrs = std::vector<Point*>;
using PointConstPtrs = std::vector<const Point*>;
using Points3 = std::vector<Vec3crd>;
@ -57,6 +60,8 @@ using Pointfs = std::vector<Vec2d>;
using Vec2ds = std::vector<Vec2d>;
using Pointf3s = std::vector<Vec3d>;
using VecOfPoints = std::vector<Points, tbb::scalable_allocator<Points>>;
using Matrix2f = Eigen::Matrix<float, 2, 2, Eigen::DontAlign>;
using Matrix2d = Eigen::Matrix<double, 2, 2, Eigen::DontAlign>;
using Matrix3f = Eigen::Matrix<float, 3, 3, Eigen::DontAlign>;
@ -247,9 +252,9 @@ extern template BoundingBox get_extents<true>(const Points &pts);
// if IncludeBoundary, then a bounding box is defined even for a single point.
// otherwise a bounding box is only defined if it has a positive area.
template<bool IncludeBoundary = false>
BoundingBox get_extents(const std::vector<Points> &pts);
extern template BoundingBox get_extents<false>(const std::vector<Points> &pts);
extern template BoundingBox get_extents<true>(const std::vector<Points> &pts);
BoundingBox get_extents(const VecOfPoints &pts);
extern template BoundingBox get_extents<false>(const VecOfPoints &pts);
extern template BoundingBox get_extents<true>(const VecOfPoints &pts);
BoundingBoxf get_extents(const std::vector<Vec2d> &pts);
@ -263,16 +268,16 @@ inline std::pair<Point, bool> nearest_point(const Points &points, const Point &p
// Test for duplicate points in a vector of points.
// The points are copied, sorted and checked for duplicates globally.
bool has_duplicate_points(std::vector<Point> &&pts);
inline bool has_duplicate_points(const std::vector<Point> &pts)
bool has_duplicate_points(Points &&pts);
inline bool has_duplicate_points(const Points &pts)
{
std::vector<Point> cpy = pts;
Points cpy = pts;
return has_duplicate_points(std::move(cpy));
}
// Test for duplicate points in a vector of points.
// Only successive points are checked for equality.
inline bool has_duplicate_successive_points(const std::vector<Point> &pts)
inline bool has_duplicate_successive_points(const Points &pts)
{
for (size_t i = 1; i < pts.size(); ++ i)
if (pts[i - 1] == pts[i])
@ -282,7 +287,7 @@ inline bool has_duplicate_successive_points(const std::vector<Point> &pts)
// Test for duplicate points in a vector of points.
// Only successive points are checked for equality. Additionally, first and last points are compared for equality.
inline bool has_duplicate_successive_points_closed(const std::vector<Point> &pts)
inline bool has_duplicate_successive_points_closed(const Points &pts)
{
return has_duplicate_successive_points(pts) || (pts.size() >= 2 && pts.front() == pts.back());
}

View File

@ -404,7 +404,7 @@ bool has_duplicate_points(const Polygons &polys)
// Check globally.
#if 0
// Detect duplicates by sorting with quicksort. It is quite fast, but ankerl::unordered_dense is around 1/4 faster.
std::vector<Point> allpts;
Points allpts;
allpts.reserve(count_points(polys));
for (const Polygon &poly : polys)
allpts.insert(allpts.end(), poly.points.begin(), poly.points.end());

View File

@ -5,6 +5,7 @@
#include <vector>
#include <string>
#include "Line.hpp"
#include "Point.hpp"
#include "MultiPoint.hpp"
#include "Polyline.hpp"
@ -241,7 +242,7 @@ inline Polylines to_polylines(Polygons &&polys)
return polylines;
}
inline Polygons to_polygons(const std::vector<Points> &paths)
inline Polygons to_polygons(const VecOfPoints &paths)
{
Polygons out;
out.reserve(paths.size());
@ -250,7 +251,7 @@ inline Polygons to_polygons(const std::vector<Points> &paths)
return out;
}
inline Polygons to_polygons(std::vector<Points> &&paths)
inline Polygons to_polygons(VecOfPoints &&paths)
{
Polygons out;
out.reserve(paths.size());

View File

@ -17,7 +17,7 @@ namespace EdgeGrid {
struct TrimmedLoop
{
std::vector<Point> points;
Points points;
// Number of points per segment. Empty if the loop is
std::vector<unsigned int> segments;

View File

@ -158,9 +158,10 @@ inline void polylines_append(Polylines &dst, Polylines &&src)
// src_first: the merge point is at src.begin() or src.end()?
// The orientation of the resulting polyline is unknown, the output polyline may start
// either with src piece or dst piece.
template<typename PointType>
inline void polylines_merge(std::vector<PointType> &dst, bool dst_first, std::vector<PointType> &&src, bool src_first)
template<typename PointsType>
inline void polylines_merge(PointsType &dst, bool dst_first, PointsType &&src, bool src_first)
{
using PointType = typename PointsType::value_type;
if (dst_first) {
if (src_first)
std::reverse(dst.begin(), dst.end());

View File

@ -1132,9 +1132,9 @@ Polygons Print::first_layer_islands() const
return islands;
}
std::vector<Point> Print::first_layer_wipe_tower_corners() const
Points Print::first_layer_wipe_tower_corners() const
{
std::vector<Point> pts_scaled;
Points pts_scaled;
if (has_wipe_tower() && ! m_wipe_tower_data.tool_changes.empty()) {
double width = m_config.wipe_tower_width + 2*m_wipe_tower_data.brim_width;

View File

@ -626,7 +626,7 @@ private:
// Islands of objects and their supports extruded at the 1st layer.
Polygons first_layer_islands() const;
// Return 4 wipe tower corners in the world coordinates (shifted and rotated), including the wipe tower brim.
std::vector<Point> first_layer_wipe_tower_corners() const;
Points first_layer_wipe_tower_corners() const;
// Returns true if any of the print_objects has print_object_step valid.
// That means data shared by all print objects of the print_objects span may still use the shared data.

View File

@ -1990,8 +1990,8 @@ void PrintObject::bridge_over_infill()
// reconstruct polygon from polygon sections
struct TracedPoly
{
std::vector<Point> lows;
std::vector<Point> highs;
Points lows;
Points highs;
};
std::vector<TracedPoly> current_traced_polys;

View File

@ -43,7 +43,8 @@ Point ConcaveHull::centroid(const Points &pp)
Points ConcaveHull::calculate_centroids() const
{
// We get the centroids of all the islands in the 2D slice
Points centroids = reserve_vector<Point>(m_polys.size());
Points centroids;
centroids.reserve(m_polys.size());
std::transform(m_polys.begin(), m_polys.end(),
std::back_inserter(centroids),
[](const Polygon &poly) { return centroid(poly); });

View File

@ -8,10 +8,15 @@
#include <utility>
#include <vector>
namespace ClipperLib { class PolyNode; }
#include <oneapi/tbb/scalable_allocator.h>
namespace Slic3r {
namespace ClipperLib {
class PolyNode;
using PolyNodes = std::vector<PolyNode*, tbb::scalable_allocator<PolyNode*>>;
}
class ExPolygon;
using ExPolygons = std::vector<ExPolygon>;
@ -29,7 +34,7 @@ void chain_and_reorder_extrusion_paths(std::vect
Polylines chain_polylines(Polylines &&src, const Point *start_near = nullptr);
inline Polylines chain_polylines(const Polylines& src, const Point* start_near = nullptr) { Polylines tmp(src); return chain_polylines(std::move(tmp), start_near); }
std::vector<ClipperLib::PolyNode*> chain_clipper_polynodes(const Points &points, const std::vector<ClipperLib::PolyNode*> &items);
ClipperLib::PolyNodes chain_clipper_polynodes(const Points &points, const ClipperLib::PolyNodes &items);
// Chain instances of print objects by an approximate shortest path.
// Returns pairs of PrintObject idx and instance of that PrintObject.

View File

@ -106,8 +106,8 @@ enum Axis {
NUM_AXES_WITH_UNKNOWN,
};
template <typename T>
inline void append(std::vector<T>& dest, const std::vector<T>& src)
template <typename T, typename Alloc, typename Alloc2>
inline void append(std::vector<T, Alloc> &dest, const std::vector<T, Alloc2> &src)
{
if (dest.empty())
dest = src; // copy
@ -115,8 +115,8 @@ inline void append(std::vector<T>& dest, const std::vector<T>& src)
dest.insert(dest.end(), src.begin(), src.end());
}
template <typename T>
inline void append(std::vector<T>& dest, std::vector<T>&& src)
template <typename T, typename Alloc>
inline void append(std::vector<T, Alloc> &dest, std::vector<T, Alloc> &&src)
{
if (dest.empty())
dest = std::move(src);

View File

@ -2,7 +2,7 @@ get_filename_component(_TEST_NAME ${CMAKE_CURRENT_LIST_DIR} NAME)
add_executable(${_TEST_NAME}_tests ${_TEST_NAME}_tests_main.cpp printer_parts.cpp printer_parts.hpp)
# mold linker for successful linking needs also to link TBB library and link it before libslic3r.
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb libnest2d )
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb TBB::tbbmalloc libnest2d )
set_property(TARGET ${_TEST_NAME}_tests PROPERTY FOLDER "tests")
# catch_discover_tests(${_TEST_NAME}_tests TEST_PREFIX "${_TEST_NAME}: ")

View File

@ -83,7 +83,7 @@ TEST_CASE("Line::perpendicular_to", "[Geometry]") {
TEST_CASE("Polygon::contains works properly", "[Geometry]"){
// this test was failing on Windows (GH #1950)
Slic3r::Polygon polygon(std::vector<Point>({
Slic3r::Polygon polygon(Points({
Point(207802834,-57084522),
Point(196528149,-37556190),
Point(173626821,-25420928),
@ -145,7 +145,7 @@ SCENARIO("polygon_is_convex works") {
TEST_CASE("Creating a polyline generates the obvious lines", "[Geometry]"){
Slic3r::Polyline polyline;
polyline.points = std::vector<Point>({Point(0, 0), Point(10, 0), Point(20, 0)});
polyline.points = Points({Point(0, 0), Point(10, 0), Point(20, 0)});
REQUIRE(polyline.lines().at(0).a == Point(0,0));
REQUIRE(polyline.lines().at(0).b == Point(10,0));
REQUIRE(polyline.lines().at(1).a == Point(10,0));
@ -153,7 +153,7 @@ TEST_CASE("Creating a polyline generates the obvious lines", "[Geometry]"){
}
TEST_CASE("Splitting a Polygon generates a polyline correctly", "[Geometry]"){
Slic3r::Polygon polygon(std::vector<Point>({Point(0, 0), Point(10, 0), Point(5, 5)}));
Slic3r::Polygon polygon(Points({Point(0, 0), Point(10, 0), Point(5, 5)}));
Slic3r::Polyline split = polygon.split_at_index(1);
REQUIRE(split.points[0]==Point(10,0));
REQUIRE(split.points[1]==Point(5,5));
@ -164,7 +164,7 @@ TEST_CASE("Splitting a Polygon generates a polyline correctly", "[Geometry]"){
SCENARIO("BoundingBox", "[Geometry]") {
WHEN("Bounding boxes are scaled") {
BoundingBox bb(std::vector<Point>({Point(0, 1), Point(10, 2), Point(20, 2)}));
BoundingBox bb(Points({Point(0, 1), Point(10, 2), Point(20, 2)}));
bb.scale(2);
REQUIRE(bb.min == Point(0,2));
REQUIRE(bb.max == Point(40,4));
@ -193,7 +193,7 @@ SCENARIO("BoundingBox", "[Geometry]") {
TEST_CASE("Offseting a line generates a polygon correctly", "[Geometry]"){
Slic3r::Polyline tmp = { Point(10,10), Point(20,10) };
Slic3r::Polygon area = offset(tmp,5).at(0);
REQUIRE(area.area() == Slic3r::Polygon(std::vector<Point>({Point(10,5),Point(20,5),Point(20,15),Point(10,15)})).area());
REQUIRE(area.area() == Slic3r::Polygon(Points({Point(10,5),Point(20,5),Point(20,15),Point(10,15)})).area());
}
SCENARIO("Circle Fit, TaubinFit with Newton's method", "[Geometry]") {
@ -308,7 +308,7 @@ TEST_CASE("smallest_enclosing_circle_welzl", "[Geometry]") {
SCENARIO("Path chaining", "[Geometry]") {
GIVEN("A path") {
std::vector<Point> points = { Point(26,26),Point(52,26),Point(0,26),Point(26,52),Point(26,0),Point(0,52),Point(52,52),Point(52,0) };
Points points = { Point(26,26),Point(52,26),Point(0,26),Point(26,52),Point(26,0),Point(0,52),Point(52,52),Point(52,0) };
THEN("Chained with no diagonals (thus 26 units long)") {
std::vector<Points::size_type> indices = chain_points(points);
for (Points::size_type i = 0; i + 1 < indices.size(); ++ i) {
@ -431,7 +431,7 @@ SCENARIO("Calculating angles", "[Geometry]")
SCENARIO("Polygon convex/concave detection", "[Geometry]"){
static constexpr const double angle_threshold = M_PI / 3.;
GIVEN(("A Square with dimension 100")){
auto square = Slic3r::Polygon /*new_scale*/(std::vector<Point>({
auto square = Slic3r::Polygon /*new_scale*/(Points({
Point(100,100),
Point(200,100),
Point(200,200),
@ -447,7 +447,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
}
}
GIVEN("A Square with an extra colinearvertex"){
auto square = Slic3r::Polygon /*new_scale*/(std::vector<Point>({
auto square = Slic3r::Polygon /*new_scale*/(Points({
Point(150,100),
Point(200,100),
Point(200,200),
@ -459,7 +459,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
}
}
GIVEN("A Square with an extra collinear vertex in different order"){
auto square = Slic3r::Polygon /*new_scale*/(std::vector<Point>({
auto square = Slic3r::Polygon /*new_scale*/(Points({
Point(200,200),
Point(100,200),
Point(100,100),
@ -472,7 +472,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
}
GIVEN("A triangle"){
auto triangle = Slic3r::Polygon(std::vector<Point>({
auto triangle = Slic3r::Polygon(Points({
Point(16000170,26257364),
Point(714223,461012),
Point(31286371,461008)
@ -484,7 +484,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
}
GIVEN("A triangle with an extra collinear point"){
auto triangle = Slic3r::Polygon(std::vector<Point>({
auto triangle = Slic3r::Polygon(Points({
Point(16000170,26257364),
Point(714223,461012),
Point(20000000,461012),
@ -498,7 +498,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
GIVEN("A polygon with concave vertices with angles of specifically 4/3pi"){
// Two concave vertices of this polygon have angle = PI*4/3, so this test fails
// if epsilon is not used.
auto polygon = Slic3r::Polygon(std::vector<Point>({
auto polygon = Slic3r::Polygon(Points({
Point(60246458,14802768),Point(64477191,12360001),
Point(63727343,11060995),Point(64086449,10853608),
Point(66393722,14850069),Point(66034704,15057334),
@ -516,7 +516,7 @@ SCENARIO("Polygon convex/concave detection", "[Geometry]"){
}
TEST_CASE("Triangle Simplification does not result in less than 3 points", "[Geometry]"){
auto triangle = Slic3r::Polygon(std::vector<Point>({
auto triangle = Slic3r::Polygon(Points({
Point(16000170,26257364), Point(714223,461012), Point(31286371,461008)
}));
REQUIRE(triangle.simplify(250000).at(0).points.size() == 3);

View File

@ -8,7 +8,7 @@ add_executable(${_TEST_NAME}_tests ${_TEST_NAME}_tests_main.cpp
sla_archive_readwrite_tests.cpp)
# mold linker for successful linking needs also to link TBB library and link it before libslic3r.
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb libslic3r)
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb TBB::tbbmalloc libslic3r)
set_property(TARGET ${_TEST_NAME}_tests PROPERTY FOLDER "tests")
if (WIN32)

View File

@ -6,7 +6,7 @@ add_executable(${_TEST_NAME}_tests
)
# mold linker for successful linking needs also to link TBB library and link it before libslic3r.
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb libslic3r_gui libslic3r)
target_link_libraries(${_TEST_NAME}_tests test_common TBB::tbb TBB::tbbmalloc libslic3r_gui libslic3r)
if (MSVC)
target_link_libraries(${_TEST_NAME}_tests Setupapi.lib)
endif ()