Fixes of the offset curves from Voronoi diagram.
The offset curve extractor is already quite usable, though singular cases are still not covered yet when the offset curve intersects or nearly intersects a Voronoi vertex. Removal of the PRINTF_ZU "%zu" Visual Studio printf compatibility macro. Fixes of a contours self intersection test for collinear segments. SVG exporter now exports white background, so that the GNOME Eye viewer is usable.
This commit is contained in:
parent
af5c3583e8
commit
b101a8e266
16 changed files with 749 additions and 343 deletions
|
@ -53,7 +53,7 @@ void BridgeDetector::initialize()
|
||||||
this->_edges = intersection_pl(to_polylines(grown), contours);
|
this->_edges = intersection_pl(to_polylines(grown), contours);
|
||||||
|
|
||||||
#ifdef SLIC3R_DEBUG
|
#ifdef SLIC3R_DEBUG
|
||||||
printf(" bridge has " PRINTF_ZU " support(s)\n", this->_edges.size());
|
printf(" bridge has %zu support(s)\n", this->_edges.size());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// detect anchors as intersection between our bridge expolygon and the lower slices
|
// detect anchors as intersection between our bridge expolygon and the lower slices
|
||||||
|
|
|
@ -1586,12 +1586,17 @@ std::vector<std::pair<EdgeGrid::Grid::ContourEdge, EdgeGrid::Grid::ContourEdge>>
|
||||||
++ cnt;
|
++ cnt;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
len /= double(cnt);
|
|
||||||
bbox.offset(20);
|
std::vector<std::pair<EdgeGrid::Grid::ContourEdge, EdgeGrid::Grid::ContourEdge>> out;
|
||||||
EdgeGrid::Grid grid;
|
if (cnt > 0) {
|
||||||
grid.set_bbox(bbox);
|
len /= double(cnt);
|
||||||
grid.create(polygons, len);
|
bbox.offset(20);
|
||||||
return grid.intersecting_edges();
|
EdgeGrid::Grid grid;
|
||||||
|
grid.set_bbox(bbox);
|
||||||
|
grid.create(polygons, len);
|
||||||
|
out = grid.intersecting_edges();
|
||||||
|
}
|
||||||
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Find all pairs of intersectiong edges from the set of polygons, highlight them in an SVG.
|
// Find all pairs of intersectiong edges from the set of polygons, highlight them in an SVG.
|
||||||
|
|
|
@ -404,7 +404,7 @@ void ExPolygon::triangulate_pp(Polygons* polygons) const
|
||||||
{
|
{
|
||||||
TPPLPoly p;
|
TPPLPoly p;
|
||||||
p.Init(int(ex->contour.points.size()));
|
p.Init(int(ex->contour.points.size()));
|
||||||
//printf(PRINTF_ZU "\n0\n", ex->contour.points.size());
|
//printf("%zu\n0\n", ex->contour.points.size());
|
||||||
for (const Point &point : ex->contour.points) {
|
for (const Point &point : ex->contour.points) {
|
||||||
size_t i = &point - &ex->contour.points.front();
|
size_t i = &point - &ex->contour.points.front();
|
||||||
p[i].x = point(0);
|
p[i].x = point(0);
|
||||||
|
@ -419,7 +419,7 @@ void ExPolygon::triangulate_pp(Polygons* polygons) const
|
||||||
for (Polygons::const_iterator hole = ex->holes.begin(); hole != ex->holes.end(); ++hole) {
|
for (Polygons::const_iterator hole = ex->holes.begin(); hole != ex->holes.end(); ++hole) {
|
||||||
TPPLPoly p;
|
TPPLPoly p;
|
||||||
p.Init(hole->points.size());
|
p.Init(hole->points.size());
|
||||||
//printf(PRINTF_ZU "\n1\n", hole->points.size());
|
//printf("%zu\n1\n", hole->points.size());
|
||||||
for (const Point &point : hole->points) {
|
for (const Point &point : hole->points) {
|
||||||
size_t i = &point - &hole->points.front();
|
size_t i = &point - &hole->points.front();
|
||||||
p[i].x = point(0);
|
p[i].x = point(0);
|
||||||
|
|
|
@ -1218,7 +1218,7 @@ bool store_amf(const char* path, Model* model, const DynamicPrintConfig* config,
|
||||||
for (ModelInstance *instance : object->instances) {
|
for (ModelInstance *instance : object->instances) {
|
||||||
char buf[512];
|
char buf[512];
|
||||||
sprintf(buf,
|
sprintf(buf,
|
||||||
" <instance objectid=\"" PRINTF_ZU "\">\n"
|
" <instance objectid=\"%zu\">\n"
|
||||||
" <deltax>%lf</deltax>\n"
|
" <deltax>%lf</deltax>\n"
|
||||||
" <deltay>%lf</deltay>\n"
|
" <deltay>%lf</deltay>\n"
|
||||||
" <deltaz>%lf</deltaz>\n"
|
" <deltaz>%lf</deltaz>\n"
|
||||||
|
|
|
@ -393,7 +393,7 @@ GCodeSender::on_read(const boost::system::error_code& error,
|
||||||
}
|
}
|
||||||
this->send();
|
this->send();
|
||||||
} else {
|
} else {
|
||||||
printf("Cannot resend " PRINTF_ZU " (oldest we have is " PRINTF_ZU ")\n", toresend, this->sent - this->last_sent.size());
|
printf("Cannot resend %zu (oldest we have is %zu)\n", toresend, this->sent - this->last_sent.size());
|
||||||
}
|
}
|
||||||
} else if (boost::starts_with(line, "wait")) {
|
} else if (boost::starts_with(line, "wait")) {
|
||||||
// ignore
|
// ignore
|
||||||
|
|
|
@ -471,7 +471,7 @@ Pointfs arrange(size_t num_parts, const Vec2d &part_size, coordf_t gap, const Bo
|
||||||
size_t cellw = size_t(floor((bed_bbox.size()(0) + gap) / cell_size(0)));
|
size_t cellw = size_t(floor((bed_bbox.size()(0) + gap) / cell_size(0)));
|
||||||
size_t cellh = size_t(floor((bed_bbox.size()(1) + gap) / cell_size(1)));
|
size_t cellh = size_t(floor((bed_bbox.size()(1) + gap) / cell_size(1)));
|
||||||
if (num_parts > cellw * cellh)
|
if (num_parts > cellw * cellh)
|
||||||
throw std::invalid_argument(PRINTF_ZU " parts won't fit in your print area!\n", num_parts);
|
throw std::invalid_argument("%zu parts won't fit in your print area!\n", num_parts);
|
||||||
|
|
||||||
// Get a bounding box of cellw x cellh cells, centered at the center of the bed.
|
// Get a bounding box of cellw x cellh cells, centered at the center of the bed.
|
||||||
Vec2d cells_size(cellw * cell_size(0) - gap, cellh * cell_size(1) - gap);
|
Vec2d cells_size(cellw * cell_size(0) - gap, cellh * cell_size(1) - gap);
|
||||||
|
|
|
@ -115,32 +115,94 @@ inline bool segment_segment_intersection(const Vec2d &p1, const Vec2d &v1, const
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
inline int segments_could_intersect(
|
|
||||||
const Slic3r::Point &ip1, const Slic3r::Point &ip2,
|
|
||||||
const Slic3r::Point &jp1, const Slic3r::Point &jp2)
|
|
||||||
{
|
|
||||||
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;
|
|
||||||
}
|
|
||||||
|
|
||||||
inline bool segments_intersect(
|
inline bool segments_intersect(
|
||||||
const Slic3r::Point &ip1, const Slic3r::Point &ip2,
|
const Slic3r::Point &ip1, const Slic3r::Point &ip2,
|
||||||
const Slic3r::Point &jp1, const Slic3r::Point &jp2)
|
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)
|
||||||
{
|
{
|
||||||
return segments_could_intersect(ip1, ip2, jp1, jp2) <= 0 &&
|
T v = pt - line_pt;
|
||||||
segments_could_intersect(jp1, jp2, ip1, ip2) <= 0;
|
auto l2 = line_dir.squaredNorm();
|
||||||
|
auto t = (l2 == 0) ? 0 : v.dot(line_dir) / l2;
|
||||||
|
return line_pt + line_dir * t;
|
||||||
|
}
|
||||||
|
|
||||||
|
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 (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
|
// Based on Liang-Barsky function by Daniel White @ http://www.skytopia.com/project/articles/compsci/clipping.html
|
||||||
template<typename T>
|
template<typename T>
|
||||||
bool liang_barsky_line_clipping(
|
inline bool liang_barsky_line_clipping(
|
||||||
// Start and end points of the source line, result will be stored there as well.
|
// 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> &x0,
|
||||||
Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &x1,
|
Eigen::Matrix<T, 2, 1, Eigen::DontAlign> &x1,
|
||||||
|
|
|
@ -264,7 +264,7 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
||||||
this->flow(frInfill, true).scaled_width()
|
this->flow(frInfill, true).scaled_width()
|
||||||
);
|
);
|
||||||
#ifdef SLIC3R_DEBUG
|
#ifdef SLIC3R_DEBUG
|
||||||
printf("Processing bridge at layer " PRINTF_ZU ":\n", this->layer()->id());
|
printf("Processing bridge at layer %zu:\n", this->layer()->id());
|
||||||
#endif
|
#endif
|
||||||
double custom_angle = Geometry::deg2rad(this->region()->config().bridge_angle.value);
|
double custom_angle = Geometry::deg2rad(this->region()->config().bridge_angle.value);
|
||||||
if (bd.detect_angle(custom_angle)) {
|
if (bd.detect_angle(custom_angle)) {
|
||||||
|
|
|
@ -153,9 +153,11 @@ inline Lines to_lines(const Polygon &poly)
|
||||||
{
|
{
|
||||||
Lines lines;
|
Lines lines;
|
||||||
lines.reserve(poly.points.size());
|
lines.reserve(poly.points.size());
|
||||||
for (Points::const_iterator it = poly.points.begin(); it != poly.points.end()-1; ++it)
|
if (poly.points.size() > 2) {
|
||||||
lines.push_back(Line(*it, *(it + 1)));
|
for (Points::const_iterator it = poly.points.begin(); it != poly.points.end()-1; ++it)
|
||||||
lines.push_back(Line(poly.points.back(), poly.points.front()));
|
lines.push_back(Line(*it, *(it + 1)));
|
||||||
|
lines.push_back(Line(poly.points.back(), poly.points.front()));
|
||||||
|
}
|
||||||
return lines;
|
return lines;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -1431,7 +1431,7 @@ void PrintObject::bridge_over_infill()
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef SLIC3R_DEBUG
|
#ifdef SLIC3R_DEBUG
|
||||||
printf("Bridging " PRINTF_ZU " internal areas at layer " PRINTF_ZU "\n", to_bridge.size(), layer->id());
|
printf("Bridging %zu internal areas at layer %zu\n", to_bridge.size(), layer->id());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// compute the remaning internal solid surfaces as difference
|
// compute the remaning internal solid surfaces as difference
|
||||||
|
|
|
@ -21,6 +21,7 @@ bool SVG::open(const char* afilename)
|
||||||
" <polyline fill=\"darkblue\" points=\"0,0 10,5 0,10 1,5\" />\n"
|
" <polyline fill=\"darkblue\" points=\"0,0 10,5 0,10 1,5\" />\n"
|
||||||
" </marker>\n"
|
" </marker>\n"
|
||||||
);
|
);
|
||||||
|
fprintf(this->f, "<rect fill='white' stroke='none' x='0' y='0' width='%f' height='%f'/>\n", 2000.f, 2000.f);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -42,6 +43,7 @@ bool SVG::open(const char* afilename, const BoundingBox &bbox, const coord_t bbo
|
||||||
" <polyline fill=\"darkblue\" points=\"0,0 10,5 0,10 1,5\" />\n"
|
" <polyline fill=\"darkblue\" points=\"0,0 10,5 0,10 1,5\" />\n"
|
||||||
" </marker>\n",
|
" </marker>\n",
|
||||||
h, w);
|
h, w);
|
||||||
|
fprintf(this->f, "<rect fill='white' stroke='none' x='0' y='0' width='%f' height='%f'/>\n", w, h);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -952,7 +952,7 @@ void TriangleMeshSlicer::slice(const std::vector<float> &z, SlicingMode mode, co
|
||||||
[&layers_p, mode, closing_radius, layers, throw_on_cancel, this](const tbb::blocked_range<size_t>& range) {
|
[&layers_p, mode, closing_radius, layers, throw_on_cancel, this](const tbb::blocked_range<size_t>& range) {
|
||||||
for (size_t layer_id = range.begin(); layer_id < range.end(); ++ layer_id) {
|
for (size_t layer_id = range.begin(); layer_id < range.end(); ++ layer_id) {
|
||||||
#ifdef SLIC3R_TRIANGLEMESH_DEBUG
|
#ifdef SLIC3R_TRIANGLEMESH_DEBUG
|
||||||
printf("Layer " PRINTF_ZU " (slice_z = %.2f):\n", layer_id, z[layer_id]);
|
printf("Layer %zu (slice_z = %.2f):\n", layer_id, z[layer_id]);
|
||||||
#endif
|
#endif
|
||||||
throw_on_cancel();
|
throw_on_cancel();
|
||||||
ExPolygons &expolygons = (*layers)[layer_id];
|
ExPolygons &expolygons = (*layers)[layer_id];
|
||||||
|
@ -1779,7 +1779,7 @@ void TriangleMeshSlicer::make_expolygons(const Polygons &loops, const float clos
|
||||||
size_t holes_count = 0;
|
size_t holes_count = 0;
|
||||||
for (ExPolygons::const_iterator e = ex_slices.begin(); e != ex_slices.end(); ++ e)
|
for (ExPolygons::const_iterator e = ex_slices.begin(); e != ex_slices.end(); ++ e)
|
||||||
holes_count += e->holes.size();
|
holes_count += e->holes.size();
|
||||||
printf(PRINTF_ZU " surface(s) having " PRINTF_ZU " holes detected from " PRINTF_ZU " polylines\n",
|
printf("%zu surface(s) having %zu holes detected from %zu polylines\n",
|
||||||
ex_slices.size(), holes_count, loops.size());
|
ex_slices.size(), holes_count, loops.size());
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -15,7 +15,8 @@ namespace Slic3r {
|
||||||
using VD = Geometry::VoronoiDiagram;
|
using VD = Geometry::VoronoiDiagram;
|
||||||
|
|
||||||
namespace detail {
|
namespace detail {
|
||||||
// Intersect a circle with a ray, return the two parameters
|
// Intersect a circle with a ray, return the two parameters.
|
||||||
|
// Currently used for unbounded Voronoi edges only.
|
||||||
double first_circle_segment_intersection_parameter(
|
double first_circle_segment_intersection_parameter(
|
||||||
const Vec2d ¢er, const double r, const Vec2d &pt, const Vec2d &v)
|
const Vec2d ¢er, const double r, const Vec2d &pt, const Vec2d &v)
|
||||||
{
|
{
|
||||||
|
@ -61,70 +62,109 @@ namespace detail {
|
||||||
// Return maximum two points, that are at distance "d" from both points
|
// Return maximum two points, that are at distance "d" from both points
|
||||||
Intersections point_point_equal_distance_points(const Point &pt1, const Point &pt2, const double d)
|
Intersections point_point_equal_distance_points(const Point &pt1, const Point &pt2, const double d)
|
||||||
{
|
{
|
||||||
// input points
|
// Calculate the two intersection points.
|
||||||
const auto cx = double(pt1.x());
|
// With the help of Python package sympy:
|
||||||
const auto cy = double(pt1.y());
|
// res = solve([(x - cx)**2 + (y - cy)**2 - d**2, x**2 + y**2 - d**2], [x, y])
|
||||||
const auto qx = double(pt2.x());
|
// ccode(cse((res[0][0], res[0][1], res[1][0], res[1][1])))
|
||||||
const auto qy = double(pt2.y());
|
// where cx, cy is the center of pt1 relative to pt2,
|
||||||
|
// d is distance from the line and the point (0, 0).
|
||||||
// Calculating determinant.
|
// The result is then shifted to pt2.
|
||||||
auto x0 = 2. * qy;
|
auto cx = double(pt1.x() - pt2.x());
|
||||||
auto cx2 = cx * cx;
|
auto cy = double(pt1.y() - pt2.y());
|
||||||
auto cy2 = cy * cy;
|
double cl = cx * cx + cy * cy;
|
||||||
auto x5 = 2 * cx * qx;
|
double discr = 4. * d * d - cl;
|
||||||
auto x6 = cy * x0;
|
if (discr < 0.) {
|
||||||
auto qx2 = qx * qx;
|
|
||||||
auto qy2 = qy * qy;
|
|
||||||
auto x9 = qx2 + qy2;
|
|
||||||
auto x10 = cx2 + cy2 - x5 - x6 + x9;
|
|
||||||
auto x11 = - cx2 - cy2;
|
|
||||||
auto discr = x10 * (4. * d + x11 + x5 + x6 - qx2 - qy2);
|
|
||||||
if (discr < 0.)
|
|
||||||
// No intersection point found, the two circles are too far away.
|
// No intersection point found, the two circles are too far away.
|
||||||
return Intersections { 0, { Vec2d(), Vec2d() } };
|
return Intersections { 0, { Vec2d(), Vec2d() } };
|
||||||
|
}
|
||||||
|
// Avoid division by zero if a gets too small.
|
||||||
|
bool xy_swapped = std::abs(cx) < std::abs(cy);
|
||||||
|
if (xy_swapped)
|
||||||
|
std::swap(cx, cy);
|
||||||
|
double u;
|
||||||
|
int cnt;
|
||||||
|
if (discr == 0.) {
|
||||||
|
cnt = 1;
|
||||||
|
u = 0;
|
||||||
|
} else {
|
||||||
|
cnt = 2;
|
||||||
|
u = 0.5 * cx * sqrt(cl * discr) / cl;
|
||||||
|
}
|
||||||
|
double v = 0.5 * cy - u;
|
||||||
|
double w = 2. * cy;
|
||||||
|
double e = 0.5 / cx;
|
||||||
|
double f = 0.5 * cy + u;
|
||||||
|
Intersections out { cnt, { Vec2d(-e * (v * w - cl), v),
|
||||||
|
Vec2d(-e * (w * f - cl), f) } };
|
||||||
|
if (xy_swapped) {
|
||||||
|
std::swap(out.pts[0].x(), out.pts[0].y());
|
||||||
|
std::swap(out.pts[1].x(), out.pts[1].y());
|
||||||
|
}
|
||||||
|
out.pts[0] += pt2.cast<double>();
|
||||||
|
out.pts[1] += pt2.cast<double>();
|
||||||
|
|
||||||
// Some intersections are found.
|
assert(std::abs((out.pts[0] - pt1.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
int npoints = (discr > 0) ? 2 : 1;
|
assert(std::abs((out.pts[1] - pt1.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
auto x1 = 2. * cy - x0;
|
assert(std::abs((out.pts[0] - pt2.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
auto x2 = cx - qx;
|
assert(std::abs((out.pts[1] - pt2.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
auto x12 = 0.5 * x2 * sqrt(discr) / x10;
|
return out;
|
||||||
auto x13 = 0.5 * (cy + qy);
|
|
||||||
auto x14 = - x12 + x13;
|
|
||||||
auto x15 = x11 + x9;
|
|
||||||
auto x16 = 0.5 / x2;
|
|
||||||
auto x17 = x12 + x13;
|
|
||||||
return Intersections { npoints, { Vec2d(- x16 * (x1 * x14 + x15), x14),
|
|
||||||
Vec2d(- x16 * (x1 * x17 + x15), x17) } };
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Return maximum two points, that are at distance "d" from both the line and point.
|
// Return maximum two points, that are at distance "d" from both the line and point.
|
||||||
Intersections line_point_equal_distance_points(const Line &line, const Point &pt, const double d)
|
Intersections line_point_equal_distance_points(const Line &line, const Point &ipt, const double d)
|
||||||
{
|
{
|
||||||
assert(line.a != pt && line.b != pt);
|
assert(line.a != ipt && line.b != ipt);
|
||||||
// Calculating two points of distance "d" to a ray and a point.
|
// Calculating two points of distance "d" to a ray and a point.
|
||||||
// Point.
|
// Point.
|
||||||
auto x0 = double(pt.x());
|
Vec2d pt = ipt.cast<double>();
|
||||||
auto y0 = double(pt.y());
|
Vec2d lv = (line.b - line.a).cast<double>();
|
||||||
// Ray equation. Vector (a, b) is perpendicular to line.
|
double l2 = lv.squaredNorm();
|
||||||
auto a = double(line.a.y() - line.b.y());
|
Vec2d lpv = (line.a - ipt).cast<double>();
|
||||||
auto b = double(line.b.x() - line.a.x());
|
double c = cross2(lpv, lv);
|
||||||
// pt shall not lie on line.
|
if (c < 0) {
|
||||||
assert(std::abs((x0 - line.a.x()) * a + (y0 - line.a.y()) * b) < SCALED_EPSILON);
|
lv = - lv;
|
||||||
// Orient line so that the vector (a, b) points towards pt.
|
c = - c;
|
||||||
if (a * (x0 - line.a.x()) + b * (y0 - line.a.y()) < 0.)
|
}
|
||||||
std::swap(x0, y0);
|
|
||||||
double c = - a * double(line.a.x()) - b * double(line.a.y());
|
// Line equation (ax + by + c - d * sqrt(l2)).
|
||||||
// Calculate the two points.
|
auto a = - lv.y();
|
||||||
double a2 = a * a;
|
auto b = lv.x();
|
||||||
double b2 = b * b;
|
// Line point shifted by -ipt is on the line.
|
||||||
double a2b2 = a2 + b2;
|
assert(std::abs(lpv.x() * a + lpv.y() * b + c) < SCALED_EPSILON);
|
||||||
double d2 = d * d;
|
// Line vector (a, b) points towards ipt.
|
||||||
double s = a2*d2 - a2*sqr(x0) - 2*a*b*x0*y0 - 2*a*c*x0 + 2*a*d*x0 + b2*d2 - b2*sqr(y0) - 2*b*c*y0 + 2*b*d*y0 - sqr(c) + 2*c*d - d2;
|
assert(a * lpv.x() + b * lpv.y() < - SCALED_EPSILON);
|
||||||
|
|
||||||
|
#ifndef NDEBUG
|
||||||
|
{
|
||||||
|
// Foot point of ipt on line.
|
||||||
|
Vec2d ft = Geometry::foot_pt(line, ipt);
|
||||||
|
// Center point between ipt and line, its distance to both line and ipt is equal.
|
||||||
|
Vec2d centerpt = 0.5 * (ft + pt) - pt;
|
||||||
|
double dcenter = 0.5 * (ft - pt).norm();
|
||||||
|
// Verify that the center point
|
||||||
|
assert(std::abs(centerpt.x() * a + centerpt.y() * b + c - dcenter * sqrt(l2)) < SCALED_EPSILON * sqrt(l2));
|
||||||
|
}
|
||||||
|
#endif // NDEBUG
|
||||||
|
|
||||||
|
// Calculate the two intersection points.
|
||||||
|
// With the help of Python package sympy:
|
||||||
|
// res = solve([a * x + b * y + c - d * sqrt(a**2 + b**2), x**2 + y**2 - d**2], [x, y])
|
||||||
|
// ccode(cse((res[0][0], res[0][1], res[1][0], res[1][1])))
|
||||||
|
// where (a, b, c, d) is the line equation, not normalized (vector a,b is not normalized),
|
||||||
|
// d is distance from the line and the point (0, 0).
|
||||||
|
// The result is then shifted to ipt.
|
||||||
|
|
||||||
|
double dscaled = d * sqrt(l2);
|
||||||
|
double s = c * (2. * dscaled - c);
|
||||||
if (s < 0.)
|
if (s < 0.)
|
||||||
// Distance of pt from line is bigger than 2 * d.
|
// Distance of pt from line is bigger than 2 * d.
|
||||||
return Intersections { 0 };
|
return Intersections { 0 };
|
||||||
double u;
|
double u;
|
||||||
int cnt;
|
int cnt;
|
||||||
|
// Avoid division by zero if a gets too small.
|
||||||
|
bool xy_swapped = std::abs(a) < std::abs(b);
|
||||||
|
if (xy_swapped)
|
||||||
|
std::swap(a, b);
|
||||||
if (s == 0.) {
|
if (s == 0.) {
|
||||||
// Distance of pt from line is 2 * d.
|
// Distance of pt from line is 2 * d.
|
||||||
cnt = 1;
|
cnt = 1;
|
||||||
|
@ -132,110 +172,34 @@ namespace detail {
|
||||||
} else {
|
} else {
|
||||||
// Distance of pt from line is smaller than 2 * d.
|
// Distance of pt from line is smaller than 2 * d.
|
||||||
cnt = 2;
|
cnt = 2;
|
||||||
u = a*sqrt(s)/a2b2;
|
u = a * sqrt(s) / l2;
|
||||||
}
|
}
|
||||||
double v = (-a2*y0 + a*b*x0 + b*c - b*d)/a2b2;
|
double e = dscaled - c;
|
||||||
return Intersections { cnt, { Vec2d((b * ( u + v) - c + d) / a, - u - v),
|
double f = b * e / l2;
|
||||||
Vec2d((b * (- u + v) - c + d) / a, u - v) } };
|
double g = f - u;
|
||||||
|
double h = f + u;
|
||||||
|
Intersections out { cnt, { Vec2d((- b * g + e) / a, g),
|
||||||
|
Vec2d((- b * h + e) / a, h) } };
|
||||||
|
if (xy_swapped) {
|
||||||
|
std::swap(out.pts[0].x(), out.pts[0].y());
|
||||||
|
std::swap(out.pts[1].x(), out.pts[1].y());
|
||||||
|
}
|
||||||
|
out.pts[0] += pt;
|
||||||
|
out.pts[1] += pt;
|
||||||
|
|
||||||
|
assert(std::abs(Geometry::ray_point_distance<Vec2d>(line.a.cast<double>(), (line.b - line.a).cast<double>(), out.pts[0]) - d) < SCALED_EPSILON);
|
||||||
|
assert(std::abs(Geometry::ray_point_distance<Vec2d>(line.a.cast<double>(), (line.b - line.a).cast<double>(), out.pts[1]) - d) < SCALED_EPSILON);
|
||||||
|
assert(std::abs((out.pts[0] - ipt.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
|
assert(std::abs((out.pts[1] - ipt.cast<double>()).norm() - d) < SCALED_EPSILON);
|
||||||
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
Vec2d voronoi_edge_offset_point(
|
} // namespace detail
|
||||||
const VD &vd,
|
|
||||||
const Lines &lines,
|
|
||||||
// Distance of a VD vertex to the closest site (input polygon edge or vertex).
|
|
||||||
const std::vector<double> &vertex_dist,
|
|
||||||
// Minium distance of a VD edge to the closest site (input polygon edge or vertex).
|
|
||||||
// For a parabolic segment the distance may be smaller than the distance of the two end points.
|
|
||||||
const std::vector<double> &edge_dist,
|
|
||||||
// Edge for which to calculate the offset point. If the distance towards the input polygon
|
|
||||||
// is not monotonical, pick the offset point closer to edge.vertex0().
|
|
||||||
const VD::edge_type &edge,
|
|
||||||
// Distance from the input polygon along the edge.
|
|
||||||
const double offset_distance)
|
|
||||||
{
|
|
||||||
const VD::vertex_type *v0 = edge.vertex0();
|
|
||||||
const VD::vertex_type *v1 = edge.vertex1();
|
|
||||||
const VD::cell_type *cell = edge.cell();
|
|
||||||
const VD::cell_type *cell2 = edge.twin()->cell();
|
|
||||||
const Line &line0 = lines[cell->source_index()];
|
|
||||||
const Line &line1 = lines[cell2->source_index()];
|
|
||||||
if (v0 == nullptr || v1 == nullptr) {
|
|
||||||
assert(edge.is_infinite());
|
|
||||||
assert(v0 != nullptr || v1 != nullptr);
|
|
||||||
// Offsetting on an unconstrained edge.
|
|
||||||
assert(offset_distance > vertex_dist[(v0 ? v0 : v1) - &vd.vertices().front()] - EPSILON);
|
|
||||||
Vec2d pt, dir;
|
|
||||||
double t;
|
|
||||||
if (cell->contains_point() && cell2->contains_point()) {
|
|
||||||
const Point &pt0 = (cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b;
|
|
||||||
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
|
||||||
// Direction vector of this unconstrained Voronoi edge.
|
|
||||||
dir = Vec2d(double(pt0.y() - pt1.y()), double(pt1.x() - pt0.x()));
|
|
||||||
if (v0 == nullptr) {
|
|
||||||
v0 = v1;
|
|
||||||
dir = - dir;
|
|
||||||
}
|
|
||||||
pt = Vec2d(v0->x(), v0->y());
|
|
||||||
t = detail::first_circle_segment_intersection_parameter(Vec2d(pt0.x(), pt0.y()), offset_distance, pt, dir);
|
|
||||||
} else {
|
|
||||||
// Infinite edges could not be created by two segment sites.
|
|
||||||
assert(cell->contains_point() != cell2->contains_point());
|
|
||||||
// Linear edge goes through the endpoint of a segment.
|
|
||||||
assert(edge.is_linear());
|
|
||||||
assert(edge.is_secondary());
|
|
||||||
const Line &line = cell->contains_segment() ? line0 : line1;
|
|
||||||
const Point &ipt = cell->contains_segment() ?
|
|
||||||
((cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b) :
|
|
||||||
((cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b);
|
|
||||||
assert(line.a == ipt || line.b == ipt);
|
|
||||||
pt = Vec2d(ipt.x(), ipt.y());
|
|
||||||
dir = Vec2d(line.a.y() - line.b.y(), line.b.x() - line.a.x());
|
|
||||||
assert(dir.norm() > 0.);
|
|
||||||
t = offset_distance / dir.norm();
|
|
||||||
if (((line.a == ipt) == cell->contains_point()) == (v0 == nullptr))
|
|
||||||
t = - t;
|
|
||||||
}
|
|
||||||
return pt + t * dir;
|
|
||||||
} else {
|
|
||||||
// Constrained edge.
|
|
||||||
Vec2d p0(v0->x(), v0->y());
|
|
||||||
Vec2d p1(v1->x(), v1->y());
|
|
||||||
double d0 = vertex_dist[v0 - &vd.vertices().front()];
|
|
||||||
double d1 = vertex_dist[v1 - &vd.vertices().front()];
|
|
||||||
if (cell->contains_segment() && cell2->contains_segment()) {
|
|
||||||
// This edge is a bisector of two line segments. Distance to the input polygon increases/decreases monotonically.
|
|
||||||
double ddif = d1 - d0;
|
|
||||||
assert(offset_distance > std::min(d0, d1) - EPSILON && offset_distance < std::max(d0, d1) + EPSILON);
|
|
||||||
double t = (ddif == 0) ? 0. : clamp(0., 1., (offset_distance - d0) / ddif);
|
|
||||||
return Slic3r::lerp(p0, p1, t);
|
|
||||||
} else {
|
|
||||||
// One cell contains a point, the other contains an edge or a point.
|
|
||||||
assert(cell->contains_point() || cell2->contains_point());
|
|
||||||
const Point &ipt = cell->contains_point() ?
|
|
||||||
((cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b) :
|
|
||||||
((cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b);
|
|
||||||
double t = detail::first_circle_segment_intersection_parameter(
|
|
||||||
Vec2d(ipt.x(), ipt.y()), offset_distance, p0, p1 - p0);
|
|
||||||
return Slic3r::lerp(p0, p1, t);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
};
|
|
||||||
|
|
||||||
static Vec2d foot_pt(const Line &iline, const Point &ipt)
|
|
||||||
{
|
|
||||||
Vec2d pt = iline.a.cast<double>();
|
|
||||||
Vec2d dir = (iline.b - iline.a).cast<double>();
|
|
||||||
Vec2d v = ipt.cast<double>() - pt;
|
|
||||||
double l2 = dir.squaredNorm();
|
|
||||||
double t = (l2 == 0.) ? 0. : v.dot(dir) / l2;
|
|
||||||
return pt + dir * t;
|
|
||||||
}
|
|
||||||
|
|
||||||
Polygons voronoi_offset(
|
Polygons voronoi_offset(
|
||||||
const Geometry::VoronoiDiagram &vd,
|
const Geometry::VoronoiDiagram &vd,
|
||||||
const Lines &lines,
|
const Lines &lines,
|
||||||
double offset_distance,
|
double offset_distance,
|
||||||
double discretization_error)
|
double discretization_error)
|
||||||
{
|
{
|
||||||
#ifndef NDEBUG
|
#ifndef NDEBUG
|
||||||
|
@ -259,20 +223,94 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
#endif // NDEBUG
|
#endif // NDEBUG
|
||||||
|
|
||||||
|
enum class EdgeState : unsigned char {
|
||||||
|
// Initial state, don't know.
|
||||||
|
Unknown,
|
||||||
|
// This edge will certainly not be intersected by the offset curve.
|
||||||
|
Inactive,
|
||||||
|
// This edge will certainly be intersected by the offset curve.
|
||||||
|
Active,
|
||||||
|
// This edge will possibly be intersected by the offset curve.
|
||||||
|
Possible
|
||||||
|
};
|
||||||
|
|
||||||
|
enum class CellState : unsigned char {
|
||||||
|
// Initial state, don't know.
|
||||||
|
Unknown,
|
||||||
|
// Inactive cell is inside for outside curves and outside for inside curves.
|
||||||
|
Inactive,
|
||||||
|
// Active cell is outside for outside curves and inside for inside curves.
|
||||||
|
Active,
|
||||||
|
// Boundary cell is intersected by the input segment, part of it is active.
|
||||||
|
Boundary
|
||||||
|
};
|
||||||
|
|
||||||
// Mark edges with outward vertex pointing outside the polygons, thus there is a chance
|
// Mark edges with outward vertex pointing outside the polygons, thus there is a chance
|
||||||
// that such an edge will have an intersection with our desired offset curve.
|
// that such an edge will have an intersection with our desired offset curve.
|
||||||
bool outside = offset_distance > 0.;
|
bool outside = offset_distance > 0.;
|
||||||
std::vector<char> edge_candidate(vd.num_edges(), 2); // unknown state
|
std::vector<EdgeState> edge_state(vd.num_edges(), EdgeState::Unknown);
|
||||||
const VD::edge_type *front_edge = &vd.edges().front();
|
std::vector<CellState> cell_state(vd.num_cells(), CellState::Unknown);
|
||||||
|
const VD::edge_type *front_edge = &vd.edges().front();
|
||||||
|
const VD::cell_type *front_cell = &vd.cells().front();
|
||||||
|
auto set_edge_state_initial = [&edge_state, front_edge](const VD::edge_type *edge, EdgeState new_edge_type) {
|
||||||
|
EdgeState &edge_type = edge_state[edge - front_edge];
|
||||||
|
assert(edge_type == EdgeState::Unknown || edge_type == new_edge_type);
|
||||||
|
assert(new_edge_type == EdgeState::Possible || new_edge_type == EdgeState::Inactive);
|
||||||
|
edge_type = new_edge_type;
|
||||||
|
};
|
||||||
|
auto set_edge_state_final = [&edge_state, front_edge](const size_t edge_id, EdgeState new_edge_type) {
|
||||||
|
EdgeState &edge_type = edge_state[edge_id];
|
||||||
|
assert(edge_type == EdgeState::Possible || edge_type == new_edge_type);
|
||||||
|
assert(new_edge_type == EdgeState::Active || new_edge_type == EdgeState::Inactive);
|
||||||
|
edge_type = new_edge_type;
|
||||||
|
};
|
||||||
|
auto set_cell_state = [&cell_state, front_cell](const VD::cell_type *cell, CellState new_cell_type) -> bool {
|
||||||
|
CellState &cell_type = cell_state[cell - front_cell];
|
||||||
|
assert(cell_type == CellState::Active || cell_type == CellState::Inactive || cell_type == CellState::Boundary || cell_type == CellState::Unknown);
|
||||||
|
assert(new_cell_type == CellState::Active || new_cell_type == CellState::Inactive || new_cell_type == CellState::Boundary);
|
||||||
|
switch (cell_type) {
|
||||||
|
case CellState::Unknown:
|
||||||
|
break;
|
||||||
|
case CellState::Active:
|
||||||
|
if (new_cell_type == CellState::Inactive)
|
||||||
|
new_cell_type = CellState::Boundary;
|
||||||
|
break;
|
||||||
|
case CellState::Inactive:
|
||||||
|
if (new_cell_type == CellState::Active)
|
||||||
|
new_cell_type = CellState::Boundary;
|
||||||
|
break;
|
||||||
|
case CellState::Boundary:
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (cell_type != new_cell_type) {
|
||||||
|
cell_type = new_cell_type;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
};
|
||||||
|
|
||||||
for (const VD::edge_type &edge : vd.edges())
|
for (const VD::edge_type &edge : vd.edges())
|
||||||
if (edge.vertex1() == nullptr) {
|
if (edge.vertex1() == nullptr) {
|
||||||
// Infinite Voronoi edge separating two Point sites.
|
// Infinite Voronoi edge separating two Point sites or a Point site and a Segment site.
|
||||||
// Infinite edge is always outside and it has at least one valid vertex.
|
// Infinite edge is always outside and it has at least one valid vertex.
|
||||||
assert(edge.vertex0() != nullptr);
|
assert(edge.vertex0() != nullptr);
|
||||||
edge_candidate[&edge - front_edge] = outside;
|
set_edge_state_initial(&edge, outside ? EdgeState::Possible : EdgeState::Inactive);
|
||||||
// Opposite edge of an infinite edge is certainly not active.
|
// Opposite edge of an infinite edge is certainly not active.
|
||||||
edge_candidate[edge.twin() - front_edge] = 0;
|
set_edge_state_initial(edge.twin(), EdgeState::Inactive);
|
||||||
} else if (edge.vertex1() != nullptr) {
|
if (edge.is_secondary()) {
|
||||||
|
// edge.vertex0() must lie on source contour.
|
||||||
|
const VD::cell_type *cell = edge.cell();
|
||||||
|
const VD::cell_type *cell2 = edge.twin()->cell();
|
||||||
|
if (cell->contains_segment())
|
||||||
|
std::swap(cell, cell2);
|
||||||
|
// State of a cell containing a boundary point is known.
|
||||||
|
assert(cell->contains_point());
|
||||||
|
set_cell_state(cell, outside ? CellState::Active : CellState::Inactive);
|
||||||
|
// State of a cell containing a boundary edge is Boundary.
|
||||||
|
assert(cell2->contains_segment());
|
||||||
|
set_cell_state(cell2, CellState::Boundary);
|
||||||
|
}
|
||||||
|
} else if (edge.vertex0() != nullptr) {
|
||||||
// Finite edge.
|
// Finite edge.
|
||||||
const VD::cell_type *cell = edge.cell();
|
const VD::cell_type *cell = edge.cell();
|
||||||
const Line *line = cell->contains_segment() ? &lines[cell->source_index()] : nullptr;
|
const Line *line = cell->contains_segment() ? &lines[cell->source_index()] : nullptr;
|
||||||
|
@ -281,38 +319,114 @@ Polygons voronoi_offset(
|
||||||
line = cell->contains_segment() ? &lines[cell->source_index()] : nullptr;
|
line = cell->contains_segment() ? &lines[cell->source_index()] : nullptr;
|
||||||
}
|
}
|
||||||
if (line) {
|
if (line) {
|
||||||
const VD::vertex_type *v1 = edge.vertex1();
|
const VD::vertex_type *v1 = edge.vertex1();
|
||||||
|
const VD::cell_type *cell2 = (cell == edge.cell()) ? edge.twin()->cell() : edge.cell();
|
||||||
assert(v1);
|
assert(v1);
|
||||||
|
const Point *pt_on_contour = nullptr;
|
||||||
|
if (cell == edge.cell() && edge.twin()->cell()->contains_segment()) {
|
||||||
|
// Constrained bisector of two segments.
|
||||||
|
// If the two segments share a point, then one end of the current Voronoi edge shares this point as well.
|
||||||
|
// Find pt_on_contour if it exists.
|
||||||
|
const Line &line2 = lines[cell2->source_index()];
|
||||||
|
if (line->a == line2.b)
|
||||||
|
pt_on_contour = &line->a;
|
||||||
|
else if (line->b == line2.a)
|
||||||
|
pt_on_contour = &line->b;
|
||||||
|
} else if (edge.is_secondary()) {
|
||||||
|
assert(edge.is_linear());
|
||||||
|
// One end of the current Voronoi edge shares a point of a contour.
|
||||||
|
assert(edge.cell()->contains_point() != edge.twin()->cell()->contains_point());
|
||||||
|
const Line &line2 = lines[cell2->source_index()];
|
||||||
|
pt_on_contour = &((cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line2.a : line2.b);
|
||||||
|
}
|
||||||
|
if (pt_on_contour) {
|
||||||
|
// One end of the current Voronoi edge shares a point of a contour.
|
||||||
|
// Find out which one it is.
|
||||||
|
const VD::vertex_type *v0 = edge.vertex0();
|
||||||
|
Vec2d vec0(v0->x() - pt_on_contour->x(), v0->y() - pt_on_contour->y());
|
||||||
|
Vec2d vec1(v1->x() - pt_on_contour->x(), v1->y() - pt_on_contour->y());
|
||||||
|
double d0 = vec0.squaredNorm();
|
||||||
|
double d1 = vec1.squaredNorm();
|
||||||
|
assert(std::min(d0, d1) < SCALED_EPSILON * SCALED_EPSILON);
|
||||||
|
if (d0 < d1) {
|
||||||
|
// v0 is equal to pt.
|
||||||
|
} else {
|
||||||
|
// Skip secondary edge pointing to a contour point.
|
||||||
|
set_edge_state_initial(&edge, EdgeState::Inactive);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
}
|
||||||
Vec2d l0(line->a.cast<double>());
|
Vec2d l0(line->a.cast<double>());
|
||||||
Vec2d lv((line->b - line->a).cast<double>());
|
Vec2d lv((line->b - line->a).cast<double>());
|
||||||
double side = cross2(lv, Vec2d(v1->x(), v1->y()) - l0);
|
double side = cross2(lv, Vec2d(v1->x(), v1->y()) - l0);
|
||||||
edge_candidate[&edge - front_edge] = outside ? (side < 0.) : (side > 0.);
|
bool edge_active = outside ? (side < 0.) : (side > 0.);
|
||||||
|
set_edge_state_initial(&edge, edge_active ? EdgeState::Possible : EdgeState::Inactive);
|
||||||
|
assert(cell->contains_segment());
|
||||||
|
set_cell_state(cell,
|
||||||
|
pt_on_contour ? CellState::Boundary :
|
||||||
|
edge_active ? CellState::Active : CellState::Inactive);
|
||||||
|
set_cell_state(cell2,
|
||||||
|
(pt_on_contour && cell2->contains_segment()) ?
|
||||||
|
CellState::Boundary :
|
||||||
|
edge_active ? CellState::Active : CellState::Inactive);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
for (const VD::edge_type &edge : vd.edges())
|
{
|
||||||
if (edge_candidate[&edge - front_edge] == 2) {
|
// Perform one round of expansion marking Voronoi edges and cells next to boundary cells as active / inactive.
|
||||||
assert(edge.cell()->contains_point() && edge.twin()->cell()->contains_point());
|
std::vector<const VD::cell_type*> cell_queue;
|
||||||
// Edge separating two point sources, not yet classified as inside / outside.
|
for (const VD::edge_type &edge : vd.edges())
|
||||||
const VD::edge_type *e = &edge;
|
if (edge_state[&edge - front_edge] == EdgeState::Unknown) {
|
||||||
char state;
|
assert(edge.cell()->contains_point() && edge.twin()->cell()->contains_point());
|
||||||
do {
|
// Edge separating two point sources, not yet classified as inside / outside.
|
||||||
state = edge_candidate[e - front_edge];
|
CellState cs = cell_state[edge.cell() - front_cell];
|
||||||
if (state != 2)
|
CellState cs2 = cell_state[edge.twin()->cell() - front_cell];
|
||||||
break;
|
if (cs != CellState::Unknown || cs2 != CellState::Unknown) {
|
||||||
e = e->next();
|
if (cs == CellState::Unknown) {
|
||||||
} while (e != &edge);
|
cs = cs2;
|
||||||
e = &edge;
|
if (set_cell_state(edge.cell(), cs))
|
||||||
do {
|
cell_queue.emplace_back(edge.cell());
|
||||||
char &s = edge_candidate[e - front_edge];
|
} else if (set_cell_state(edge.twin()->cell(), cs))
|
||||||
if (s == 2) {
|
cell_queue.emplace_back(edge.twin()->cell());
|
||||||
assert(e->cell()->contains_point() && e->twin()->cell()->contains_point());
|
EdgeState es = (cs == CellState::Active) ? EdgeState::Possible : EdgeState::Inactive;
|
||||||
assert(edge_candidate[e->twin() - front_edge] == 2);
|
set_edge_state_initial(&edge, es);
|
||||||
s = state;
|
set_edge_state_initial(edge.twin(), es);
|
||||||
edge_candidate[e->twin() - front_edge] = state;
|
} else {
|
||||||
|
const VD::edge_type *e = edge.twin()->rot_prev();
|
||||||
|
do {
|
||||||
|
EdgeState es = edge_state[e->twin() - front_edge];
|
||||||
|
if (es != EdgeState::Unknown) {
|
||||||
|
assert(es == EdgeState::Possible || es == EdgeState::Inactive);
|
||||||
|
set_edge_state_initial(&edge, es);
|
||||||
|
CellState cs = (es == EdgeState::Possible) ? CellState::Active : CellState::Inactive;
|
||||||
|
if (set_cell_state(edge.cell(), cs))
|
||||||
|
cell_queue.emplace_back(edge.cell());
|
||||||
|
if (set_cell_state(edge.twin()->cell(), cs))
|
||||||
|
cell_queue.emplace_back(edge.twin()->cell());
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
e = e->rot_prev();
|
||||||
|
} while (e != edge.twin());
|
||||||
}
|
}
|
||||||
e = e->next();
|
}
|
||||||
} while (e != &edge);
|
// Do a final seed fill over Voronoi cells and unmarked Voronoi edges.
|
||||||
|
while (! cell_queue.empty()) {
|
||||||
|
const VD::cell_type *cell = cell_queue.back();
|
||||||
|
const CellState cs = cell_state[cell - front_cell];
|
||||||
|
cell_queue.pop_back();
|
||||||
|
const VD::edge_type *first_edge = cell->incident_edge();
|
||||||
|
const VD::edge_type *edge = cell->incident_edge();
|
||||||
|
EdgeState es = (cs == CellState::Active) ? EdgeState::Possible : EdgeState::Inactive;
|
||||||
|
do {
|
||||||
|
if (set_cell_state(edge->twin()->cell(), cs)) {
|
||||||
|
set_edge_state_initial(edge, es);
|
||||||
|
set_edge_state_initial(edge->twin(), es);
|
||||||
|
cell_queue.emplace_back(edge->twin()->cell());
|
||||||
|
}
|
||||||
|
edge = edge->next();
|
||||||
|
} while (edge != first_edge);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (! outside)
|
if (! outside)
|
||||||
offset_distance = - offset_distance;
|
offset_distance = - offset_distance;
|
||||||
|
|
||||||
|
@ -323,10 +437,12 @@ Polygons voronoi_offset(
|
||||||
bbox.min -= (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
bbox.min -= (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
||||||
bbox.max += (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
bbox.max += (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
||||||
}
|
}
|
||||||
|
static int irun = 0;
|
||||||
|
++ irun;
|
||||||
{
|
{
|
||||||
Lines helper_lines;
|
Lines helper_lines;
|
||||||
for (const VD::edge_type &edge : vd.edges())
|
for (const VD::edge_type &edge : vd.edges())
|
||||||
if (edge_candidate[&edge - front_edge]) {
|
if (edge_state[&edge - front_edge] == EdgeState::Possible) {
|
||||||
const VD::vertex_type *v0 = edge.vertex0();
|
const VD::vertex_type *v0 = edge.vertex0();
|
||||||
const VD::vertex_type *v1 = edge.vertex1();
|
const VD::vertex_type *v1 = edge.vertex1();
|
||||||
assert(v0 != nullptr);
|
assert(v0 != nullptr);
|
||||||
|
@ -370,16 +486,16 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
helper_lines.emplace_back(Line(Point(pt1.cast<coord_t>()), Point(((pt1 + pt2) * 0.5).cast<coord_t>())));
|
helper_lines.emplace_back(Line(Point(pt1.cast<coord_t>()), Point(((pt1 + pt2) * 0.5).cast<coord_t>())));
|
||||||
}
|
}
|
||||||
dump_voronoi_to_svg(debug_out_path("voronoi-offset-candidates1.svg").c_str(), vd, Points(), lines, Polygons(), helper_lines);
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-candidates1-%d.svg", irun).c_str(), vd, Points(), lines, Polygons(), helper_lines);
|
||||||
}
|
}
|
||||||
#endif // VORONOI_DEBUG_OUT
|
#endif // VORONOI_DEBUG_OUT
|
||||||
|
|
||||||
std::vector<Vec2d> edge_offset_point(vd.num_edges(), Vec2d());
|
std::vector<Vec2d> edge_offset_point(vd.num_edges(), Vec2d());
|
||||||
const double offset_distance2 = offset_distance * offset_distance;
|
const double offset_distance2 = offset_distance * offset_distance;
|
||||||
for (const VD::edge_type &edge : vd.edges()) {
|
for (const VD::edge_type &edge : vd.edges()) {
|
||||||
assert(edge_candidate[&edge - front_edge] != 2);
|
assert(edge_state[&edge - front_edge] != EdgeState::Unknown);
|
||||||
size_t edge_idx = &edge - front_edge;
|
size_t edge_idx = &edge - front_edge;
|
||||||
if (edge_candidate[edge_idx] == 1) {
|
if (edge_state[edge_idx] == EdgeState::Possible) {
|
||||||
// Edge candidate, intersection points were not calculated yet.
|
// Edge candidate, intersection points were not calculated yet.
|
||||||
const VD::vertex_type *v0 = edge.vertex0();
|
const VD::vertex_type *v0 = edge.vertex0();
|
||||||
const VD::vertex_type *v1 = edge.vertex1();
|
const VD::vertex_type *v1 = edge.vertex1();
|
||||||
|
@ -391,11 +507,14 @@ Polygons voronoi_offset(
|
||||||
size_t edge_idx2 = edge.twin() - front_edge;
|
size_t edge_idx2 = edge.twin() - front_edge;
|
||||||
if (v1 == nullptr) {
|
if (v1 == nullptr) {
|
||||||
assert(edge.is_infinite());
|
assert(edge.is_infinite());
|
||||||
assert(edge_candidate[edge_idx2] == 0);
|
assert(edge.is_linear());
|
||||||
|
assert(edge_state[edge_idx2] == EdgeState::Inactive);
|
||||||
if (cell->contains_point() && cell2->contains_point()) {
|
if (cell->contains_point() && cell2->contains_point()) {
|
||||||
|
assert(! edge.is_secondary());
|
||||||
const Point &pt0 = (cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b;
|
const Point &pt0 = (cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b;
|
||||||
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
||||||
double dmin2 = (Vec2d(v0->x(), v0->y()) - pt0.cast<double>()).squaredNorm();
|
double dmin2 = (Vec2d(v0->x(), v0->y()) - pt0.cast<double>()).squaredNorm();
|
||||||
|
assert(dmin2 >= SCALED_EPSILON * SCALED_EPSILON);
|
||||||
if (dmin2 <= offset_distance2) {
|
if (dmin2 <= offset_distance2) {
|
||||||
// There shall be an intersection of this unconstrained edge with the offset curve.
|
// There shall be an intersection of this unconstrained edge with the offset curve.
|
||||||
// Direction vector of this unconstrained Voronoi edge.
|
// Direction vector of this unconstrained Voronoi edge.
|
||||||
|
@ -403,14 +522,13 @@ Polygons voronoi_offset(
|
||||||
Vec2d pt(v0->x(), v0->y());
|
Vec2d pt(v0->x(), v0->y());
|
||||||
double t = detail::first_circle_segment_intersection_parameter(Vec2d(pt0.x(), pt0.y()), offset_distance, pt, dir);
|
double t = detail::first_circle_segment_intersection_parameter(Vec2d(pt0.x(), pt0.y()), offset_distance, pt, dir);
|
||||||
edge_offset_point[edge_idx] = pt + t * dir;
|
edge_offset_point[edge_idx] = pt + t * dir;
|
||||||
edge_candidate[edge_idx] = 3;
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
} else
|
} else
|
||||||
edge_candidate[edge_idx] = 0;
|
set_edge_state_final(edge_idx, EdgeState::Inactive);
|
||||||
} else {
|
} else {
|
||||||
// Infinite edges could not be created by two segment sites.
|
// Infinite edges could not be created by two segment sites.
|
||||||
assert(cell->contains_point() != cell2->contains_point());
|
assert(cell->contains_point() != cell2->contains_point());
|
||||||
// Linear edge goes through the endpoint of a segment.
|
// Linear edge goes through the endpoint of a segment.
|
||||||
assert(edge.is_linear());
|
|
||||||
assert(edge.is_secondary());
|
assert(edge.is_secondary());
|
||||||
const Point &ipt = cell->contains_segment() ?
|
const Point &ipt = cell->contains_segment() ?
|
||||||
((cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b) :
|
((cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b) :
|
||||||
|
@ -428,20 +546,15 @@ Polygons voronoi_offset(
|
||||||
assert((Vec2d(v0->x(), v0->y()) - ipt.cast<double>()).norm() < SCALED_EPSILON);
|
assert((Vec2d(v0->x(), v0->y()) - ipt.cast<double>()).norm() < SCALED_EPSILON);
|
||||||
#endif /* NDEBUG */
|
#endif /* NDEBUG */
|
||||||
// Infinite edge starts at an input contour, therefore there is always an intersection with an offset curve.
|
// Infinite edge starts at an input contour, therefore there is always an intersection with an offset curve.
|
||||||
const Line &line = cell->contains_segment() ? line0 : line1;
|
const Line &line = cell->contains_segment() ? line0 : line1;
|
||||||
assert(line.a == ipt || line.b == ipt);
|
assert(line.a == ipt || line.b == ipt);
|
||||||
Vec2d pt = ipt.cast<double>();
|
edge_offset_point[edge_idx] = ipt.cast<double>() + offset_distance * Vec2d(line.b.y() - line.a.y(), line.a.x() - line.b.x()).normalized();
|
||||||
Vec2d dir(line.a.y() - line.b.y(), line.b.x() - line.a.x());
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
assert(dir.norm() > 0.);
|
|
||||||
double t = offset_distance / dir.norm();
|
|
||||||
if (((line.a == ipt) == cell->contains_point()) == (v0 == nullptr))
|
|
||||||
t = - t;
|
|
||||||
edge_offset_point[edge_idx] = pt + t * dir;
|
|
||||||
edge_candidate[edge_idx] = 3;
|
|
||||||
}
|
}
|
||||||
// The other edge of an unconstrained edge starting with null vertex shall never be intersected.
|
// The other edge of an unconstrained edge starting with null vertex shall never be intersected.
|
||||||
edge_candidate[edge_idx2] = 0;
|
set_edge_state_final(edge_idx2, EdgeState::Inactive);
|
||||||
} else if (edge.is_secondary()) {
|
} else if (edge.is_secondary()) {
|
||||||
|
assert(edge.is_linear());
|
||||||
assert(cell->contains_point() != cell2->contains_point());
|
assert(cell->contains_point() != cell2->contains_point());
|
||||||
const Line &line0 = lines[edge.cell()->source_index()];
|
const Line &line0 = lines[edge.cell()->source_index()];
|
||||||
const Line &line1 = lines[edge.twin()->cell()->source_index()];
|
const Line &line1 = lines[edge.twin()->cell()->source_index()];
|
||||||
|
@ -455,11 +568,11 @@ Polygons voronoi_offset(
|
||||||
double l2 = dir.squaredNorm();
|
double l2 = dir.squaredNorm();
|
||||||
if (offset_distance2 <= l2) {
|
if (offset_distance2 <= l2) {
|
||||||
edge_offset_point[edge_idx] = pt.cast<double>() + (offset_distance / sqrt(l2)) * dir;
|
edge_offset_point[edge_idx] = pt.cast<double>() + (offset_distance / sqrt(l2)) * dir;
|
||||||
edge_candidate[edge_idx] = 3;
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
} else {
|
} else {
|
||||||
edge_candidate[edge_idx] = 0;
|
set_edge_state_final(edge_idx, EdgeState::Inactive);
|
||||||
}
|
}
|
||||||
edge_candidate[edge_idx2] = 0;
|
set_edge_state_final(edge_idx2, EdgeState::Inactive);
|
||||||
} else {
|
} else {
|
||||||
// Finite edge has valid points at both sides.
|
// Finite edge has valid points at both sides.
|
||||||
bool done = false;
|
bool done = false;
|
||||||
|
@ -492,8 +605,8 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
double t = clamp(0., 1., (offset_distance - dmin) / ddif);
|
double t = clamp(0., 1., (offset_distance - dmin) / ddif);
|
||||||
edge_offset_point[edge_idx] = Vec2d(lerp(v0->x(), v1->x(), t), lerp(v0->y(), v1->y(), t));
|
edge_offset_point[edge_idx] = Vec2d(lerp(v0->x(), v1->x(), t), lerp(v0->y(), v1->y(), t));
|
||||||
edge_candidate[edge_idx] = 3;
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
edge_candidate[edge_idx2] = 0;
|
set_edge_state_final(edge_idx2, EdgeState::Inactive);
|
||||||
done = true;
|
done = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -512,23 +625,44 @@ Polygons voronoi_offset(
|
||||||
double dmin = std::min(d0, d1);
|
double dmin = std::min(d0, d1);
|
||||||
double dmax = std::max(d0, d1);
|
double dmax = std::max(d0, d1);
|
||||||
bool has_intersection = false;
|
bool has_intersection = false;
|
||||||
|
bool possibly_two_points = false;
|
||||||
if (offset_distance2 <= dmax) {
|
if (offset_distance2 <= dmax) {
|
||||||
if (offset_distance2 >= dmin) {
|
if (offset_distance2 >= dmin) {
|
||||||
has_intersection = true;
|
has_intersection = true;
|
||||||
} else {
|
} else {
|
||||||
double dmin_new;
|
double dmin_new = dmin;
|
||||||
if (point_vs_segment) {
|
if (point_vs_segment) {
|
||||||
Vec2d ft = foot_pt(cell->contains_segment() ? line0 : line1, pt0);
|
// Project on the source segment.
|
||||||
dmin_new = (ft - px).squaredNorm() * 0.25;
|
const Line &line = cell->contains_segment() ? line0 : line1;
|
||||||
|
const Vec2d pt_line = line.a.cast<double>();
|
||||||
|
const Vec2d v_line = (line.b - line.a).cast<double>();
|
||||||
|
double t0 = (p0 - pt_line).dot(v_line);
|
||||||
|
double t1 = (p1 - pt_line).dot(v_line);
|
||||||
|
double tx = (px - pt_line).dot(v_line);
|
||||||
|
if ((tx >= t0 && tx <= t1) || (tx >= t1 && tx <= t0)) {
|
||||||
|
// Projection of the Point site falls between the projections of the Voronoi edge end points
|
||||||
|
// onto the Line site.
|
||||||
|
Vec2d ft = pt_line + (tx / v_line.squaredNorm()) * v_line;
|
||||||
|
dmin_new = (ft - px).squaredNorm() * 0.25;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
// point vs. point
|
// Point-Point Voronoi sites. Project point site onto the current Voronoi edge.
|
||||||
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
Vec2d v = p1 - p0;
|
||||||
dmin_new = (pt1.cast<double>() - px).squaredNorm() * 0.25;
|
auto l2 = v.squaredNorm();
|
||||||
|
assert(l2 > 0);
|
||||||
|
auto t = v.dot(px - p0);
|
||||||
|
if (t >= 0. && t <= l2) {
|
||||||
|
// Projection falls onto the Voronoi edge. Calculate foot point and distance.
|
||||||
|
Vec2d ft = p0 + (t / l2) * v;
|
||||||
|
dmin_new = (ft - px).squaredNorm();
|
||||||
|
}
|
||||||
}
|
}
|
||||||
assert(dmin_new < dmax + SCALED_EPSILON);
|
assert(dmin_new < dmax + SCALED_EPSILON);
|
||||||
assert(dmin_new < dmin + SCALED_EPSILON);
|
assert(dmin_new < dmin + SCALED_EPSILON);
|
||||||
dmin = dmin_new;
|
if (dmin_new < dmin) {
|
||||||
has_intersection = offset_distance2 >= dmin;
|
dmin = dmin_new;
|
||||||
|
has_intersection = possibly_two_points = offset_distance2 >= dmin;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (has_intersection) {
|
if (has_intersection) {
|
||||||
|
@ -540,67 +674,90 @@ Polygons voronoi_offset(
|
||||||
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
const Point &pt1 = (cell2->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line1.a : line1.b;
|
||||||
intersections = detail::point_point_equal_distance_points(pt0, pt1, offset_distance);
|
intersections = detail::point_point_equal_distance_points(pt0, pt1, offset_distance);
|
||||||
}
|
}
|
||||||
|
// If the span of distances of start / end point / foot point to the point site indicate an intersection,
|
||||||
|
// we should find one.
|
||||||
|
assert(intersections.count > 0);
|
||||||
if (intersections.count == 2) {
|
if (intersections.count == 2) {
|
||||||
// Now decide which points fall on this Voronoi edge.
|
// Now decide which points fall on this Voronoi edge.
|
||||||
// Tangential points (single intersection) are ignored.
|
// Tangential points (single intersection) are ignored.
|
||||||
Vec2d v = p1 - p0;
|
if (possibly_two_points) {
|
||||||
double l2 = v.squaredNorm();
|
Vec2d v = p1 - p0;
|
||||||
double t0 = v.dot(intersections.pts[0] - p0);
|
double l2 = v.squaredNorm();
|
||||||
double t1 = v.dot(intersections.pts[1] - p0);
|
double t0 = v.dot(intersections.pts[0] - p0);
|
||||||
if (t0 > t1) {
|
double t1 = v.dot(intersections.pts[1] - p0);
|
||||||
std::swap(t0, t1);
|
if (t0 > t1) {
|
||||||
std::swap(intersections.pts[0], intersections.pts[1]);
|
std::swap(t0, t1);
|
||||||
}
|
std::swap(intersections.pts[0], intersections.pts[1]);
|
||||||
// Remove points outside of the line range.
|
|
||||||
if (t0 < 0. || t0 > l2) {
|
|
||||||
if (t1 < 0. || t1 > l2)
|
|
||||||
intersections.count = 0;
|
|
||||||
else {
|
|
||||||
-- intersections.count;
|
|
||||||
t0 = t1;
|
|
||||||
intersections.pts[0] = intersections.pts[1];
|
|
||||||
}
|
}
|
||||||
} else if (t1 < 0. || t1 > l2)
|
// Remove points outside of the line range.
|
||||||
|
if (t0 < 0. || t0 > l2) {
|
||||||
|
if (t1 < 0. || t1 > l2)
|
||||||
|
intersections.count = 0;
|
||||||
|
else {
|
||||||
|
-- intersections.count;
|
||||||
|
t0 = t1;
|
||||||
|
intersections.pts[0] = intersections.pts[1];
|
||||||
|
}
|
||||||
|
} else if (t1 < 0. || t1 > l2)
|
||||||
|
-- intersections.count;
|
||||||
|
} else {
|
||||||
|
// Take the point furthest from the end points of the Voronoi edge or a Voronoi parabolic arc.
|
||||||
|
double d0 = std::max((intersections.pts[0] - p0).squaredNorm(), (intersections.pts[0] - p1).squaredNorm());
|
||||||
|
double d1 = std::max((intersections.pts[1] - p0).squaredNorm(), (intersections.pts[1] - p1).squaredNorm());
|
||||||
|
if (d0 > d1)
|
||||||
|
intersections.pts[0] = intersections.pts[1];
|
||||||
-- intersections.count;
|
-- intersections.count;
|
||||||
|
}
|
||||||
|
assert(intersections.count > 0);
|
||||||
if (intersections.count == 2) {
|
if (intersections.count == 2) {
|
||||||
edge_candidate[edge_idx] = edge_candidate[edge_idx2] = 3;
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
edge_offset_point[edge_idx] = intersections.pts[0];
|
set_edge_state_final(edge_idx2, EdgeState::Active);
|
||||||
edge_offset_point[edge_idx2] = intersections.pts[1];
|
edge_offset_point[edge_idx] = intersections.pts[1];
|
||||||
|
edge_offset_point[edge_idx2] = intersections.pts[0];
|
||||||
done = true;
|
done = true;
|
||||||
} else if (intersections.count == 1) {
|
} else if (intersections.count == 1) {
|
||||||
if (d1 > d0) {
|
if (d1 < d0)
|
||||||
std::swap(edge_idx, edge_idx2);
|
std::swap(edge_idx, edge_idx2);
|
||||||
edge_candidate[edge_idx] = 3;
|
set_edge_state_final(edge_idx, EdgeState::Active);
|
||||||
edge_candidate[edge_idx2] = 0;
|
set_edge_state_final(edge_idx2, EdgeState::Inactive);
|
||||||
edge_offset_point[edge_idx] = intersections.pts[0];
|
edge_offset_point[edge_idx] = intersections.pts[0];
|
||||||
}
|
|
||||||
done = true;
|
done = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (! done)
|
|
||||||
edge_candidate[edge_idx] = edge_candidate[edge_idx2] = 0;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (! done) {
|
||||||
|
set_edge_state_final(edge_idx, EdgeState::Inactive);
|
||||||
|
set_edge_state_final(edge_idx2, EdgeState::Inactive);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifndef NDEBUG
|
||||||
|
for (const VD::edge_type &edge : vd.edges()) {
|
||||||
|
assert(edge_state[&edge - front_edge] == EdgeState::Inactive || edge_state[&edge - front_edge] == EdgeState::Active);
|
||||||
|
// None of a new edge candidate may start with null vertex.
|
||||||
|
assert(edge_state[&edge - front_edge] == EdgeState::Inactive || edge.vertex0() != nullptr);
|
||||||
|
assert(edge_state[edge.twin() - front_edge] == EdgeState::Inactive || edge.twin()->vertex0() != nullptr);
|
||||||
|
}
|
||||||
|
#endif // NDEBUG
|
||||||
|
|
||||||
#ifdef VORONOI_DEBUG_OUT
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
{
|
{
|
||||||
Lines helper_lines;
|
Lines helper_lines;
|
||||||
for (const VD::edge_type &edge : vd.edges())
|
for (const VD::edge_type &edge : vd.edges())
|
||||||
if (edge_candidate[&edge - front_edge] == 3)
|
if (edge_state[&edge - front_edge] == EdgeState::Active)
|
||||||
helper_lines.emplace_back(Line(Point(edge.vertex0()->x(), edge.vertex0()->y()), Point(edge_offset_point[&edge - front_edge].cast<coord_t>())));
|
helper_lines.emplace_back(Line(Point(edge.vertex0()->x(), edge.vertex0()->y()), Point(edge_offset_point[&edge - front_edge].cast<coord_t>())));
|
||||||
dump_voronoi_to_svg(debug_out_path("voronoi-offset-candidates2.svg").c_str(), vd, Points(), lines, Polygons(), helper_lines);
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-candidates2-%d.svg", irun).c_str(), vd, Points(), lines, Polygons(), helper_lines);
|
||||||
}
|
}
|
||||||
#endif // VORONOI_DEBUG_OUT
|
#endif // VORONOI_DEBUG_OUT
|
||||||
|
|
||||||
auto next_offset_edge = [&edge_candidate, front_edge](const VD::edge_type *start_edge) -> const VD::edge_type* {
|
auto next_offset_edge = [&edge_state, front_edge](const VD::edge_type *start_edge) -> const VD::edge_type* {
|
||||||
for (const VD::edge_type *edge = start_edge->next(); edge != start_edge; edge = edge->next())
|
for (const VD::edge_type *edge = start_edge->next(); edge != start_edge; edge = edge->next())
|
||||||
if (edge_candidate[edge->twin() - front_edge] == 3)
|
if (edge_state[edge->twin() - front_edge] == EdgeState::Active)
|
||||||
return edge->twin();
|
return edge->twin();
|
||||||
assert(false);
|
// assert(false);
|
||||||
return nullptr;
|
return nullptr;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -609,56 +766,66 @@ Polygons voronoi_offset(
|
||||||
const Line &line = lines[cell.source_index()];
|
const Line &line = lines[cell.source_index()];
|
||||||
return cell.contains_point() ?
|
return cell.contains_point() ?
|
||||||
(((cell.source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line.a : line.b).cast<double>() - point).norm() :
|
(((cell.source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line.a : line.b).cast<double>() - point).norm() :
|
||||||
line.distance_to(point.cast<coord_t>());
|
(Geometry::foot_pt<Vec2d>(line.a.cast<double>(), (line.b - line.a).cast<double>(), point) - point).norm();
|
||||||
};
|
};
|
||||||
#endif /* NDEBUG */
|
#endif /* NDEBUG */
|
||||||
|
|
||||||
// Track the offset curves.
|
// Track the offset curves.
|
||||||
Polygons out;
|
Polygons out;
|
||||||
double angle_step = 2. * acos((offset_distance - discretization_error) / offset_distance);
|
double angle_step = 2. * acos((offset_distance - discretization_error) / offset_distance);
|
||||||
double sin_threshold = sin(angle_step) + EPSILON;
|
double cos_threshold = cos(angle_step);
|
||||||
for (size_t seed_edge_idx = 0; seed_edge_idx < vd.num_edges(); ++ seed_edge_idx)
|
for (size_t seed_edge_idx = 0; seed_edge_idx < vd.num_edges(); ++ seed_edge_idx)
|
||||||
if (edge_candidate[seed_edge_idx] == 3) {
|
if (edge_state[seed_edge_idx] == EdgeState::Active) {
|
||||||
const VD::edge_type *start_edge = &vd.edges()[seed_edge_idx];
|
const VD::edge_type *start_edge = &vd.edges()[seed_edge_idx];
|
||||||
const VD::edge_type *edge = start_edge;
|
const VD::edge_type *edge = start_edge;
|
||||||
Polygon poly;
|
Polygon poly;
|
||||||
do {
|
do {
|
||||||
// find the next edge
|
// find the next edge
|
||||||
const VD::edge_type *next_edge = next_offset_edge(edge);
|
const VD::edge_type *next_edge = next_offset_edge(edge);
|
||||||
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
if (next_edge == nullptr) {
|
||||||
|
Lines helper_lines;
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-open-loop-%d.svg", irun).c_str(), vd, Points(), lines, Polygons(), to_lines(poly));
|
||||||
|
}
|
||||||
|
#endif // VORONOI_DEBUG_OUT
|
||||||
|
assert(next_edge);
|
||||||
//std::cout << "offset-output: "; print_edge(edge); std::cout << " to "; print_edge(next_edge); std::cout << "\n";
|
//std::cout << "offset-output: "; print_edge(edge); std::cout << " to "; print_edge(next_edge); std::cout << "\n";
|
||||||
// Interpolate a circular segment or insert a linear segment between edge and next_edge.
|
// Interpolate a circular segment or insert a linear segment between edge and next_edge.
|
||||||
const VD::cell_type *cell = edge->cell();
|
const VD::cell_type *cell = edge->cell();
|
||||||
edge_candidate[next_edge - front_edge] = 0;
|
edge_state[next_edge - front_edge] = EdgeState::Inactive;
|
||||||
Vec2d p1 = edge_offset_point[edge - front_edge];
|
Vec2d p1 = edge_offset_point[edge - front_edge];
|
||||||
Vec2d p2 = edge_offset_point[next_edge - front_edge];
|
Vec2d p2 = edge_offset_point[next_edge - front_edge];
|
||||||
#ifndef NDEBUG
|
#ifndef NDEBUG
|
||||||
{
|
{
|
||||||
double err = dist_to_site(*cell, p1) - offset_distance;
|
double err = dist_to_site(*cell, p1) - offset_distance;
|
||||||
assert(std::abs(err) < SCALED_EPSILON);
|
double err2 = dist_to_site(*cell, p2) - offset_distance;
|
||||||
err = dist_to_site(*cell, p2) - offset_distance;
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
if (std::max(err, err2) >= SCALED_EPSILON) {
|
||||||
|
Lines helper_lines;
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-incorrect_pt-%d.svg", irun).c_str(), vd, Points(), lines, Polygons(), to_lines(poly));
|
||||||
|
}
|
||||||
|
#endif // VORONOI_DEBUG_OUT
|
||||||
assert(std::abs(err) < SCALED_EPSILON);
|
assert(std::abs(err) < SCALED_EPSILON);
|
||||||
|
assert(std::abs(err2) < SCALED_EPSILON);
|
||||||
}
|
}
|
||||||
#endif /* NDEBUG */
|
#endif /* NDEBUG */
|
||||||
if (cell->contains_point()) {
|
if (cell->contains_point()) {
|
||||||
// Discretize an arc from p1 to p2 with radius = offset_distance and discretization_error.
|
// Discretize an arc from p1 to p2 with radius = offset_distance and discretization_error.
|
||||||
// The arc should cover angle < PI.
|
// The extracted contour is CCW oriented, extracted holes are CW oriented.
|
||||||
//FIXME we should be able to produce correctly oriented output curves based on the first edge taken!
|
// The extracted arc will have the same orientation. As the Voronoi regions are convex, the angle covered by the arc will be convex as well.
|
||||||
const Line &line0 = lines[cell->source_index()];
|
const Line &line0 = lines[cell->source_index()];
|
||||||
const Vec2d ¢er = ((cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b).cast<double>();
|
const Vec2d ¢er = ((cell->source_category() == boost::polygon::SOURCE_CATEGORY_SEGMENT_START_POINT) ? line0.a : line0.b).cast<double>();
|
||||||
const Vec2d v1 = p1 - center;
|
const Vec2d v1 = p1 - center;
|
||||||
const Vec2d v2 = p2 - center;
|
const Vec2d v2 = p2 - center;
|
||||||
double orient = cross2(v1, v2);
|
bool ccw = cross2(v1, v2) > 0;
|
||||||
double orient_norm = v1.norm() * v2.norm();
|
double cos_a = v1.dot(v2);
|
||||||
bool ccw = orient > 0;
|
double norm = v1.norm() * v2.norm();
|
||||||
bool obtuse = v1.dot(v2) < 0.;
|
assert(norm > 0.);
|
||||||
if (! ccw)
|
if (cos_a < cos_threshold * norm) {
|
||||||
orient = - orient;
|
|
||||||
assert(orient != 0.);
|
|
||||||
if (obtuse || orient > orient_norm * sin_threshold) {
|
|
||||||
// Angle is bigger than the threshold, therefore the arc will be discretized.
|
// Angle is bigger than the threshold, therefore the arc will be discretized.
|
||||||
double angle = asin(orient / orient_norm);
|
cos_a /= norm;
|
||||||
if (obtuse)
|
assert(cos_a > -1. - EPSILON && cos_a < 1. + EPSILON);
|
||||||
angle = M_PI - angle;
|
double angle = acos(std::max(-1., std::min(1., cos_a)));
|
||||||
size_t n_steps = size_t(ceil(angle / angle_step));
|
size_t n_steps = size_t(ceil(angle / angle_step));
|
||||||
double astep = angle / n_steps;
|
double astep = angle / n_steps;
|
||||||
if (! ccw)
|
if (! ccw)
|
||||||
|
@ -670,9 +837,13 @@ Polygons voronoi_offset(
|
||||||
Vec2d p = center + Vec2d(c * v1.x() - s * v1.y(), s * v1.x() + c * v1.y());
|
Vec2d p = center + Vec2d(c * v1.x() - s * v1.y(), s * v1.x() + c * v1.y());
|
||||||
poly.points.emplace_back(Point(coord_t(p.x()), coord_t(p.y())));
|
poly.points.emplace_back(Point(coord_t(p.x()), coord_t(p.y())));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
poly.points.emplace_back(Point(coord_t(p2.x()), coord_t(p2.y())));
|
{
|
||||||
|
Point pt_last(coord_t(p2.x()), coord_t(p2.y()));
|
||||||
|
if (poly.empty() || poly.points.back() != pt_last)
|
||||||
|
poly.points.emplace_back(pt_last);
|
||||||
|
}
|
||||||
edge = next_edge;
|
edge = next_edge;
|
||||||
} while (edge != start_edge);
|
} while (edge != start_edge);
|
||||||
out.emplace_back(std::move(poly));
|
out.emplace_back(std::move(poly));
|
||||||
|
|
|
@ -305,44 +305,52 @@ static inline void dump_voronoi_to_svg(
|
||||||
const Lines &lines,
|
const Lines &lines,
|
||||||
const Polygons &offset_curves = Polygons(),
|
const Polygons &offset_curves = Polygons(),
|
||||||
const Lines &helper_lines = Lines(),
|
const Lines &helper_lines = Lines(),
|
||||||
const double scale = 0.7) // 0.2?
|
double scale = 0)
|
||||||
{
|
{
|
||||||
const std::string inputSegmentPointColor = "lightseagreen";
|
|
||||||
const coord_t inputSegmentPointRadius = coord_t(0.09 * scale / SCALING_FACTOR);
|
|
||||||
const std::string inputSegmentColor = "lightseagreen";
|
|
||||||
const coord_t inputSegmentLineWidth = coord_t(0.03 * scale / SCALING_FACTOR);
|
|
||||||
|
|
||||||
const std::string voronoiPointColor = "black";
|
|
||||||
const coord_t voronoiPointRadius = coord_t(0.06 * scale / SCALING_FACTOR);
|
|
||||||
const std::string voronoiLineColorPrimary = "black";
|
|
||||||
const std::string voronoiLineColorSecondary = "green";
|
|
||||||
const std::string voronoiArcColor = "red";
|
|
||||||
const coord_t voronoiLineWidth = coord_t(0.02 * scale / SCALING_FACTOR);
|
|
||||||
|
|
||||||
const std::string offsetCurveColor = "magenta";
|
|
||||||
const coord_t offsetCurveLineWidth = coord_t(0.09 * scale / SCALING_FACTOR);
|
|
||||||
|
|
||||||
const std::string helperLineColor = "orange";
|
|
||||||
const coord_t helperLineWidth = coord_t(0.09 * scale / SCALING_FACTOR);
|
|
||||||
|
|
||||||
const bool internalEdgesOnly = false;
|
|
||||||
const bool primaryEdgesOnly = false;
|
|
||||||
|
|
||||||
BoundingBox bbox;
|
BoundingBox bbox;
|
||||||
bbox.merge(get_extents(points));
|
bbox.merge(get_extents(points));
|
||||||
bbox.merge(get_extents(lines));
|
bbox.merge(get_extents(lines));
|
||||||
bbox.merge(get_extents(offset_curves));
|
bbox.merge(get_extents(offset_curves));
|
||||||
|
bbox.merge(get_extents(helper_lines));
|
||||||
bbox.min -= (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
bbox.min -= (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
||||||
bbox.max += (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
bbox.max += (0.01 * bbox.size().cast<double>()).cast<coord_t>();
|
||||||
|
|
||||||
|
if (scale == 0)
|
||||||
|
scale =
|
||||||
|
// 0.1
|
||||||
|
0.01
|
||||||
|
* std::min(bbox.size().x(), bbox.size().y());
|
||||||
|
else
|
||||||
|
scale /= SCALING_FACTOR;
|
||||||
|
|
||||||
|
const std::string inputSegmentPointColor = "lightseagreen";
|
||||||
|
const coord_t inputSegmentPointRadius = coord_t(0.09 * scale);
|
||||||
|
const std::string inputSegmentColor = "lightseagreen";
|
||||||
|
const coord_t inputSegmentLineWidth = coord_t(0.03 * scale);
|
||||||
|
|
||||||
|
const std::string voronoiPointColor = "black";
|
||||||
|
const coord_t voronoiPointRadius = coord_t(0.06 * scale);
|
||||||
|
const std::string voronoiLineColorPrimary = "black";
|
||||||
|
const std::string voronoiLineColorSecondary = "green";
|
||||||
|
const std::string voronoiArcColor = "red";
|
||||||
|
const coord_t voronoiLineWidth = coord_t(0.02 * scale);
|
||||||
|
|
||||||
|
const std::string offsetCurveColor = "magenta";
|
||||||
|
const coord_t offsetCurveLineWidth = coord_t(0.02 * scale);
|
||||||
|
|
||||||
|
const std::string helperLineColor = "orange";
|
||||||
|
const coord_t helperLineWidth = coord_t(0.04 * scale);
|
||||||
|
|
||||||
|
const bool internalEdgesOnly = false;
|
||||||
|
const bool primaryEdgesOnly = false;
|
||||||
|
|
||||||
::Slic3r::SVG svg(path, bbox);
|
::Slic3r::SVG svg(path, bbox);
|
||||||
|
|
||||||
// bbox.scale(1.2);
|
|
||||||
// For clipping of half-lines to some reasonable value.
|
// For clipping of half-lines to some reasonable value.
|
||||||
// The line will then be clipped by the SVG viewer anyway.
|
// The line will then be clipped by the SVG viewer anyway.
|
||||||
const double bbox_dim_max = double(std::max(bbox.size().x(), bbox.size().y()));
|
const double bbox_dim_max = double(std::max(bbox.size().x(), bbox.size().y()));
|
||||||
// For the discretization of the Voronoi parabolic segments.
|
// For the discretization of the Voronoi parabolic segments.
|
||||||
const double discretization_step = 0.05 * bbox_dim_max;
|
const double discretization_step = 0.0002 * bbox_dim_max;
|
||||||
|
|
||||||
// Make a copy of the input segments with the double type.
|
// Make a copy of the input segments with the double type.
|
||||||
std::vector<Voronoi::Internal::segment_type> segments;
|
std::vector<Voronoi::Internal::segment_type> segments;
|
||||||
|
|
|
@ -73,13 +73,6 @@ inline std::string debug_out_path(const char *name, ...)
|
||||||
return std::string(SLIC3R_DEBUG_OUT_PATH_PREFIX) + std::string(buffer);
|
return std::string(SLIC3R_DEBUG_OUT_PATH_PREFIX) + std::string(buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef _MSC_VER
|
|
||||||
// Visual Studio older than 2015 does not support the prinf type specifier %zu. Use %Iu instead.
|
|
||||||
#define PRINTF_ZU "%Iu"
|
|
||||||
#else
|
|
||||||
#define PRINTF_ZU "%zu"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef UNUSED
|
#ifndef UNUSED
|
||||||
#define UNUSED(x) (void)(x)
|
#define UNUSED(x) (void)(x)
|
||||||
#endif /* UNUSED */
|
#endif /* UNUSED */
|
||||||
|
|
|
@ -1198,6 +1198,12 @@ TEST_CASE("Voronoi NaN coordinates 12139", "[Voronoi][!hide][!mayfail]")
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
struct OffsetTest {
|
||||||
|
double distance;
|
||||||
|
size_t num_outer;
|
||||||
|
size_t num_inner;
|
||||||
|
};
|
||||||
|
|
||||||
TEST_CASE("Voronoi offset", "[VoronoiOffset]")
|
TEST_CASE("Voronoi offset", "[VoronoiOffset]")
|
||||||
{
|
{
|
||||||
Polygons poly_with_hole = { Polygon {
|
Polygons poly_with_hole = { Polygon {
|
||||||
|
@ -1210,23 +1216,180 @@ TEST_CASE("Voronoi offset", "[VoronoiOffset]")
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
double area = std::accumulate(poly_with_hole.begin(), poly_with_hole.end(), 0., [](double a, auto &poly){ return a + poly.area(); });
|
||||||
|
REQUIRE(area > 0.);
|
||||||
|
|
||||||
VD vd;
|
VD vd;
|
||||||
Lines lines = to_lines(poly_with_hole);
|
Lines lines = to_lines(poly_with_hole);
|
||||||
construct_voronoi(lines.begin(), lines.end(), &vd);
|
construct_voronoi(lines.begin(), lines.end(), &vd);
|
||||||
|
|
||||||
Polygons offsetted_polygons_out = voronoi_offset(vd, lines, scale_(0.2), scale_(0.005));
|
for (const OffsetTest &ot : {
|
||||||
REQUIRE(offsetted_polygons_out.size() == 1);
|
OffsetTest { scale_(0.2), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.4), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.5), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.505), 1, 2 },
|
||||||
|
OffsetTest { scale_(0.51), 1, 2 },
|
||||||
|
OffsetTest { scale_(0.52), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.53), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.54), 1, 1 },
|
||||||
|
OffsetTest { scale_(0.55), 1, 0 }
|
||||||
|
}) {
|
||||||
|
|
||||||
|
Polygons offsetted_polygons_out = voronoi_offset(vd, lines, ot.distance, scale_(0.005));
|
||||||
|
REQUIRE(offsetted_polygons_out.size() == ot.num_outer);
|
||||||
|
|
||||||
#ifdef VORONOI_DEBUG_OUT
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
dump_voronoi_to_svg(debug_out_path("voronoi-offset-out.svg").c_str(),
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-out-%lf.svg", ot.distance).c_str(),
|
||||||
vd, Points(), lines, offsetted_polygons_out);
|
vd, Points(), lines, offsetted_polygons_out);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Polygons offsetted_polygons_in = voronoi_offset(vd, lines, - scale_(0.2), scale_(0.005));
|
Polygons offsetted_polygons_in = voronoi_offset(vd, lines, - ot.distance, scale_(0.005));
|
||||||
REQUIRE(offsetted_polygons_in.size() == 1);
|
REQUIRE(offsetted_polygons_in.size() == ot.num_inner);
|
||||||
|
|
||||||
#ifdef VORONOI_DEBUG_OUT
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
dump_voronoi_to_svg(debug_out_path("voronoi-offset-in.svg").c_str(),
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset-in-%lf.svg", ot.distance).c_str(),
|
||||||
vd, Points(), lines, offsetted_polygons_in);
|
vd, Points(), lines, offsetted_polygons_in);
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("Voronoi offset 2", "[VoronoiOffset]")
|
||||||
|
{
|
||||||
|
coord_t mm = coord_t(scale_(1.));
|
||||||
|
Polygons poly = {
|
||||||
|
Polygon {
|
||||||
|
{ 0, 0 },
|
||||||
|
{ 1, 0 },
|
||||||
|
{ 1, 1 },
|
||||||
|
{ 2, 1 },
|
||||||
|
{ 2, 0 },
|
||||||
|
{ 3, 0 },
|
||||||
|
{ 3, 2 },
|
||||||
|
{ 0, 2 }
|
||||||
|
},
|
||||||
|
Polygon {
|
||||||
|
{ 0, - 1 - 2 },
|
||||||
|
{ 3, - 1 - 2 },
|
||||||
|
{ 3, - 1 - 0 },
|
||||||
|
{ 2, - 1 - 0 },
|
||||||
|
{ 2, - 1 - 1 },
|
||||||
|
{ 1, - 1 - 1 },
|
||||||
|
{ 1, - 1 - 0 },
|
||||||
|
{ 0, - 1 - 0 }
|
||||||
|
},
|
||||||
|
};
|
||||||
|
for (Polygon &p : poly)
|
||||||
|
for (Point &pt : p.points)
|
||||||
|
pt *= mm;
|
||||||
|
|
||||||
|
double area = std::accumulate(poly.begin(), poly.end(), 0., [](double a, auto &poly){ return a + poly.area(); });
|
||||||
|
REQUIRE(area > 0.);
|
||||||
|
|
||||||
|
VD vd;
|
||||||
|
Lines lines = to_lines(poly);
|
||||||
|
construct_voronoi(lines.begin(), lines.end(), &vd);
|
||||||
|
|
||||||
|
for (const OffsetTest &ot : {
|
||||||
|
OffsetTest { scale_(0.2), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.4), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.45), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.48), 2, 2 },
|
||||||
|
//FIXME Exact intersections of an Offset curve with any Voronoi vertex are not handled correctly yet.
|
||||||
|
// OffsetTest { scale_(0.5), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.505), 2, 4 },
|
||||||
|
OffsetTest { scale_(0.7), 2, 0 },
|
||||||
|
OffsetTest { scale_(0.8), 1, 0 }
|
||||||
|
}) {
|
||||||
|
|
||||||
|
Polygons offsetted_polygons_out = voronoi_offset(vd, lines, ot.distance, scale_(0.005));
|
||||||
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset2-out-%lf.svg", ot.distance).c_str(),
|
||||||
|
vd, Points(), lines, offsetted_polygons_out);
|
||||||
|
#endif
|
||||||
|
REQUIRE(offsetted_polygons_out.size() == ot.num_outer);
|
||||||
|
|
||||||
|
Polygons offsetted_polygons_in = voronoi_offset(vd, lines, - ot.distance, scale_(0.005));
|
||||||
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset2-in-%lf.svg", ot.distance).c_str(),
|
||||||
|
vd, Points(), lines, offsetted_polygons_in);
|
||||||
|
#endif
|
||||||
|
REQUIRE(offsetted_polygons_in.size() == ot.num_inner);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST_CASE("Voronoi offset 3", "[VoronoiOffset]")
|
||||||
|
{
|
||||||
|
coord_t mm = coord_t(scale_(1.));
|
||||||
|
Polygons poly = {
|
||||||
|
Polygon {
|
||||||
|
{ 0, 0 },
|
||||||
|
{ 2, 0 },
|
||||||
|
{ 2, 1 },
|
||||||
|
{ 3, 1 },
|
||||||
|
{ 3, 0 },
|
||||||
|
{ 5, 0 },
|
||||||
|
{ 5, 2 },
|
||||||
|
{ 4, 2 },
|
||||||
|
{ 4, 3 },
|
||||||
|
{ 1, 3 },
|
||||||
|
{ 1, 2 },
|
||||||
|
{ 0, 2 }
|
||||||
|
},
|
||||||
|
Polygon {
|
||||||
|
{ 0, -1 - 2 },
|
||||||
|
{ 1, -1 - 2 },
|
||||||
|
{ 1, -1 - 3 },
|
||||||
|
{ 4, -1 - 3 },
|
||||||
|
{ 4, -1 - 2 },
|
||||||
|
{ 5, -1 - 2 },
|
||||||
|
{ 5, -1 - 0 },
|
||||||
|
{ 3, -1 - 0 },
|
||||||
|
{ 3, -1 - 1 },
|
||||||
|
{ 2, -1 - 1 },
|
||||||
|
{ 2, -1 - 0 },
|
||||||
|
{ 0, -1 - 0 }
|
||||||
|
},
|
||||||
|
};
|
||||||
|
for (Polygon &p : poly) {
|
||||||
|
REQUIRE(p.area() > 0.);
|
||||||
|
for (Point &pt : p.points)
|
||||||
|
pt *= mm;
|
||||||
|
}
|
||||||
|
|
||||||
|
VD vd;
|
||||||
|
Lines lines = to_lines(poly);
|
||||||
|
construct_voronoi(lines.begin(), lines.end(), &vd);
|
||||||
|
|
||||||
|
for (const OffsetTest &ot : {
|
||||||
|
OffsetTest { scale_(0.2), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.4), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.49), 2, 2 },
|
||||||
|
//FIXME this fails
|
||||||
|
// OffsetTest { scale_(0.5), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.51), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.56), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.6), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.7), 2, 2 },
|
||||||
|
OffsetTest { scale_(0.8), 1, 6 },
|
||||||
|
OffsetTest { scale_(0.9), 1, 6 },
|
||||||
|
OffsetTest { scale_(0.99), 1, 6 },
|
||||||
|
//FIXME this fails
|
||||||
|
// OffsetTest { scale_(1.0), 1, 6 },
|
||||||
|
OffsetTest { scale_(1.01), 1, 0 },
|
||||||
|
}) {
|
||||||
|
|
||||||
|
Polygons offsetted_polygons_out = voronoi_offset(vd, lines, ot.distance, scale_(0.005));
|
||||||
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset2-out-%lf.svg", ot.distance).c_str(),
|
||||||
|
vd, Points(), lines, offsetted_polygons_out);
|
||||||
|
#endif
|
||||||
|
REQUIRE(offsetted_polygons_out.size() == ot.num_outer);
|
||||||
|
|
||||||
|
Polygons offsetted_polygons_in = voronoi_offset(vd, lines, - ot.distance, scale_(0.005));
|
||||||
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
dump_voronoi_to_svg(debug_out_path("voronoi-offset2-in-%lf.svg", ot.distance).c_str(),
|
||||||
|
vd, Points(), lines, offsetted_polygons_in);
|
||||||
|
#endif
|
||||||
|
REQUIRE(offsetted_polygons_in.size() == ot.num_inner);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in a new issue