Welcome to mirror list, hosted at ThFree Co, Russian Federation.

github.com/prusa3d/PrusaSlicer.git - Unnamed repository; edit this file 'description' to name the repository.
summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
Diffstat (limited to 'src/libslic3r/Geometry.hpp')
-rw-r--r--src/libslic3r/Geometry.hpp255
1 files changed, 182 insertions, 73 deletions
diff --git a/src/libslic3r/Geometry.hpp b/src/libslic3r/Geometry.hpp
index 1fa15ba63..f8d3b0a5c 100644
--- a/src/libslic3r/Geometry.hpp
+++ b/src/libslic3r/Geometry.hpp
@@ -10,6 +10,7 @@
// Serialization through the Cereal library
#include <cereal/access.hpp>
+#define BOOST_VORONOI_USE_GMP 1
#include "boost/polygon/voronoi.hpp"
namespace ClipperLib {
@@ -114,32 +115,145 @@ inline bool segment_segment_intersection(const Vec2d &p1, const Vec2d &v1, const
return true;
}
-
-inline int segments_could_intersect(
+inline bool segments_intersect(
const Slic3r::Point &ip1, const Slic3r::Point &ip2,
const Slic3r::Point &jp1, const Slic3r::Point &jp2)
+{
+ assert(ip1 != ip2);
+ assert(jp1 != jp2);
+
+ auto segments_could_intersect = [](
+ const Slic3r::Point &ip1, const Slic3r::Point &ip2,
+ const Slic3r::Point &jp1, const Slic3r::Point &jp2) -> std::pair<int, int>
+ {
+ Vec2i64 iv = (ip2 - ip1).cast<int64_t>();
+ Vec2i64 vij1 = (jp1 - ip1).cast<int64_t>();
+ Vec2i64 vij2 = (jp2 - ip1).cast<int64_t>();
+ int64_t tij1 = cross2(iv, vij1);
+ int64_t tij2 = cross2(iv, vij2);
+ return std::make_pair(
+ // signum
+ (tij1 > 0) ? 1 : ((tij1 < 0) ? -1 : 0),
+ (tij2 > 0) ? 1 : ((tij2 < 0) ? -1 : 0));
+ };
+
+ std::pair<int, int> sign1 = segments_could_intersect(ip1, ip2, jp1, jp2);
+ std::pair<int, int> sign2 = segments_could_intersect(jp1, jp2, ip1, ip2);
+ int test1 = sign1.first * sign1.second;
+ int test2 = sign2.first * sign2.second;
+ if (test1 <= 0 && test2 <= 0) {
+ // The segments possibly intersect. They may also be collinear, but not intersect.
+ if (test1 != 0 || test2 != 0)
+ // Certainly not collinear, then the segments intersect.
+ return true;
+ // If the first segment is collinear with the other, the other is collinear with the first segment.
+ assert((sign1.first == 0 && sign1.second == 0) == (sign2.first == 0 && sign2.second == 0));
+ if (sign1.first == 0 && sign1.second == 0) {
+ // The segments are certainly collinear. Now verify whether they overlap.
+ Slic3r::Point vi = ip2 - ip1;
+ // Project both on the longer coordinate of vi.
+ int axis = std::abs(vi.x()) > std::abs(vi.y()) ? 0 : 1;
+ coord_t i = ip1(axis);
+ coord_t j = ip2(axis);
+ coord_t k = jp1(axis);
+ coord_t l = jp2(axis);
+ if (i > j)
+ std::swap(i, j);
+ if (k > l)
+ std::swap(k, l);
+ return (k >= i && k <= j) || (i >= k && i <= l);
+ }
+ }
+ return false;
+}
+
+template<typename T> inline T foot_pt(const T &line_pt, const T &line_dir, const T &pt)
{
- Vec2i64 iv = (ip2 - ip1).cast<int64_t>();
- Vec2i64 vij1 = (jp1 - ip1).cast<int64_t>();
- Vec2i64 vij2 = (jp2 - ip1).cast<int64_t>();
- int64_t tij1 = cross2(iv, vij1);
- int64_t tij2 = cross2(iv, vij2);
- int sij1 = (tij1 > 0) ? 1 : ((tij1 < 0) ? -1 : 0); // signum
- int sij2 = (tij2 > 0) ? 1 : ((tij2 < 0) ? -1 : 0);
- return sij1 * sij2;
+ T v = pt - line_pt;
+ auto l2 = line_dir.squaredNorm();
+ auto t = (l2 == 0) ? 0 : v.dot(line_dir) / l2;
+ return line_pt + line_dir * t;
}
-inline bool segments_intersect(
- const Slic3r::Point &ip1, const Slic3r::Point &ip2,
- const Slic3r::Point &jp1, const Slic3r::Point &jp2)
+inline Vec2d foot_pt(const Line &iline, const Point &ipt)
+{
+ return foot_pt<Vec2d>(iline.a.cast<double>(), (iline.b - iline.a).cast<double>(), ipt.cast<double>());
+}
+
+template<typename T> inline auto ray_point_distance_squared(const T &ray_pt, const T &ray_dir, const T &pt)
{
- return segments_could_intersect(ip1, ip2, jp1, jp2) <= 0 &&
- segments_could_intersect(jp1, jp2, ip1, ip2) <= 0;
+ return (foot_pt(ray_pt, ray_dir, pt) - pt).squaredNorm();
+}
+
+template<typename T> inline auto ray_point_distance(const T &ray_pt, const T &ray_dir, const T &pt)
+{
+ return (foot_pt(ray_pt, ray_dir, pt) - pt).norm();
+}
+
+inline double ray_point_distance_squared(const Line &iline, const Point &ipt)
+{
+ return (foot_pt(iline, ipt) - ipt.cast<double>()).squaredNorm();
+}
+
+inline double ray_point_distance(const Line &iline, const Point &ipt)
+{
+ return (foot_pt(iline, ipt) - ipt.cast<double>()).norm();
}
// Based on Liang-Barsky function by Daniel White @ http://www.skytopia.com/project/articles/compsci/clipping.html
template<typename T>
-bool liang_barsky_line_clipping(
+inline bool liang_barsky_line_clipping_interval(
+ // Start and end points of the source line, result will be stored there as well.
+ const Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &x0,
+ const Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &v,
+ // Bounding box to clip with.
+ const BoundingBoxBase<Eigen::Matrix<T, 2, 1, Eigen::DontAlign>> &bbox,
+ std::pair<double, double> &out_interval)
+{
+ double t0 = 0.0;
+ double t1 = 1.0;
+ // Traverse through left, right, bottom, top edges.
+ auto clip_side = [&x0, &v, &bbox, &t0, &t1](double p, double q) -> bool {
+ if (p == 0) {
+ if (q < 0)
+ // Line parallel to the bounding box edge is fully outside of the bounding box.
+ return false;
+ // else don't clip
+ } else {
+ double r = q / p;
+ if (p < 0) {
+ if (r > t1)
+ // Fully clipped.
+ return false;
+ if (r > t0)
+ // Partially clipped.
+ t0 = r;
+ } else {
+ assert(p > 0);
+ if (r < t0)
+ // Fully clipped.
+ return false;
+ if (r < t1)
+ // Partially clipped.
+ t1 = r;
+ }
+ }
+ return true;
+ };
+
+ if (clip_side(- v.x(), - bbox.min.x() + x0.x()) &&
+ clip_side( v.x(), bbox.max.x() - x0.x()) &&
+ clip_side(- v.y(), - bbox.min.y() + x0.y()) &&
+ clip_side( v.y(), bbox.max.y() - x0.y())) {
+ out_interval.first = t0;
+ out_interval.second = t1;
+ return true;
+ }
+ return false;
+}
+
+template<typename T>
+inline bool liang_barsky_line_clipping(
// Start and end points of the source line, result will be stored there as well.
Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &x0,
Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &x1,
@@ -147,50 +261,14 @@ bool liang_barsky_line_clipping(
const BoundingBoxBase<Eigen::Matrix<T, 2, 1, Eigen::DontAlign>> &bbox)
{
Eigen::Matrix<T, 2, 1, Eigen::DontAlign> v = x1 - x0;
- double t0 = 0.0;
- double t1 = 1.0;
-
- // Traverse through left, right, bottom, top edges.
- for (int edge = 0; edge < 4; ++ edge)
- {
- double p, q;
- switch (edge) {
- case 0: p = - v.x(); q = - bbox.min.x() + x0.x(); break;
- case 1: p = v.x(); q = bbox.max.x() - x0.x(); break;
- case 2: p = - v.y(); q = - bbox.min.y() + x0.y(); break;
- default: p = v.y(); q = bbox.max.y() - x0.y(); break;
- }
-
- if (p == 0) {
- if (q < 0)
- // Line parallel to the bounding box edge is fully outside of the bounding box.
- return false;
- // else don't clip
- } else {
- double r = q / p;
- if (p < 0) {
- if (r > t1)
- // Fully clipped.
- return false;
- if (r > t0)
- // Partially clipped.
- t0 = r;
- } else {
- assert(p > 0);
- if (r < t0)
- // Fully clipped.
- return false;
- if (r < t1)
- // Partially clipped.
- t1 = r;
- }
- }
+ std::pair<double, double> interval;
+ if (liang_barsky_line_clipping_interval(x0, v, bbox, interval)) {
+ // Clipped successfully.
+ x1 = x0 + interval.second * v;
+ x0 += interval.first * v;
+ return true;
}
-
- // Clipped successfully.
- x1 = x0 + t1 * v;
- x0 += t0 * v;
- return true;
+ return false;
}
// Based on Liang-Barsky function by Daniel White @ http://www.skytopia.com/project/articles/compsci/clipping.html
@@ -210,6 +288,35 @@ bool liang_barsky_line_clipping(
return liang_barsky_line_clipping(x0clip, x1clip, bbox);
}
+// Ugly named variant, that accepts the squared line
+// Don't call me with a nearly zero length vector!
+template<typename T>
+int ray_circle_intersections_r2_lv2_c(T r2, T a, T b, T lv2, T c, std::pair<Eigen::Matrix<T, 2, 1, Eigen::DontAlign>, Eigen::Matrix<T, 2, 1, Eigen::DontAlign>> &out)
+{
+ T x0 = - a * c / lv2;
+ T y0 = - b * c / lv2;
+ T d = r2 - c * c / lv2;
+ if (d < T(0))
+ return 0;
+ T mult = sqrt(d / lv2);
+ out.first.x() = x0 + b * mult;
+ out.first.y() = y0 - a * mult;
+ out.second.x() = x0 - b * mult;
+ out.second.y() = y0 + a * mult;
+ return mult == T(0) ? 1 : 2;
+}
+template<typename T>
+int ray_circle_intersections(T r, T a, T b, T c, std::pair<Eigen::Matrix<T, 2, 1, Eigen::DontAlign>, Eigen::Matrix<T, 2, 1, Eigen::DontAlign>> &out)
+{
+ T lv2 = a * a + b * b;
+ if (lv2 < T(SCALED_EPSILON * SCALED_EPSILON)) {
+ //FIXME what is the correct epsilon?
+ // What if the line touches the circle?
+ return false;
+ }
+ return ray_circle_intersections_r2_lv2_c2(r * r, a, b, a * a + b * b, c, out);
+}
+
Pointf3s convex_hull(Pointf3s points);
Polygon convex_hull(Points points);
Polygon convex_hull(const Polygons &polygons);
@@ -218,7 +325,7 @@ bool directions_parallel(double angle1, double angle2, double max_diff = 0);
template<class T> bool contains(const std::vector<T> &vector, const Point &point);
template<typename T> T rad2deg(T angle) { return T(180.0) * angle / T(PI); }
double rad2deg_dir(double angle);
-template<typename T> T deg2rad(T angle) { return T(PI) * angle / T(180.0); }
+template<typename T> constexpr T deg2rad(const T angle) { return T(PI) * angle / T(180.0); }
template<typename T> T angle_to_0_2PI(T angle)
{
static const T TWO_PI = T(2) * T(PI);
@@ -235,12 +342,12 @@ template<typename T> T angle_to_0_2PI(T angle)
}
/// Find the center of the circle corresponding to the vector of Points as an arc.
-Point circle_taubin_newton(const Points::const_iterator& input_start, const Points::const_iterator& input_end, size_t cycles = 20);
-inline Point circle_taubin_newton(const Points& input, size_t cycles = 20) { return circle_taubin_newton(input.cbegin(), input.cend(), cycles); }
+Point circle_center_taubin_newton(const Points::const_iterator& input_start, const Points::const_iterator& input_end, size_t cycles = 20);
+inline Point circle_center_taubin_newton(const Points& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
/// Find the center of the circle corresponding to the vector of Pointfs as an arc.
-Vec2d circle_taubin_newton(const Vec2ds::const_iterator& input_start, const Vec2ds::const_iterator& input_end, size_t cycles = 20);
-inline Vec2d circle_taubin_newton(const Vec2ds& input, size_t cycles = 20) { return circle_taubin_newton(input.cbegin(), input.cend(), cycles); }
+Vec2d circle_center_taubin_newton(const Vec2ds::const_iterator& input_start, const Vec2ds::const_iterator& input_end, size_t cycles = 20);
+inline Vec2d circle_center_taubin_newton(const Vec2ds& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
void simplify_polygons(const Polygons &polygons, double tolerance, Polygons* retval);
@@ -251,8 +358,16 @@ bool arrange(
// output
Pointfs &positions);
+class VoronoiDiagram : public boost::polygon::voronoi_diagram<double> {
+public:
+ typedef double coord_type;
+ typedef boost::polygon::point_data<coordinate_type> point_type;
+ typedef boost::polygon::segment_data<coordinate_type> segment_type;
+ typedef boost::polygon::rectangle_data<coordinate_type> rect_type;
+};
+
class MedialAxis {
- public:
+public:
Lines lines;
const ExPolygon* expolygon;
double max_width;
@@ -262,14 +377,8 @@ class MedialAxis {
void build(ThickPolylines* polylines);
void build(Polylines* polylines);
- private:
- class VD : public boost::polygon::voronoi_diagram<double> {
- public:
- typedef double coord_type;
- typedef boost::polygon::point_data<coordinate_type> point_type;
- typedef boost::polygon::segment_data<coordinate_type> segment_type;
- typedef boost::polygon::rectangle_data<coordinate_type> rect_type;
- };
+private:
+ using VD = VoronoiDiagram;
VD vd;
std::set<const VD::edge_type*> edges, valid_edges;
std::map<const VD::edge_type*, std::pair<coordf_t,coordf_t> > thickness;