mirror of
https://github.com/SoftFever/OrcaSlicer.git
synced 2025-10-23 16:51:21 -06:00
Fixed conflict after merge with master
This commit is contained in:
commit
5c7b0948bc
25 changed files with 1168 additions and 366 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;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::vector<std::pair<EdgeGrid::Grid::ContourEdge, EdgeGrid::Grid::ContourEdge>> out;
|
||||||
|
if (cnt > 0) {
|
||||||
len /= double(cnt);
|
len /= double(cnt);
|
||||||
bbox.offset(20);
|
bbox.offset(20);
|
||||||
EdgeGrid::Grid grid;
|
EdgeGrid::Grid grid;
|
||||||
grid.set_bbox(bbox);
|
grid.set_bbox(bbox);
|
||||||
grid.create(polygons, len);
|
grid.create(polygons, len);
|
||||||
return grid.intersecting_edges();
|
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 bool segments_intersect(
|
||||||
inline int segments_could_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 iv = (ip2 - ip1).cast<int64_t>();
|
||||||
Vec2i64 vij1 = (jp1 - ip1).cast<int64_t>();
|
Vec2i64 vij1 = (jp1 - ip1).cast<int64_t>();
|
||||||
Vec2i64 vij2 = (jp2 - ip1).cast<int64_t>();
|
Vec2i64 vij2 = (jp2 - ip1).cast<int64_t>();
|
||||||
int64_t tij1 = cross2(iv, vij1);
|
int64_t tij1 = cross2(iv, vij1);
|
||||||
int64_t tij2 = cross2(iv, vij2);
|
int64_t tij2 = cross2(iv, vij2);
|
||||||
int sij1 = (tij1 > 0) ? 1 : ((tij1 < 0) ? -1 : 0); // signum
|
return std::make_pair(
|
||||||
int sij2 = (tij2 > 0) ? 1 : ((tij2 < 0) ? -1 : 0);
|
// signum
|
||||||
return sij1 * sij2;
|
(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;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline bool segments_intersect(
|
template<typename T> inline T foot_pt(const T &line_pt, const T &line_dir, const T &pt)
|
||||||
const Slic3r::Point &ip1, const Slic3r::Point &ip2,
|
|
||||||
const Slic3r::Point &jp1, const Slic3r::Point &jp2)
|
|
||||||
{
|
{
|
||||||
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());
|
||||||
|
if (poly.points.size() > 2) {
|
||||||
for (Points::const_iterator it = poly.points.begin(); it != poly.points.end()-1; ++it)
|
for (Points::const_iterator it = poly.points.begin(); it != poly.points.end()-1; ++it)
|
||||||
lines.push_back(Line(*it, *(it + 1)));
|
lines.push_back(Line(*it, *(it + 1)));
|
||||||
lines.push_back(Line(poly.points.back(), poly.points.front()));
|
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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -51,6 +51,12 @@
|
||||||
// Enable error logging for OpenGL calls when SLIC3R_LOGLEVEL >= 5
|
// Enable error logging for OpenGL calls when SLIC3R_LOGLEVEL >= 5
|
||||||
#define ENABLE_OPENGL_ERROR_LOGGING (1 && ENABLE_2_3_0_ALPHA1)
|
#define ENABLE_OPENGL_ERROR_LOGGING (1 && ENABLE_2_3_0_ALPHA1)
|
||||||
|
|
||||||
|
// Enable built-in DPI changed event handler of wxWidgets 3.1.3
|
||||||
|
#define ENABLE_WX_3_1_3_DPI_CHANGED_EVENT (1 && ENABLE_2_3_0_ALPHA1)
|
||||||
|
|
||||||
|
// Enable changing application layout without the need to restart
|
||||||
|
#define ENABLE_LAYOUT_NO_RESTART (1 && ENABLE_2_3_0_ALPHA1)
|
||||||
|
|
||||||
// Enable G-Code viewer
|
// Enable G-Code viewer
|
||||||
#define ENABLE_GCODE_VIEWER (1 && ENABLE_2_3_0_ALPHA1)
|
#define ENABLE_GCODE_VIEWER (1 && ENABLE_2_3_0_ALPHA1)
|
||||||
#define ENABLE_GCODE_VIEWER_STATISTICS (0 && ENABLE_GCODE_VIEWER)
|
#define ENABLE_GCODE_VIEWER_STATISTICS (0 && ENABLE_GCODE_VIEWER)
|
||||||
|
|
|
@ -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,105 +172,29 @@ 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,
|
||||||
|
@ -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);
|
||||||
|
std::vector<CellState> cell_state(vd.num_cells(), CellState::Unknown);
|
||||||
const VD::edge_type *front_edge = &vd.edges().front();
|
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;
|
||||||
|
@ -282,37 +320,113 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
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);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
{
|
||||||
|
// Perform one round of expansion marking Voronoi edges and cells next to boundary cells as active / inactive.
|
||||||
|
std::vector<const VD::cell_type*> cell_queue;
|
||||||
for (const VD::edge_type &edge : vd.edges())
|
for (const VD::edge_type &edge : vd.edges())
|
||||||
if (edge_candidate[&edge - front_edge] == 2) {
|
if (edge_state[&edge - front_edge] == EdgeState::Unknown) {
|
||||||
assert(edge.cell()->contains_point() && edge.twin()->cell()->contains_point());
|
assert(edge.cell()->contains_point() && edge.twin()->cell()->contains_point());
|
||||||
// Edge separating two point sources, not yet classified as inside / outside.
|
// Edge separating two point sources, not yet classified as inside / outside.
|
||||||
const VD::edge_type *e = &edge;
|
CellState cs = cell_state[edge.cell() - front_cell];
|
||||||
char state;
|
CellState cs2 = cell_state[edge.twin()->cell() - front_cell];
|
||||||
|
if (cs != CellState::Unknown || cs2 != CellState::Unknown) {
|
||||||
|
if (cs == CellState::Unknown) {
|
||||||
|
cs = cs2;
|
||||||
|
if (set_cell_state(edge.cell(), cs))
|
||||||
|
cell_queue.emplace_back(edge.cell());
|
||||||
|
} else if (set_cell_state(edge.twin()->cell(), cs))
|
||||||
|
cell_queue.emplace_back(edge.twin()->cell());
|
||||||
|
EdgeState es = (cs == CellState::Active) ? EdgeState::Possible : EdgeState::Inactive;
|
||||||
|
set_edge_state_initial(&edge, es);
|
||||||
|
set_edge_state_initial(edge.twin(), es);
|
||||||
|
} else {
|
||||||
|
const VD::edge_type *e = edge.twin()->rot_prev();
|
||||||
do {
|
do {
|
||||||
state = edge_candidate[e - front_edge];
|
EdgeState es = edge_state[e->twin() - front_edge];
|
||||||
if (state != 2)
|
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;
|
break;
|
||||||
e = e->next();
|
}
|
||||||
} while (e != &edge);
|
e = e->rot_prev();
|
||||||
e = &edge;
|
} while (e != edge.twin());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// 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 {
|
do {
|
||||||
char &s = edge_candidate[e - front_edge];
|
if (set_cell_state(edge->twin()->cell(), cs)) {
|
||||||
if (s == 2) {
|
set_edge_state_initial(edge, es);
|
||||||
assert(e->cell()->contains_point() && e->twin()->cell()->contains_point());
|
set_edge_state_initial(edge->twin(), es);
|
||||||
assert(edge_candidate[e->twin() - front_edge] == 2);
|
cell_queue.emplace_back(edge->twin()->cell());
|
||||||
s = state;
|
|
||||||
edge_candidate[e->twin() - front_edge] = state;
|
|
||||||
}
|
}
|
||||||
e = e->next();
|
edge = edge->next();
|
||||||
} while (e != &edge);
|
} 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) :
|
||||||
|
@ -430,18 +548,13 @@ Polygons voronoi_offset(
|
||||||
// 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.
|
||||||
|
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;
|
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);
|
||||||
|
if (dmin_new < dmin) {
|
||||||
dmin = dmin_new;
|
dmin = dmin_new;
|
||||||
has_intersection = offset_distance2 >= dmin;
|
has_intersection = possibly_two_points = offset_distance2 >= dmin;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (has_intersection) {
|
if (has_intersection) {
|
||||||
|
@ -540,9 +674,13 @@ 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.
|
||||||
|
if (possibly_two_points) {
|
||||||
Vec2d v = p1 - p0;
|
Vec2d v = p1 - p0;
|
||||||
double l2 = v.squaredNorm();
|
double l2 = v.squaredNorm();
|
||||||
double t0 = v.dot(intersections.pts[0] - p0);
|
double t0 = v.dot(intersections.pts[0] - p0);
|
||||||
|
@ -562,45 +700,64 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
} else if (t1 < 0. || t1 > l2)
|
} else if (t1 < 0. || t1 > l2)
|
||||||
-- intersections.count;
|
-- 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;
|
||||||
|
}
|
||||||
|
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;
|
||||||
|
double err2 = 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);
|
||||||
err = dist_to_site(*cell, p2) - offset_distance;
|
assert(std::abs(err2) < SCALED_EPSILON);
|
||||||
assert(std::abs(err) < 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)
|
||||||
|
@ -672,7 +839,11 @@ Polygons voronoi_offset(
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
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;
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
// Saves around 32% RAM after slicing step, 6.7% after G-code export (tested on PrusaSlicer 2.2.0 final).
|
// Saves around 32% RAM after slicing step, 6.7% after G-code export (tested on PrusaSlicer 2.2.0 final).
|
||||||
using coord_t = int32_t;
|
using coord_t = int32_t;
|
||||||
#else
|
#else
|
||||||
//FIXME At least FillRectilinear2 requires coord_t to be 32bit.
|
//FIXME At least FillRectilinear2 and std::boost Voronoi require coord_t to be 32bit.
|
||||||
typedef int64_t coord_t;
|
typedef int64_t coord_t;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -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 */
|
||||||
|
|
|
@ -106,6 +106,7 @@ wxString file_wildcards(FileType file_type, const std::string &custom_extension)
|
||||||
static std::string libslic3r_translate_callback(const char *s) { return wxGetTranslation(wxString(s, wxConvUTF8)).utf8_str().data(); }
|
static std::string libslic3r_translate_callback(const char *s) { return wxGetTranslation(wxString(s, wxConvUTF8)).utf8_str().data(); }
|
||||||
|
|
||||||
#ifdef WIN32
|
#ifdef WIN32
|
||||||
|
#if !wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
static void register_win32_dpi_event()
|
static void register_win32_dpi_event()
|
||||||
{
|
{
|
||||||
enum { WM_DPICHANGED_ = 0x02e0 };
|
enum { WM_DPICHANGED_ = 0x02e0 };
|
||||||
|
@ -121,13 +122,12 @@ static void register_win32_dpi_event()
|
||||||
return true;
|
return true;
|
||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
#endif // !wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
|
||||||
static GUID GUID_DEVINTERFACE_HID = { 0x4D1E55B2, 0xF16F, 0x11CF, 0x88, 0xCB, 0x00, 0x11, 0x11, 0x00, 0x00, 0x30 };
|
static GUID GUID_DEVINTERFACE_HID = { 0x4D1E55B2, 0xF16F, 0x11CF, 0x88, 0xCB, 0x00, 0x11, 0x11, 0x00, 0x00, 0x30 };
|
||||||
|
|
||||||
static void register_win32_device_notification_event()
|
static void register_win32_device_notification_event()
|
||||||
{
|
{
|
||||||
enum { WM_DPICHANGED_ = 0x02e0 };
|
|
||||||
|
|
||||||
wxWindow::MSWRegisterMessageHandler(WM_DEVICECHANGE, [](wxWindow *win, WXUINT /* nMsg */, WXWPARAM wParam, WXLPARAM lParam) {
|
wxWindow::MSWRegisterMessageHandler(WM_DEVICECHANGE, [](wxWindow *win, WXUINT /* nMsg */, WXWPARAM wParam, WXLPARAM lParam) {
|
||||||
// Some messages are sent to top level windows by default, some messages are sent to only registered windows, and we explictely register on MainFrame only.
|
// Some messages are sent to top level windows by default, some messages are sent to only registered windows, and we explictely register on MainFrame only.
|
||||||
auto main_frame = dynamic_cast<MainFrame*>(win);
|
auto main_frame = dynamic_cast<MainFrame*>(win);
|
||||||
|
@ -410,7 +410,9 @@ bool GUI_App::on_init_inner()
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef WIN32
|
#ifdef WIN32
|
||||||
|
#if !wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
register_win32_dpi_event();
|
register_win32_dpi_event();
|
||||||
|
#endif // !wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
register_win32_device_notification_event();
|
register_win32_device_notification_event();
|
||||||
#endif // WIN32
|
#endif // WIN32
|
||||||
|
|
||||||
|
@ -1073,17 +1075,34 @@ void GUI_App::add_config_menu(wxMenuBar *menu)
|
||||||
break;
|
break;
|
||||||
case ConfigMenuPreferences:
|
case ConfigMenuPreferences:
|
||||||
{
|
{
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
bool app_layout_changed = false;
|
||||||
|
#else
|
||||||
bool recreate_app = false;
|
bool recreate_app = false;
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
{
|
{
|
||||||
// the dialog needs to be destroyed before the call to recreate_GUI()
|
// the dialog needs to be destroyed before the call to recreate_GUI()
|
||||||
// or sometimes the application crashes into wxDialogBase() destructor
|
// or sometimes the application crashes into wxDialogBase() destructor
|
||||||
// so we put it into an inner scope
|
// so we put it into an inner scope
|
||||||
PreferencesDialog dlg(mainframe);
|
PreferencesDialog dlg(mainframe);
|
||||||
dlg.ShowModal();
|
dlg.ShowModal();
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
app_layout_changed = dlg.settings_layout_changed();
|
||||||
|
#else
|
||||||
recreate_app = dlg.settings_layout_changed();
|
recreate_app = dlg.settings_layout_changed();
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
}
|
}
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (app_layout_changed) {
|
||||||
|
mainframe->Hide();
|
||||||
|
mainframe->update_layout();
|
||||||
|
mainframe->select_tab(0);
|
||||||
|
mainframe->Show();
|
||||||
|
}
|
||||||
|
#else
|
||||||
if (recreate_app)
|
if (recreate_app)
|
||||||
recreate_GUI(_L("Changing of the settings layout") + dots);
|
recreate_GUI(_L("Changing of the settings layout") + dots);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
case ConfigMenuLanguage:
|
case ConfigMenuLanguage:
|
||||||
|
|
|
@ -61,7 +61,9 @@ void on_window_geometry(wxTopLevelWindow *tlw, std::function<void()> callback)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if !wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
wxDEFINE_EVENT(EVT_DPI_CHANGED_SLICER, DpiChangedEvent);
|
wxDEFINE_EVENT(EVT_DPI_CHANGED_SLICER, DpiChangedEvent);
|
||||||
|
#endif // !wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
|
||||||
#ifdef _WIN32
|
#ifdef _WIN32
|
||||||
template<class F> typename F::FN winapi_get_function(const wchar_t *dll, const char *fn_name) {
|
template<class F> typename F::FN winapi_get_function(const wchar_t *dll, const char *fn_name) {
|
||||||
|
|
|
@ -24,6 +24,11 @@ class wxCheckBox;
|
||||||
class wxTopLevelWindow;
|
class wxTopLevelWindow;
|
||||||
class wxRect;
|
class wxRect;
|
||||||
|
|
||||||
|
#if ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
#define wxVERSION_EQUAL_OR_GREATER_THAN(major, minor, release) ((wxMAJOR_VERSION > major) || ((wxMAJOR_VERSION == major) && (wxMINOR_VERSION > minor)) || ((wxMAJOR_VERSION == major) && (wxMINOR_VERSION == minor) && (wxRELEASE_NUMBER >= release)))
|
||||||
|
#else
|
||||||
|
#define wxVERSION_EQUAL_OR_GREATER_THAN(major, minor, release) 0
|
||||||
|
#endif // ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
namespace GUI {
|
namespace GUI {
|
||||||
|
@ -51,6 +56,7 @@ enum { DPI_DEFAULT = 96 };
|
||||||
int get_dpi_for_window(wxWindow *window);
|
int get_dpi_for_window(wxWindow *window);
|
||||||
wxFont get_default_font_for_dpi(int dpi);
|
wxFont get_default_font_for_dpi(int dpi);
|
||||||
|
|
||||||
|
#if !wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
struct DpiChangedEvent : public wxEvent {
|
struct DpiChangedEvent : public wxEvent {
|
||||||
int dpi;
|
int dpi;
|
||||||
wxRect rect;
|
wxRect rect;
|
||||||
|
@ -66,6 +72,7 @@ struct DpiChangedEvent : public wxEvent {
|
||||||
};
|
};
|
||||||
|
|
||||||
wxDECLARE_EVENT(EVT_DPI_CHANGED_SLICER, DpiChangedEvent);
|
wxDECLARE_EVENT(EVT_DPI_CHANGED_SLICER, DpiChangedEvent);
|
||||||
|
#endif // !wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
|
||||||
template<class P> class DPIAware : public P
|
template<class P> class DPIAware : public P
|
||||||
{
|
{
|
||||||
|
@ -86,11 +93,33 @@ public:
|
||||||
this->SetFont(m_normal_font);
|
this->SetFont(m_normal_font);
|
||||||
#endif
|
#endif
|
||||||
// initialize default width_unit according to the width of the one symbol ("m") of the currently active font of this window.
|
// initialize default width_unit according to the width of the one symbol ("m") of the currently active font of this window.
|
||||||
|
#if ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
m_em_unit = std::max<size_t>(10, 10.0f * m_scale_factor);
|
||||||
|
#else
|
||||||
m_em_unit = std::max<size_t>(10, this->GetTextExtent("m").x - 1);
|
m_em_unit = std::max<size_t>(10, this->GetTextExtent("m").x - 1);
|
||||||
|
#endif // ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
|
||||||
// recalc_font();
|
// recalc_font();
|
||||||
|
|
||||||
this->Bind(EVT_DPI_CHANGED_SLICER, [this](const DpiChangedEvent &evt) {
|
#if wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
|
this->Bind(wxEVT_DPI_CHANGED, [this](wxDPIChangedEvent& evt) {
|
||||||
|
m_scale_factor = (float)evt.GetNewDPI().x / (float)DPI_DEFAULT;
|
||||||
|
|
||||||
|
m_new_font_point_size = get_default_font_for_dpi(evt.GetNewDPI().x).GetPointSize();
|
||||||
|
|
||||||
|
if (!m_can_rescale)
|
||||||
|
return;
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_force_rescale || is_new_scale_factor())
|
||||||
|
rescale(wxRect());
|
||||||
|
#else
|
||||||
|
if (is_new_scale_factor())
|
||||||
|
rescale(wxRect());
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
});
|
||||||
|
#else
|
||||||
|
this->Bind(EVT_DPI_CHANGED_SLICER, [this](const DpiChangedEvent& evt) {
|
||||||
m_scale_factor = (float)evt.dpi / (float)DPI_DEFAULT;
|
m_scale_factor = (float)evt.dpi / (float)DPI_DEFAULT;
|
||||||
|
|
||||||
m_new_font_point_size = get_default_font_for_dpi(evt.dpi).GetPointSize();
|
m_new_font_point_size = get_default_font_for_dpi(evt.dpi).GetPointSize();
|
||||||
|
@ -98,9 +127,15 @@ public:
|
||||||
if (!m_can_rescale)
|
if (!m_can_rescale)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_force_rescale || is_new_scale_factor())
|
||||||
|
rescale(evt.rect);
|
||||||
|
#else
|
||||||
if (is_new_scale_factor())
|
if (is_new_scale_factor())
|
||||||
rescale(evt.rect);
|
rescale(evt.rect);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
});
|
});
|
||||||
|
#endif // wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
|
||||||
this->Bind(wxEVT_MOVE_START, [this](wxMoveEvent& event)
|
this->Bind(wxEVT_MOVE_START, [this](wxMoveEvent& event)
|
||||||
{
|
{
|
||||||
|
@ -140,6 +175,9 @@ public:
|
||||||
int em_unit() const { return m_em_unit; }
|
int em_unit() const { return m_em_unit; }
|
||||||
// int font_size() const { return m_font_size; }
|
// int font_size() const { return m_font_size; }
|
||||||
const wxFont& normal_font() const { return m_normal_font; }
|
const wxFont& normal_font() const { return m_normal_font; }
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
void enable_force_rescale() { m_force_rescale = true; }
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
virtual void on_dpi_changed(const wxRect &suggested_rect) = 0;
|
virtual void on_dpi_changed(const wxRect &suggested_rect) = 0;
|
||||||
|
@ -153,6 +191,9 @@ private:
|
||||||
wxFont m_normal_font;
|
wxFont m_normal_font;
|
||||||
float m_prev_scale_factor;
|
float m_prev_scale_factor;
|
||||||
bool m_can_rescale{ true };
|
bool m_can_rescale{ true };
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
bool m_force_rescale{ false };
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
int m_new_font_point_size;
|
int m_new_font_point_size;
|
||||||
|
|
||||||
|
@ -192,17 +233,27 @@ private:
|
||||||
{
|
{
|
||||||
this->Freeze();
|
this->Freeze();
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_force_rescale) {
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
// rescale fonts of all controls
|
// rescale fonts of all controls
|
||||||
scale_controls_fonts(this, m_new_font_point_size);
|
scale_controls_fonts(this, m_new_font_point_size);
|
||||||
// rescale current window font
|
// rescale current window font
|
||||||
scale_win_font(this, m_new_font_point_size);
|
scale_win_font(this, m_new_font_point_size);
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
m_force_rescale = false;
|
||||||
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// set normal application font as a current window font
|
// set normal application font as a current window font
|
||||||
m_normal_font = this->GetFont();
|
m_normal_font = this->GetFont();
|
||||||
|
|
||||||
// update em_unit value for new window font
|
// update em_unit value for new window font
|
||||||
|
#if ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
m_em_unit = std::max<int>(10, 10.0f * m_scale_factor);
|
||||||
|
#else
|
||||||
m_em_unit = std::max<size_t>(10, this->GetTextExtent("m").x - 1);
|
m_em_unit = std::max<size_t>(10, this->GetTextExtent("m").x - 1);
|
||||||
|
#endif // ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
|
||||||
// rescale missed controls sizes and images
|
// rescale missed controls sizes and images
|
||||||
on_dpi_changed(suggested_rect);
|
on_dpi_changed(suggested_rect);
|
||||||
|
|
|
@ -448,6 +448,7 @@ void SupportsClipper::render_cut() const
|
||||||
|
|
||||||
// Get transformation of supports
|
// Get transformation of supports
|
||||||
Geometry::Transformation supports_trafo = trafo;
|
Geometry::Transformation supports_trafo = trafo;
|
||||||
|
supports_trafo.set_scaling_factor(Vec3d::Ones());
|
||||||
supports_trafo.set_offset(Vec3d(trafo.get_offset()(0), trafo.get_offset()(1), sel_info->get_sla_shift()));
|
supports_trafo.set_offset(Vec3d(trafo.get_offset()(0), trafo.get_offset()(1), sel_info->get_sla_shift()));
|
||||||
supports_trafo.set_rotation(Vec3d(0., 0., trafo.get_rotation()(2)));
|
supports_trafo.set_rotation(Vec3d(0., 0., trafo.get_rotation()(2)));
|
||||||
// I don't know why, but following seems to be correct.
|
// I don't know why, but following seems to be correct.
|
||||||
|
|
|
@ -42,10 +42,44 @@
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
namespace GUI {
|
namespace GUI {
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
enum class ERescaleTarget
|
||||||
|
{
|
||||||
|
Mainframe,
|
||||||
|
SettingsDialog
|
||||||
|
};
|
||||||
|
|
||||||
|
static void rescale_dialog_after_dpi_change(MainFrame& mainframe, SettingsDialog& dialog, ERescaleTarget target)
|
||||||
|
{
|
||||||
|
int mainframe_dpi = get_dpi_for_window(&mainframe);
|
||||||
|
int dialog_dpi = get_dpi_for_window(&dialog);
|
||||||
|
if (mainframe_dpi != dialog_dpi) {
|
||||||
|
if (target == ERescaleTarget::SettingsDialog) {
|
||||||
|
dialog.enable_force_rescale();
|
||||||
|
#if wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
|
dialog.GetEventHandler()->AddPendingEvent(wxDPIChangedEvent(wxSize(mainframe_dpi, mainframe_dpi), wxSize(dialog_dpi, dialog_dpi)));
|
||||||
|
#else
|
||||||
|
dialog.GetEventHandler()->AddPendingEvent(DpiChangedEvent(EVT_DPI_CHANGED_SLICER, dialog_dpi, dialog.GetRect()));
|
||||||
|
#endif // wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
} else {
|
||||||
|
#if wxVERSION_EQUAL_OR_GREATER_THAN(3,1,3)
|
||||||
|
mainframe.GetEventHandler()->AddPendingEvent(wxDPIChangedEvent(wxSize(dialog_dpi, dialog_dpi), wxSize(mainframe_dpi, mainframe_dpi)));
|
||||||
|
#else
|
||||||
|
mainframe.enable_force_rescale();
|
||||||
|
mainframe.GetEventHandler()->AddPendingEvent(DpiChangedEvent(EVT_DPI_CHANGED_SLICER, mainframe_dpi, mainframe.GetRect()));
|
||||||
|
#endif // wxVERSION_EQUAL_OR_GREATER_THAN
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
MainFrame::MainFrame() :
|
MainFrame::MainFrame() :
|
||||||
DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_STYLE, "mainframe"),
|
DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_STYLE, "mainframe"),
|
||||||
m_printhost_queue_dlg(new PrintHostQueueDialog(this))
|
m_printhost_queue_dlg(new PrintHostQueueDialog(this))
|
||||||
, m_recent_projects(9)
|
, m_recent_projects(9)
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
, m_settings_dialog(this)
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
{
|
{
|
||||||
// Fonts were created by the DPIFrame constructor for the monitor, on which the window opened.
|
// Fonts were created by the DPIFrame constructor for the monitor, on which the window opened.
|
||||||
wxGetApp().update_fonts(this);
|
wxGetApp().update_fonts(this);
|
||||||
|
@ -108,6 +142,7 @@ DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_S
|
||||||
|
|
||||||
m_loaded = true;
|
m_loaded = true;
|
||||||
|
|
||||||
|
#if !ENABLE_LAYOUT_NO_RESTART
|
||||||
#ifdef __APPLE__
|
#ifdef __APPLE__
|
||||||
// Using SetMinSize() on Mac messes up the window position in some cases
|
// Using SetMinSize() on Mac messes up the window position in some cases
|
||||||
// cf. https://groups.google.com/forum/#!topic/wx-users/yUKPBBfXWO0
|
// cf. https://groups.google.com/forum/#!topic/wx-users/yUKPBBfXWO0
|
||||||
|
@ -121,8 +156,17 @@ DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_S
|
||||||
m_tabpanel->SetMinSize(size);
|
m_tabpanel->SetMinSize(size);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
#endif // !ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// initialize layout
|
// initialize layout
|
||||||
auto sizer = new wxBoxSizer(wxVERTICAL);
|
auto sizer = new wxBoxSizer(wxVERTICAL);
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
SetSizer(sizer);
|
||||||
|
// initialize layout from config
|
||||||
|
update_layout();
|
||||||
|
sizer->SetSizeHints(this);
|
||||||
|
Fit();
|
||||||
|
#else
|
||||||
if (m_plater && m_layout != slOld)
|
if (m_plater && m_layout != slOld)
|
||||||
sizer->Add(m_plater, 1, wxEXPAND);
|
sizer->Add(m_plater, 1, wxEXPAND);
|
||||||
|
|
||||||
|
@ -132,6 +176,7 @@ DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_S
|
||||||
sizer->SetSizeHints(this);
|
sizer->SetSizeHints(this);
|
||||||
SetSizer(sizer);
|
SetSizer(sizer);
|
||||||
Fit();
|
Fit();
|
||||||
|
#endif // !ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
const wxSize min_size = wxGetApp().get_min_size(); //wxSize(76*wxGetApp().em_unit(), 49*wxGetApp().em_unit());
|
const wxSize min_size = wxGetApp().get_min_size(); //wxSize(76*wxGetApp().em_unit(), 49*wxGetApp().em_unit());
|
||||||
#ifdef __APPLE__
|
#ifdef __APPLE__
|
||||||
|
@ -223,8 +268,12 @@ DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_S
|
||||||
});
|
});
|
||||||
|
|
||||||
wxGetApp().persist_window_geometry(this, true);
|
wxGetApp().persist_window_geometry(this, true);
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
wxGetApp().persist_window_geometry(&m_settings_dialog, true);
|
||||||
|
#else
|
||||||
if (m_settings_dialog != nullptr)
|
if (m_settings_dialog != nullptr)
|
||||||
wxGetApp().persist_window_geometry(m_settings_dialog, true);
|
wxGetApp().persist_window_geometry(m_settings_dialog, true);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
update_ui_from_settings(); // FIXME (?)
|
update_ui_from_settings(); // FIXME (?)
|
||||||
|
|
||||||
|
@ -232,6 +281,123 @@ DPIFrame(NULL, wxID_ANY, "", wxDefaultPosition, wxDefaultSize, wxDEFAULT_FRAME_S
|
||||||
m_plater->show_action_buttons(true);
|
m_plater->show_action_buttons(true);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
void MainFrame::update_layout()
|
||||||
|
{
|
||||||
|
auto restore_to_creation = [this]() {
|
||||||
|
auto clean_sizer = [](wxSizer* sizer) {
|
||||||
|
while (!sizer->GetChildren().IsEmpty()) {
|
||||||
|
sizer->Detach(0);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// On Linux m_plater needs to be removed from m_tabpanel before to reparent it
|
||||||
|
int plater_page_id = m_tabpanel->FindPage(m_plater);
|
||||||
|
if (plater_page_id != wxNOT_FOUND)
|
||||||
|
m_tabpanel->RemovePage(plater_page_id);
|
||||||
|
|
||||||
|
if (m_plater->GetParent() != this)
|
||||||
|
m_plater->Reparent(this);
|
||||||
|
|
||||||
|
if (m_tabpanel->GetParent() != this)
|
||||||
|
m_tabpanel->Reparent(this);
|
||||||
|
|
||||||
|
plater_page_id = (m_plater_page != nullptr) ? m_tabpanel->FindPage(m_plater_page) : wxNOT_FOUND;
|
||||||
|
if (plater_page_id != wxNOT_FOUND) {
|
||||||
|
m_tabpanel->DeletePage(plater_page_id);
|
||||||
|
m_plater_page = nullptr;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (m_layout == ESettingsLayout::Dlg)
|
||||||
|
rescale_dialog_after_dpi_change(*this, m_settings_dialog, ERescaleTarget::Mainframe);
|
||||||
|
|
||||||
|
clean_sizer(GetSizer());
|
||||||
|
clean_sizer(m_settings_dialog.GetSizer());
|
||||||
|
|
||||||
|
if (m_settings_dialog.IsShown())
|
||||||
|
m_settings_dialog.Close();
|
||||||
|
|
||||||
|
m_tabpanel->Hide();
|
||||||
|
m_plater->Hide();
|
||||||
|
|
||||||
|
Layout();
|
||||||
|
};
|
||||||
|
|
||||||
|
ESettingsLayout layout = wxGetApp().app_config->get("old_settings_layout_mode") == "1" ? ESettingsLayout::Old :
|
||||||
|
wxGetApp().app_config->get("new_settings_layout_mode") == "1" ? ESettingsLayout::New :
|
||||||
|
wxGetApp().app_config->get("dlg_settings_layout_mode") == "1" ? ESettingsLayout::Dlg : ESettingsLayout::Old;
|
||||||
|
|
||||||
|
if (m_layout == layout)
|
||||||
|
return;
|
||||||
|
|
||||||
|
wxBusyCursor busy;
|
||||||
|
|
||||||
|
Freeze();
|
||||||
|
|
||||||
|
// Remove old settings
|
||||||
|
if (m_layout != ESettingsLayout::Unknown)
|
||||||
|
restore_to_creation();
|
||||||
|
|
||||||
|
m_layout = layout;
|
||||||
|
|
||||||
|
// From the very beginning the Print settings should be selected
|
||||||
|
m_last_selected_tab = m_layout == ESettingsLayout::Dlg ? 0 : 1;
|
||||||
|
|
||||||
|
// Set new settings
|
||||||
|
switch (m_layout)
|
||||||
|
{
|
||||||
|
case ESettingsLayout::Old:
|
||||||
|
{
|
||||||
|
m_plater->Reparent(m_tabpanel);
|
||||||
|
m_tabpanel->InsertPage(0, m_plater, _L("Plater"));
|
||||||
|
GetSizer()->Add(m_tabpanel, 1, wxEXPAND);
|
||||||
|
m_plater->Show();
|
||||||
|
m_tabpanel->Show();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case ESettingsLayout::New:
|
||||||
|
{
|
||||||
|
GetSizer()->Add(m_plater, 1, wxEXPAND);
|
||||||
|
m_tabpanel->Hide();
|
||||||
|
GetSizer()->Add(m_tabpanel, 1, wxEXPAND);
|
||||||
|
m_plater_page = new wxPanel(m_tabpanel);
|
||||||
|
m_tabpanel->InsertPage(0, m_plater_page, _L("Plater")); // empty panel just for Plater tab */
|
||||||
|
m_plater->Show();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case ESettingsLayout::Dlg:
|
||||||
|
{
|
||||||
|
GetSizer()->Add(m_plater, 1, wxEXPAND);
|
||||||
|
m_tabpanel->Reparent(&m_settings_dialog);
|
||||||
|
m_settings_dialog.GetSizer()->Add(m_tabpanel, 1, wxEXPAND);
|
||||||
|
|
||||||
|
rescale_dialog_after_dpi_change(*this, m_settings_dialog, ERescaleTarget::SettingsDialog);
|
||||||
|
|
||||||
|
m_tabpanel->Show();
|
||||||
|
m_plater->Show();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
//#ifdef __APPLE__
|
||||||
|
// // Using SetMinSize() on Mac messes up the window position in some cases
|
||||||
|
// // cf. https://groups.google.com/forum/#!topic/wx-users/yUKPBBfXWO0
|
||||||
|
// // So, if we haven't possibility to set MinSize() for the MainFrame,
|
||||||
|
// // set the MinSize() as a half of regular for the m_plater and m_tabpanel, when settings layout is in slNew mode
|
||||||
|
// // Otherwise, MainFrame will be maximized by height
|
||||||
|
// if (m_layout == ESettingsLayout::New) {
|
||||||
|
// wxSize size = wxGetApp().get_min_size();
|
||||||
|
// size.SetHeight(int(0.5 * size.GetHeight()));
|
||||||
|
// m_plater->SetMinSize(size);
|
||||||
|
// m_tabpanel->SetMinSize(size);
|
||||||
|
// }
|
||||||
|
//#endif
|
||||||
|
|
||||||
|
Layout();
|
||||||
|
Thaw();
|
||||||
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// Called when closing the application and when switching the application language.
|
// Called when closing the application and when switching the application language.
|
||||||
void MainFrame::shutdown()
|
void MainFrame::shutdown()
|
||||||
{
|
{
|
||||||
|
@ -279,6 +445,11 @@ void MainFrame::shutdown()
|
||||||
// In addition, there were some crashes due to the Paint events sent to already destructed windows.
|
// In addition, there were some crashes due to the Paint events sent to already destructed windows.
|
||||||
this->Show(false);
|
this->Show(false);
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_settings_dialog.IsShown())
|
||||||
|
// call Close() to trigger call to lambda defined into GUI_App::persist_window_geometry()
|
||||||
|
m_settings_dialog.Close();
|
||||||
|
#else
|
||||||
if (m_settings_dialog != nullptr)
|
if (m_settings_dialog != nullptr)
|
||||||
{
|
{
|
||||||
if (m_settings_dialog->IsShown())
|
if (m_settings_dialog->IsShown())
|
||||||
|
@ -287,6 +458,7 @@ void MainFrame::shutdown()
|
||||||
|
|
||||||
m_settings_dialog->Destroy();
|
m_settings_dialog->Destroy();
|
||||||
}
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
if (m_plater != nullptr) {
|
if (m_plater != nullptr) {
|
||||||
// restore sidebar if it was hidden when switching to gcode viewer mode
|
// restore sidebar if it was hidden when switching to gcode viewer mode
|
||||||
|
@ -350,6 +522,16 @@ void MainFrame::update_title()
|
||||||
|
|
||||||
void MainFrame::init_tabpanel()
|
void MainFrame::init_tabpanel()
|
||||||
{
|
{
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
// wxNB_NOPAGETHEME: Disable Windows Vista theme for the Notebook background. The theme performance is terrible on Windows 10
|
||||||
|
// with multiple high resolution displays connected.
|
||||||
|
m_tabpanel = new wxNotebook(this, wxID_ANY, wxDefaultPosition, wxDefaultSize, wxNB_TOP | wxTAB_TRAVERSAL | wxNB_NOPAGETHEME);
|
||||||
|
#ifndef __WXOSX__ // Don't call SetFont under OSX to avoid name cutting in ObjectList
|
||||||
|
m_tabpanel->SetFont(Slic3r::GUI::wxGetApp().normal_font());
|
||||||
|
#endif
|
||||||
|
m_tabpanel->Hide();
|
||||||
|
m_settings_dialog.set_tabpanel(m_tabpanel);
|
||||||
|
#else
|
||||||
m_layout = wxGetApp().app_config->get("old_settings_layout_mode") == "1" ? slOld :
|
m_layout = wxGetApp().app_config->get("old_settings_layout_mode") == "1" ? slOld :
|
||||||
wxGetApp().app_config->get("new_settings_layout_mode") == "1" ? slNew :
|
wxGetApp().app_config->get("new_settings_layout_mode") == "1" ? slNew :
|
||||||
wxGetApp().app_config->get("dlg_settings_layout_mode") == "1" ? slDlg : slOld;
|
wxGetApp().app_config->get("dlg_settings_layout_mode") == "1" ? slDlg : slOld;
|
||||||
|
@ -369,13 +551,14 @@ void MainFrame::init_tabpanel()
|
||||||
m_tabpanel->SetFont(Slic3r::GUI::wxGetApp().normal_font());
|
m_tabpanel->SetFont(Slic3r::GUI::wxGetApp().normal_font());
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
m_tabpanel->Bind(wxEVT_NOTEBOOK_PAGE_CHANGED, [this](wxEvent&) {
|
m_tabpanel->Bind(wxEVT_NOTEBOOK_PAGE_CHANGED, [this](wxEvent&) {
|
||||||
wxWindow* panel = m_tabpanel->GetCurrentPage();
|
wxWindow* panel = m_tabpanel->GetCurrentPage();
|
||||||
Tab* tab = dynamic_cast<Tab*>(panel);
|
Tab* tab = dynamic_cast<Tab*>(panel);
|
||||||
|
|
||||||
// There shouldn't be a case, when we try to select a tab, which doesn't support a printer technology
|
// There shouldn't be a case, when we try to select a tab, which doesn't support a printer technology
|
||||||
if (panel == nullptr || (tab && ! tab->supports_printer_technology(m_plater->printer_technology())))
|
if (panel == nullptr || (tab != nullptr && !tab->supports_printer_technology(m_plater->printer_technology())))
|
||||||
return;
|
return;
|
||||||
|
|
||||||
auto& tabs_list = wxGetApp().tabs_list;
|
auto& tabs_list = wxGetApp().tabs_list;
|
||||||
|
@ -389,6 +572,10 @@ void MainFrame::init_tabpanel()
|
||||||
select_tab(0); // select Plater
|
select_tab(0); // select Plater
|
||||||
});
|
});
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
m_plater = new Plater(this, this);
|
||||||
|
m_plater->Hide();
|
||||||
|
#else
|
||||||
if (m_layout == slOld) {
|
if (m_layout == slOld) {
|
||||||
m_plater = new Plater(m_tabpanel, this);
|
m_plater = new Plater(m_tabpanel, this);
|
||||||
m_tabpanel->AddPage(m_plater, _L("Plater"));
|
m_tabpanel->AddPage(m_plater, _L("Plater"));
|
||||||
|
@ -398,6 +585,7 @@ void MainFrame::init_tabpanel()
|
||||||
if (m_layout == slNew)
|
if (m_layout == slNew)
|
||||||
m_tabpanel->AddPage(new wxPanel(m_tabpanel), _L("Plater")); // empty panel just for Plater tab
|
m_tabpanel->AddPage(new wxPanel(m_tabpanel), _L("Plater")); // empty panel just for Plater tab
|
||||||
}
|
}
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
wxGetApp().plater_ = m_plater;
|
wxGetApp().plater_ = m_plater;
|
||||||
|
|
||||||
wxGetApp().obj_list()->create_popup_menus();
|
wxGetApp().obj_list()->create_popup_menus();
|
||||||
|
@ -539,6 +727,18 @@ bool MainFrame::can_slice() const
|
||||||
|
|
||||||
bool MainFrame::can_change_view() const
|
bool MainFrame::can_change_view() const
|
||||||
{
|
{
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
switch (m_layout)
|
||||||
|
{
|
||||||
|
default: { return false; }
|
||||||
|
case ESettingsLayout::New: { return m_plater->IsShown(); }
|
||||||
|
case ESettingsLayout::Dlg: { return true; }
|
||||||
|
case ESettingsLayout::Old: {
|
||||||
|
int page_id = m_tabpanel->GetSelection();
|
||||||
|
return page_id != wxNOT_FOUND && dynamic_cast<const Slic3r::GUI::Plater*>(m_tabpanel->GetPage((size_t)page_id)) != nullptr;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#else
|
||||||
if (m_layout == slNew)
|
if (m_layout == slNew)
|
||||||
return m_plater->IsShown();
|
return m_plater->IsShown();
|
||||||
if (m_layout == slDlg)
|
if (m_layout == slDlg)
|
||||||
|
@ -546,6 +746,7 @@ bool MainFrame::can_change_view() const
|
||||||
// slOld layout mode
|
// slOld layout mode
|
||||||
int page_id = m_tabpanel->GetSelection();
|
int page_id = m_tabpanel->GetSelection();
|
||||||
return page_id != wxNOT_FOUND && dynamic_cast<const Slic3r::GUI::Plater*>(m_tabpanel->GetPage((size_t)page_id)) != nullptr;
|
return page_id != wxNOT_FOUND && dynamic_cast<const Slic3r::GUI::Plater*>(m_tabpanel->GetPage((size_t)page_id)) != nullptr;
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
}
|
}
|
||||||
|
|
||||||
bool MainFrame::can_select() const
|
bool MainFrame::can_select() const
|
||||||
|
@ -573,9 +774,13 @@ bool MainFrame::can_reslice() const
|
||||||
return (m_plater != nullptr) && !m_plater->model().objects.empty();
|
return (m_plater != nullptr) && !m_plater->model().objects.empty();
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainFrame::on_dpi_changed(const wxRect &suggested_rect)
|
void MainFrame::on_dpi_changed(const wxRect& suggested_rect)
|
||||||
{
|
{
|
||||||
|
#if ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
|
wxGetApp().update_fonts(this);
|
||||||
|
#else
|
||||||
wxGetApp().update_fonts();
|
wxGetApp().update_fonts();
|
||||||
|
#endif // ENABLE_WX_3_1_3_DPI_CHANGED_EVENT
|
||||||
this->SetFont(this->normal_font());
|
this->SetFont(this->normal_font());
|
||||||
|
|
||||||
/* Load default preset bitmaps before a tabpanel initialization,
|
/* Load default preset bitmaps before a tabpanel initialization,
|
||||||
|
@ -587,7 +792,11 @@ void MainFrame::on_dpi_changed(const wxRect &suggested_rect)
|
||||||
wxGetApp().plater()->msw_rescale();
|
wxGetApp().plater()->msw_rescale();
|
||||||
|
|
||||||
// update Tabs
|
// update Tabs
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_layout != ESettingsLayout::Dlg) // Do not update tabs if the Settings are in the separated dialog
|
||||||
|
#else
|
||||||
if (m_layout != slDlg) // Update tabs later, from the SettingsDialog, when the Settings are in the separated dialog
|
if (m_layout != slDlg) // Update tabs later, from the SettingsDialog, when the Settings are in the separated dialog
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
for (auto tab : wxGetApp().tabs_list)
|
for (auto tab : wxGetApp().tabs_list)
|
||||||
tab->msw_rescale();
|
tab->msw_rescale();
|
||||||
|
|
||||||
|
@ -615,6 +824,11 @@ void MainFrame::on_dpi_changed(const wxRect &suggested_rect)
|
||||||
this->SetSize(sz);
|
this->SetSize(sz);
|
||||||
|
|
||||||
this->Maximize(is_maximized);
|
this->Maximize(is_maximized);
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_layout == ESettingsLayout::Dlg)
|
||||||
|
rescale_dialog_after_dpi_change(*this, m_settings_dialog, ERescaleTarget::SettingsDialog);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
}
|
}
|
||||||
|
|
||||||
void MainFrame::on_sys_color_changed()
|
void MainFrame::on_sys_color_changed()
|
||||||
|
@ -1580,15 +1794,41 @@ void MainFrame::load_config(const DynamicPrintConfig& config)
|
||||||
|
|
||||||
void MainFrame::select_tab(size_t tab/* = size_t(-1)*/)
|
void MainFrame::select_tab(size_t tab/* = size_t(-1)*/)
|
||||||
{
|
{
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_layout == ESettingsLayout::Dlg) {
|
||||||
|
#else
|
||||||
if (m_layout == slDlg) {
|
if (m_layout == slDlg) {
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
if (tab==0) {
|
if (tab==0) {
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
if (m_settings_dialog.IsShown())
|
||||||
|
this->SetFocus();
|
||||||
|
#else
|
||||||
if (m_settings_dialog->IsShown())
|
if (m_settings_dialog->IsShown())
|
||||||
this->SetFocus();
|
this->SetFocus();
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
// plater should be focused for correct navigation inside search window
|
// plater should be focused for correct navigation inside search window
|
||||||
if (m_plater->canvas3D()->is_search_pressed())
|
if (m_plater->canvas3D()->is_search_pressed())
|
||||||
m_plater->SetFocus();
|
m_plater->SetFocus();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
// Show/Activate Settings Dialog
|
||||||
|
#ifdef __WXOSX__ // Don't call SetFont under OSX to avoid name cutting in ObjectList
|
||||||
|
if (m_settings_dialog.IsShown())
|
||||||
|
m_settings_dialog.Hide();
|
||||||
|
|
||||||
|
m_tabpanel->Show();
|
||||||
|
m_settings_dialog.Show();
|
||||||
|
#else
|
||||||
|
if (m_settings_dialog.IsShown())
|
||||||
|
m_settings_dialog.SetFocus();
|
||||||
|
else {
|
||||||
|
m_tabpanel->Show();
|
||||||
|
m_settings_dialog.Show();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
// Show/Activate Settings Dialog
|
// Show/Activate Settings Dialog
|
||||||
if (m_settings_dialog->IsShown())
|
if (m_settings_dialog->IsShown())
|
||||||
#ifdef __WXOSX__ // Don't call SetFont under OSX to avoid name cutting in ObjectList
|
#ifdef __WXOSX__ // Don't call SetFont under OSX to avoid name cutting in ObjectList
|
||||||
|
@ -1598,10 +1838,20 @@ void MainFrame::select_tab(size_t tab/* = size_t(-1)*/)
|
||||||
else
|
else
|
||||||
#endif
|
#endif
|
||||||
m_settings_dialog->Show();
|
m_settings_dialog->Show();
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
}
|
}
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
else if (m_layout == ESettingsLayout::New) {
|
||||||
|
#else
|
||||||
else if (m_layout == slNew) {
|
else if (m_layout == slNew) {
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
GetSizer()->Show(m_plater, tab == 0);
|
||||||
|
GetSizer()->Show(m_tabpanel, tab != 0);
|
||||||
|
#else
|
||||||
m_plater->Show(tab == 0);
|
m_plater->Show(tab == 0);
|
||||||
m_tabpanel->Show(tab != 0);
|
m_tabpanel->Show(tab != 0);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// plater should be focused for correct navigation inside search window
|
// plater should be focused for correct navigation inside search window
|
||||||
if (tab == 0 && m_plater->canvas3D()->is_search_pressed())
|
if (tab == 0 && m_plater->canvas3D()->is_search_pressed())
|
||||||
|
@ -1609,8 +1859,12 @@ void MainFrame::select_tab(size_t tab/* = size_t(-1)*/)
|
||||||
Layout();
|
Layout();
|
||||||
}
|
}
|
||||||
|
|
||||||
// when tab == -1, it means we should to show the last selected tab
|
// when tab == -1, it means we should show the last selected tab
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
m_tabpanel->SetSelection(tab == (size_t)(-1) ? m_last_selected_tab : (m_layout == ESettingsLayout::Dlg && tab != 0) ? tab - 1 : tab);
|
||||||
|
#else
|
||||||
m_tabpanel->SetSelection(tab == (size_t)(-1) ? m_last_selected_tab : (m_layout == slDlg && tab != 0) ? tab-1 : tab);
|
m_tabpanel->SetSelection(tab == (size_t)(-1) ? m_last_selected_tab : (m_layout == slDlg && tab != 0) ? tab-1 : tab);
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set a camera direction, zoom to all objects.
|
// Set a camera direction, zoom to all objects.
|
||||||
|
@ -1721,14 +1975,12 @@ std::string MainFrame::get_dir_name(const wxString &full_name) const
|
||||||
// ----------------------------------------------------------------------------
|
// ----------------------------------------------------------------------------
|
||||||
|
|
||||||
SettingsDialog::SettingsDialog(MainFrame* mainframe)
|
SettingsDialog::SettingsDialog(MainFrame* mainframe)
|
||||||
: DPIDialog(nullptr, wxID_ANY, wxString(SLIC3R_APP_NAME) + " - " + _L("Settings"), wxDefaultPosition, wxDefaultSize,
|
: DPIDialog(mainframe, wxID_ANY, wxString(SLIC3R_APP_NAME) + " - " + _L("Settings"), wxDefaultPosition, wxDefaultSize,
|
||||||
wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER | wxMINIMIZE_BOX | wxMAXIMIZE_BOX | wxDIALOG_NO_PARENT, "settings_dialog"),
|
wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER | wxMINIMIZE_BOX | wxMAXIMIZE_BOX, "settings_dialog"),
|
||||||
m_main_frame(mainframe)
|
m_main_frame(mainframe)
|
||||||
{
|
{
|
||||||
this->SetFont(wxGetApp().normal_font());
|
this->SetFont(wxGetApp().normal_font());
|
||||||
|
this->SetBackgroundColour(wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW));
|
||||||
wxColour bgr_clr = wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW);
|
|
||||||
this->SetBackgroundColour(bgr_clr);
|
|
||||||
|
|
||||||
// Load the icon either from the exe, or from the ico file.
|
// Load the icon either from the exe, or from the ico file.
|
||||||
#if _WIN32
|
#if _WIN32
|
||||||
|
@ -1741,6 +1993,7 @@ SettingsDialog::SettingsDialog(MainFrame* mainframe)
|
||||||
SetIcon(wxIcon(var("PrusaSlicer_128px.png"), wxBITMAP_TYPE_PNG));
|
SetIcon(wxIcon(var("PrusaSlicer_128px.png"), wxBITMAP_TYPE_PNG));
|
||||||
#endif // _WIN32
|
#endif // _WIN32
|
||||||
|
|
||||||
|
#if !ENABLE_LAYOUT_NO_RESTART
|
||||||
// wxNB_NOPAGETHEME: Disable Windows Vista theme for the Notebook background. The theme performance is terrible on Windows 10
|
// wxNB_NOPAGETHEME: Disable Windows Vista theme for the Notebook background. The theme performance is terrible on Windows 10
|
||||||
// with multiple high resolution displays connected.
|
// with multiple high resolution displays connected.
|
||||||
m_tabpanel = new wxNotebook(this, wxID_ANY, wxDefaultPosition, wxGetApp().get_min_size(), wxNB_TOP | wxTAB_TRAVERSAL | wxNB_NOPAGETHEME);
|
m_tabpanel = new wxNotebook(this, wxID_ANY, wxDefaultPosition, wxGetApp().get_min_size(), wxNB_TOP | wxTAB_TRAVERSAL | wxNB_NOPAGETHEME);
|
||||||
|
@ -1765,10 +2018,45 @@ SettingsDialog::SettingsDialog(MainFrame* mainframe)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
});
|
});
|
||||||
|
#endif // !ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
this->Bind(wxEVT_SHOW, [this](wxShowEvent& evt) {
|
||||||
|
|
||||||
|
auto key_up_handker = [this](wxKeyEvent& evt) {
|
||||||
|
if ((evt.GetModifiers() & wxMOD_CONTROL) != 0) {
|
||||||
|
switch (evt.GetKeyCode()) {
|
||||||
|
case '1': { m_main_frame->select_tab(0); break; }
|
||||||
|
case '2': { m_main_frame->select_tab(1); break; }
|
||||||
|
case '3': { m_main_frame->select_tab(2); break; }
|
||||||
|
case '4': { m_main_frame->select_tab(3); break; }
|
||||||
|
#ifdef __APPLE__
|
||||||
|
case 'f':
|
||||||
|
#else /* __APPLE__ */
|
||||||
|
case WXK_CONTROL_F:
|
||||||
|
#endif /* __APPLE__ */
|
||||||
|
case 'F': { m_main_frame->plater()->search(false); break; }
|
||||||
|
default:break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
if (evt.IsShown()) {
|
||||||
|
if (m_tabpanel != nullptr)
|
||||||
|
m_tabpanel->Bind(wxEVT_KEY_UP, key_up_handker);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (m_tabpanel != nullptr)
|
||||||
|
m_tabpanel->Unbind(wxEVT_KEY_UP, key_up_handker);
|
||||||
|
}
|
||||||
|
});
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// initialize layout
|
// initialize layout
|
||||||
auto sizer = new wxBoxSizer(wxVERTICAL);
|
auto sizer = new wxBoxSizer(wxVERTICAL);
|
||||||
|
#if !ENABLE_LAYOUT_NO_RESTART
|
||||||
sizer->Add(m_tabpanel, 1, wxEXPAND);
|
sizer->Add(m_tabpanel, 1, wxEXPAND);
|
||||||
|
#endif // !ENABLE_LAYOUT_NO_RESTART
|
||||||
sizer->SetSizeHints(this);
|
sizer->SetSizeHints(this);
|
||||||
SetSizer(sizer);
|
SetSizer(sizer);
|
||||||
Fit();
|
Fit();
|
||||||
|
|
|
@ -51,11 +51,15 @@ struct PresetTab {
|
||||||
class SettingsDialog : public DPIDialog
|
class SettingsDialog : public DPIDialog
|
||||||
{
|
{
|
||||||
wxNotebook* m_tabpanel { nullptr };
|
wxNotebook* m_tabpanel { nullptr };
|
||||||
MainFrame* m_main_frame {nullptr };
|
MainFrame* m_main_frame { nullptr };
|
||||||
public:
|
public:
|
||||||
SettingsDialog(MainFrame* mainframe);
|
SettingsDialog(MainFrame* mainframe);
|
||||||
~SettingsDialog() {}
|
~SettingsDialog() {}
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
void set_tabpanel(wxNotebook* tabpanel) { m_tabpanel = tabpanel; }
|
||||||
|
#else
|
||||||
wxNotebook* get_tabpanel() { return m_tabpanel; }
|
wxNotebook* get_tabpanel() { return m_tabpanel; }
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void on_dpi_changed(const wxRect& suggested_rect) override;
|
void on_dpi_changed(const wxRect& suggested_rect) override;
|
||||||
|
@ -127,11 +131,23 @@ class MainFrame : public DPIFrame
|
||||||
|
|
||||||
wxFileHistory m_recent_projects;
|
wxFileHistory m_recent_projects;
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
enum class ESettingsLayout
|
||||||
|
{
|
||||||
|
Unknown,
|
||||||
|
Old,
|
||||||
|
New,
|
||||||
|
Dlg,
|
||||||
|
};
|
||||||
|
|
||||||
|
ESettingsLayout m_layout{ ESettingsLayout::Unknown };
|
||||||
|
#else
|
||||||
enum SettingsLayout {
|
enum SettingsLayout {
|
||||||
slOld = 0,
|
slOld = 0,
|
||||||
slNew,
|
slNew,
|
||||||
slDlg,
|
slDlg,
|
||||||
} m_layout;
|
} m_layout;
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
#if ENABLE_GCODE_VIEWER_AS_STATE
|
#if ENABLE_GCODE_VIEWER_AS_STATE
|
||||||
public:
|
public:
|
||||||
|
@ -153,6 +169,10 @@ public:
|
||||||
MainFrame();
|
MainFrame();
|
||||||
~MainFrame() = default;
|
~MainFrame() = default;
|
||||||
|
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
void update_layout();
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
// Called when closing the application and when switching the application language.
|
// Called when closing the application and when switching the application language.
|
||||||
void shutdown();
|
void shutdown();
|
||||||
|
|
||||||
|
@ -203,7 +223,12 @@ public:
|
||||||
|
|
||||||
Plater* m_plater { nullptr };
|
Plater* m_plater { nullptr };
|
||||||
wxNotebook* m_tabpanel { nullptr };
|
wxNotebook* m_tabpanel { nullptr };
|
||||||
|
#if ENABLE_LAYOUT_NO_RESTART
|
||||||
|
SettingsDialog m_settings_dialog;
|
||||||
|
wxWindow* m_plater_page{ nullptr };
|
||||||
|
#else
|
||||||
SettingsDialog* m_settings_dialog { nullptr };
|
SettingsDialog* m_settings_dialog { nullptr };
|
||||||
|
#endif // ENABLE_LAYOUT_NO_RESTART
|
||||||
wxProgressDialog* m_progress_dialog { nullptr };
|
wxProgressDialog* m_progress_dialog { nullptr };
|
||||||
std::shared_ptr<ProgressStatusBar> m_statusbar;
|
std::shared_ptr<ProgressStatusBar> m_statusbar;
|
||||||
|
|
||||||
|
|
|
@ -234,6 +234,7 @@ void PreferencesDialog::accept()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if !ENABLE_LAYOUT_NO_RESTART
|
||||||
if (m_settings_layout_changed) {
|
if (m_settings_layout_changed) {
|
||||||
// the dialog needs to be destroyed before the call to recreate_gui()
|
// the dialog needs to be destroyed before the call to recreate_gui()
|
||||||
// or sometimes the application crashes into wxDialogBase() destructor
|
// or sometimes the application crashes into wxDialogBase() destructor
|
||||||
|
@ -255,6 +256,7 @@ void PreferencesDialog::accept()
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // !ENABLE_LAYOUT_NO_RESTART
|
||||||
|
|
||||||
for (std::map<std::string, std::string>::iterator it = m_values.begin(); it != m_values.end(); ++it)
|
for (std::map<std::string, std::string>::iterator it = m_values.begin(); it != m_values.end(); ++it)
|
||||||
app_config->set(it->first, it->second);
|
app_config->set(it->first, it->second);
|
||||||
|
|
|
@ -8,6 +8,8 @@
|
||||||
|
|
||||||
#include <libslic3r/VoronoiOffset.hpp>
|
#include <libslic3r/VoronoiOffset.hpp>
|
||||||
|
|
||||||
|
#include <numeric>
|
||||||
|
|
||||||
// #define VORONOI_DEBUG_OUT
|
// #define VORONOI_DEBUG_OUT
|
||||||
|
|
||||||
#ifdef VORONOI_DEBUG_OUT
|
#ifdef VORONOI_DEBUG_OUT
|
||||||
|
@ -1198,6 +1200,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 +1218,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);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -13,7 +13,7 @@ Pointfs arrange(size_t total_parts, Vec2d* part, coordf_t dist, BoundingBoxf* bb
|
||||||
%code{%
|
%code{%
|
||||||
Pointfs points;
|
Pointfs points;
|
||||||
if (! Slic3r::Geometry::arrange(total_parts, *part, dist, bb, points))
|
if (! Slic3r::Geometry::arrange(total_parts, *part, dist, bb, points))
|
||||||
CONFESS(PRINTF_ZU " parts won't fit in your print area!\n", total_parts);
|
CONFESS("%zu parts won't fit in your print area!\n", total_parts);
|
||||||
RETVAL = points;
|
RETVAL = points;
|
||||||
%};
|
%};
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue