mirror of
https://git.mirrors.martin98.com/https://github.com/prusa3d/PrusaSlicer.git
synced 2025-08-12 22:49:04 +08:00
WIP Reworking of "ensure vertical wall thickness".
1) Flipped the order of "discover_vertical_shells" and "process_external_surfaces", now the external surfaces are expanded after "discover_vertical_shells" aka "ensure vertical wall thickness" is solved. 2) Reworked LayerRegion::process_external_surfaces() to only expand into "ensure vertical wall thickness" regions, also the expansion is done in small steps to avoid overflowing into neighbor regions. also: Utility functions reserve_more(), reserve_power_of_2(), reserve_more_power_of_2() Various SurfaceCollecion::filter_xxx() modified to accept an initializer list of surface types. New bridges detector refactored to accept overhang boundaries. BoundingBoxWrapper was moved from RetractCrossingPerimeters to AABBTreeIndirect.
This commit is contained in:
parent
fb85baf889
commit
fde0d68c40
@ -13,6 +13,7 @@
|
|||||||
|
|
||||||
#include <Eigen/Geometry>
|
#include <Eigen/Geometry>
|
||||||
|
|
||||||
|
#include "BoundingBox.hpp"
|
||||||
#include "Utils.hpp" // for next_highest_power_of_2()
|
#include "Utils.hpp" // for next_highest_power_of_2()
|
||||||
|
|
||||||
// Definition of the ray intersection hit structure.
|
// Definition of the ray intersection hit structure.
|
||||||
@ -217,6 +218,23 @@ using Tree3f = Tree<3, float>;
|
|||||||
using Tree2d = Tree<2, double>;
|
using Tree2d = Tree<2, double>;
|
||||||
using Tree3d = Tree<3, double>;
|
using Tree3d = Tree<3, double>;
|
||||||
|
|
||||||
|
// Wrap a 2D Slic3r own BoundingBox to be passed to Tree::build() and similar
|
||||||
|
// to build an AABBTree over coord_t 2D bounding boxes.
|
||||||
|
class BoundingBoxWrapper {
|
||||||
|
public:
|
||||||
|
using BoundingBox = Eigen::AlignedBox<coord_t, 2>;
|
||||||
|
BoundingBoxWrapper(const size_t idx, const Slic3r::BoundingBox &bbox) :
|
||||||
|
m_idx(idx),
|
||||||
|
// Inflate the bounding box a bit to account for numerical issues.
|
||||||
|
m_bbox(bbox.min - Point(SCALED_EPSILON, SCALED_EPSILON), bbox.max + Point(SCALED_EPSILON, SCALED_EPSILON)) {}
|
||||||
|
size_t idx() const { return m_idx; }
|
||||||
|
const BoundingBox& bbox() const { return m_bbox; }
|
||||||
|
Point centroid() const { return ((m_bbox.min().cast<int64_t>() + m_bbox.max().cast<int64_t>()) / 2).cast<int32_t>(); }
|
||||||
|
private:
|
||||||
|
size_t m_idx;
|
||||||
|
BoundingBox m_bbox;
|
||||||
|
};
|
||||||
|
|
||||||
namespace detail {
|
namespace detail {
|
||||||
template<typename AVertexType, typename AIndexedFaceType, typename ATreeType, typename AVectorType>
|
template<typename AVertexType, typename AIndexedFaceType, typename ATreeType, typename AVectorType>
|
||||||
struct RayIntersector {
|
struct RayIntersector {
|
||||||
|
@ -1,11 +1,76 @@
|
|||||||
#include "RegionExpansion.hpp"
|
#include "RegionExpansion.hpp"
|
||||||
|
|
||||||
|
#include <libslic3r/AABBTreeIndirect.hpp>
|
||||||
#include <libslic3r/ClipperZUtils.hpp>
|
#include <libslic3r/ClipperZUtils.hpp>
|
||||||
#include <libslic3r/ClipperUtils.hpp>
|
#include <libslic3r/ClipperUtils.hpp>
|
||||||
|
#include <libslic3r/Utils.hpp>
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
namespace Algorithm {
|
namespace Algorithm {
|
||||||
|
|
||||||
|
// Calculating radius discretization according to ClipperLib offsetter code, see void ClipperOffset::DoOffset(double delta)
|
||||||
|
inline double clipper_round_offset_error(double offset, double arc_tolerance)
|
||||||
|
{
|
||||||
|
static constexpr const double def_arc_tolerance = 0.25;
|
||||||
|
const double y =
|
||||||
|
arc_tolerance <= 0 ?
|
||||||
|
def_arc_tolerance :
|
||||||
|
arc_tolerance > offset * def_arc_tolerance ?
|
||||||
|
offset * def_arc_tolerance :
|
||||||
|
arc_tolerance;
|
||||||
|
double steps = std::min(M_PI / std::acos(1. - y / offset), offset * M_PI);
|
||||||
|
return offset * (1. - cos(M_PI / steps));
|
||||||
|
}
|
||||||
|
|
||||||
|
RegionExpansionParameters RegionExpansionParameters::build(
|
||||||
|
// Scaled expansion value
|
||||||
|
float full_expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_expansion_steps)
|
||||||
|
{
|
||||||
|
assert(full_expansion > 0);
|
||||||
|
assert(expansion_step > 0);
|
||||||
|
assert(max_nr_expansion_steps > 0);
|
||||||
|
|
||||||
|
RegionExpansionParameters out;
|
||||||
|
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
||||||
|
// The expansion should not be too tiny, but also small enough, so the following expansion will
|
||||||
|
// compensate for tiny_expansion and bring the wave back to the boundary without producing
|
||||||
|
// ugly cusps where it touches the boundary.
|
||||||
|
out.tiny_expansion = std::min(0.25f * full_expansion, scaled<float>(0.05f));
|
||||||
|
size_t nsteps = size_t(ceil((full_expansion - out.tiny_expansion) / expansion_step));
|
||||||
|
if (max_nr_expansion_steps > 0)
|
||||||
|
nsteps = std::min(nsteps, max_nr_expansion_steps);
|
||||||
|
assert(nsteps > 0);
|
||||||
|
out.initial_step = (full_expansion - out.tiny_expansion) / nsteps;
|
||||||
|
if (nsteps > 1 && 0.25 * out.initial_step < out.tiny_expansion) {
|
||||||
|
// Decrease the step size by lowering number of steps.
|
||||||
|
nsteps = std::max<size_t>(1, (floor((full_expansion - out.tiny_expansion) / (4. * out.tiny_expansion))));
|
||||||
|
out.initial_step = (full_expansion - out.tiny_expansion) / nsteps;
|
||||||
|
}
|
||||||
|
if (0.25 * out.initial_step < out.tiny_expansion || nsteps == 1) {
|
||||||
|
out.tiny_expansion = 0.2f * full_expansion;
|
||||||
|
out.initial_step = 0.8f * full_expansion;
|
||||||
|
}
|
||||||
|
out.other_step = out.initial_step;
|
||||||
|
out.num_other_steps = nsteps - 1;
|
||||||
|
|
||||||
|
// Accuracy of the offsetter for wave propagation.
|
||||||
|
out.arc_tolerance = scaled<double>(0.1);
|
||||||
|
out.shortest_edge_length = out.initial_step * ClipperOffsetShortestEdgeFactor;
|
||||||
|
|
||||||
|
// Maximum inflation of seed contours over the boundary. Used to trim boundary to speed up
|
||||||
|
// clipping during wave propagation. Needs to be in sync with the offsetter accuracy.
|
||||||
|
// Clipper positive round offset should rather offset less than more.
|
||||||
|
// Still a little bit of additional offset was added.
|
||||||
|
out.max_inflation = (out.tiny_expansion + nsteps * out.initial_step) * 1.1;
|
||||||
|
// (clipper_round_offset_error(out.tiny_expansion, co.ArcTolerance) + nsteps * clipper_round_offset_error(out.initial_step, co.ArcTolerance) * 1.5; // Account for uncertainty
|
||||||
|
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
// similar to expolygons_to_zpaths(), but each contour is expanded before converted to zpath.
|
// similar to expolygons_to_zpaths(), but each contour is expanded before converted to zpath.
|
||||||
// The expanded contours are then opened (the first point is repeated at the end).
|
// The expanded contours are then opened (the first point is repeated at the end).
|
||||||
static ClipperLib_Z::Paths expolygons_to_zpaths_expanded_opened(
|
static ClipperLib_Z::Paths expolygons_to_zpaths_expanded_opened(
|
||||||
@ -48,8 +113,7 @@ static inline void merge_splits(ClipperLib_Z::Paths &paths, std::vector<std::pai
|
|||||||
const ClipperLib_Z::IntPoint &front = path.front();
|
const ClipperLib_Z::IntPoint &front = path.front();
|
||||||
const ClipperLib_Z::IntPoint &back = path.back();
|
const ClipperLib_Z::IntPoint &back = path.back();
|
||||||
// The path before clipping was supposed to cross the clipping boundary or be fully out of it.
|
// The path before clipping was supposed to cross the clipping boundary or be fully out of it.
|
||||||
// Thus the clipped contour is supposed to become open.
|
// Thus the clipped contour is supposed to become open, with one exception: The anchor expands into a closed hole.
|
||||||
assert(front.x() != back.x() || front.y() != back.y());
|
|
||||||
if (front.x() != back.x() || front.y() != back.y()) {
|
if (front.x() != back.x() || front.y() != back.y()) {
|
||||||
// Look up the ends in "splits", possibly join the contours.
|
// Look up the ends in "splits", possibly join the contours.
|
||||||
// "splits" maps into the other piece connected to the same end point.
|
// "splits" maps into the other piece connected to the same end point.
|
||||||
@ -89,14 +153,156 @@ static inline void merge_splits(ClipperLib_Z::Paths &paths, std::vector<std::pai
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::vector<WaveSeed> wave_seeds(
|
||||||
|
// Source regions that are supposed to touch the boundary.
|
||||||
|
const ExPolygons &src,
|
||||||
|
// Boundaries of source regions touching the "boundary" regions will be expanded into the "boundary" region.
|
||||||
|
const ExPolygons &boundary,
|
||||||
|
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
||||||
|
float tiny_expansion,
|
||||||
|
// Sort output by boundary ID and source ID.
|
||||||
|
bool sorted)
|
||||||
|
{
|
||||||
|
assert(tiny_expansion > 0);
|
||||||
|
|
||||||
|
if (src.empty())
|
||||||
|
return {};
|
||||||
|
|
||||||
|
using Intersection = ClipperZUtils::ClipperZIntersectionVisitor::Intersection;
|
||||||
|
using Intersections = ClipperZUtils::ClipperZIntersectionVisitor::Intersections;
|
||||||
|
|
||||||
|
ClipperLib_Z::Paths segments;
|
||||||
|
Intersections intersections;
|
||||||
|
|
||||||
|
coord_t idx_boundary_begin = 1;
|
||||||
|
coord_t idx_boundary_end;
|
||||||
|
coord_t idx_src_end;
|
||||||
|
|
||||||
|
{
|
||||||
|
ClipperLib_Z::Clipper zclipper;
|
||||||
|
ClipperZUtils::ClipperZIntersectionVisitor visitor(intersections);
|
||||||
|
zclipper.ZFillFunction(visitor.clipper_callback());
|
||||||
|
// as closed contours
|
||||||
|
{
|
||||||
|
ClipperLib_Z::Paths zboundary = ClipperZUtils::expolygons_to_zpaths(boundary, idx_boundary_begin);
|
||||||
|
idx_boundary_end = idx_boundary_begin + coord_t(zboundary.size());
|
||||||
|
zclipper.AddPaths(zboundary, ClipperLib_Z::ptClip, true);
|
||||||
|
}
|
||||||
|
// as open contours
|
||||||
|
std::vector<std::pair<ClipperLib_Z::IntPoint, int>> zsrc_splits;
|
||||||
|
{
|
||||||
|
ClipperLib_Z::Paths zsrc = expolygons_to_zpaths_expanded_opened(src, tiny_expansion, idx_boundary_end);
|
||||||
|
zclipper.AddPaths(zsrc, ClipperLib_Z::ptSubject, false);
|
||||||
|
idx_src_end = idx_boundary_end + coord_t(zsrc.size());
|
||||||
|
zsrc_splits.reserve(zsrc.size());
|
||||||
|
for (const ClipperLib_Z::Path &path : zsrc) {
|
||||||
|
assert(path.size() >= 2);
|
||||||
|
assert(path.front() == path.back());
|
||||||
|
zsrc_splits.emplace_back(path.front(), -1);
|
||||||
|
}
|
||||||
|
std::sort(zsrc_splits.begin(), zsrc_splits.end(), [](const auto &l, const auto &r){ return ClipperZUtils::zpoint_lower(l.first, r.first); });
|
||||||
|
}
|
||||||
|
ClipperLib_Z::PolyTree polytree;
|
||||||
|
zclipper.Execute(ClipperLib_Z::ctIntersection, polytree, ClipperLib_Z::pftNonZero, ClipperLib_Z::pftNonZero);
|
||||||
|
ClipperLib_Z::PolyTreeToPaths(std::move(polytree), segments);
|
||||||
|
merge_splits(segments, zsrc_splits);
|
||||||
|
}
|
||||||
|
|
||||||
|
// AABBTree over bounding boxes of boundaries.
|
||||||
|
// Only built if necessary, that is if any of the seed contours is closed, thus there is no intersection point
|
||||||
|
// with the boundary and all Z coordinates of the closed contour point to the source contour.
|
||||||
|
using AABBTree = AABBTreeIndirect::Tree<2, coord_t>;
|
||||||
|
AABBTree aabb_tree;
|
||||||
|
auto init_aabb_tree = [&aabb_tree, &boundary]() {
|
||||||
|
if (aabb_tree.empty()) {
|
||||||
|
// Calculate bounding boxes of internal slices.
|
||||||
|
std::vector<AABBTreeIndirect::BoundingBoxWrapper> bboxes;
|
||||||
|
bboxes.reserve(boundary.size());
|
||||||
|
for (size_t i = 0; i < boundary.size(); ++ i)
|
||||||
|
bboxes.emplace_back(i, get_extents(boundary[i].contour));
|
||||||
|
// Build AABB tree over bounding boxes of boundary expolygons.
|
||||||
|
aabb_tree.build_modify_input(bboxes);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// Sort paths into their respective islands.
|
||||||
|
// Each src x boundary will be processed (wave expanded) independently.
|
||||||
|
// Multiple pieces of a single src may intersect the same boundary.
|
||||||
|
WaveSeeds out;
|
||||||
|
out.reserve(segments.size());
|
||||||
|
int iseed = 0;
|
||||||
|
for (const ClipperLib_Z::Path &path : segments) {
|
||||||
|
assert(path.size() >= 2);
|
||||||
|
const ClipperLib_Z::IntPoint &front = path.front();
|
||||||
|
const ClipperLib_Z::IntPoint &back = path.back();
|
||||||
|
// Both ends of a seed segment are supposed to be inside a single boundary expolygon.
|
||||||
|
// Thus as long as the seed contour is not closed, it should be open at a boundary point.
|
||||||
|
assert((front == back && front.z() >= idx_boundary_end && front.z() < idx_src_end) || (front.z() < 0 && back.z() < 0));
|
||||||
|
const Intersection *intersection = nullptr;
|
||||||
|
auto intersection_point_valid = [idx_boundary_end, idx_src_end](const Intersection &is) {
|
||||||
|
return is.first >= 1 && is.first < idx_boundary_end &&
|
||||||
|
is.second >= idx_boundary_end && is.second < idx_src_end;
|
||||||
|
};
|
||||||
|
if (front.z() < 0) {
|
||||||
|
const Intersection &is = intersections[- front.z() - 1];
|
||||||
|
assert(intersection_point_valid(is));
|
||||||
|
if (intersection_point_valid(is))
|
||||||
|
intersection = &is;
|
||||||
|
}
|
||||||
|
if (! intersection && back.z() < 0) {
|
||||||
|
const Intersection &is = intersections[- back.z() - 1];
|
||||||
|
assert(intersection_point_valid(is));
|
||||||
|
if (intersection_point_valid(is))
|
||||||
|
intersection = &is;
|
||||||
|
}
|
||||||
|
if (intersection) {
|
||||||
|
// The path intersects the boundary contour at least at one side.
|
||||||
|
out.push_back({ uint32_t(intersection->second - idx_boundary_end), uint32_t(intersection->first - 1), ClipperZUtils::from_zpath(path) });
|
||||||
|
} else {
|
||||||
|
// This should be a closed contour.
|
||||||
|
assert(front == back && front.z() >= idx_boundary_end && front.z() < idx_src_end);
|
||||||
|
// Find a source boundary expolygon of one sample of this closed path.
|
||||||
|
init_aabb_tree();
|
||||||
|
Point sample(front.x(), front.y());
|
||||||
|
int boundary_id = -1;
|
||||||
|
AABBTreeIndirect::traverse(aabb_tree,
|
||||||
|
[&sample](const AABBTree::Node &node) {
|
||||||
|
return node.bbox.contains(sample);
|
||||||
|
},
|
||||||
|
[&boundary, &sample, &boundary_id](const AABBTree::Node &node) {
|
||||||
|
assert(node.is_leaf());
|
||||||
|
assert(node.is_valid());
|
||||||
|
if (boundary[node.idx].contains(sample)) {
|
||||||
|
boundary_id = int(node.idx);
|
||||||
|
// Stop traversal.
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
// Continue traversal.
|
||||||
|
return true;
|
||||||
|
});
|
||||||
|
// Boundary that contains the sample point was found.
|
||||||
|
assert(boundary_id >= 0);
|
||||||
|
if (boundary_id >= 0)
|
||||||
|
out.push_back({ uint32_t(front.z() - idx_boundary_end), uint32_t(boundary_id), ClipperZUtils::from_zpath(path) });
|
||||||
|
}
|
||||||
|
++ iseed;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (sorted)
|
||||||
|
// Sort the seeds by their intersection boundary and source contour.
|
||||||
|
std::sort(out.begin(), out.end(), lower_by_boundary_and_src);
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
static ClipperLib::Paths wavefront_initial(ClipperLib::ClipperOffset &co, const ClipperLib::Paths &polylines, float offset)
|
static ClipperLib::Paths wavefront_initial(ClipperLib::ClipperOffset &co, const ClipperLib::Paths &polylines, float offset)
|
||||||
{
|
{
|
||||||
ClipperLib::Paths out;
|
ClipperLib::Paths out;
|
||||||
out.reserve(polylines.size());
|
out.reserve(polylines.size());
|
||||||
ClipperLib::Paths out_this;
|
ClipperLib::Paths out_this;
|
||||||
for (const ClipperLib::Path &path : polylines) {
|
for (const ClipperLib::Path &path : polylines) {
|
||||||
|
assert(path.size() >= 2);
|
||||||
co.Clear();
|
co.Clear();
|
||||||
co.AddPath(path, jtRound, ClipperLib::etOpenRound);
|
co.AddPath(path, jtRound, path.front() == path.back() ? ClipperLib::etClosedLine : ClipperLib::etOpenRound);
|
||||||
co.Execute(out_this, offset);
|
co.Execute(out_this, offset);
|
||||||
append(out, std::move(out_this));
|
append(out, std::move(out_this));
|
||||||
}
|
}
|
||||||
@ -164,22 +370,73 @@ static Polygons propagate_wave_from_boundary(
|
|||||||
return to_polygons(polygons);
|
return to_polygons(polygons);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Calculating radius discretization according to ClipperLib offsetter code, see void ClipperOffset::DoOffset(double delta)
|
// Resulting regions are sorted by boundary id and source id.
|
||||||
inline double clipper_round_offset_error(double offset, double arc_tolerance)
|
std::vector<RegionExpansion> propagate_waves(const WaveSeeds &seeds, const ExPolygons &boundary, const RegionExpansionParameters ¶ms)
|
||||||
{
|
{
|
||||||
static constexpr const double def_arc_tolerance = 0.25;
|
std::vector<RegionExpansion> out;
|
||||||
const double y =
|
ClipperLib::Paths paths;
|
||||||
arc_tolerance <= 0 ?
|
ClipperLib::ClipperOffset co;
|
||||||
def_arc_tolerance :
|
co.ArcTolerance = params.arc_tolerance;
|
||||||
arc_tolerance > offset * def_arc_tolerance ?
|
co.ShortestEdgeLength = params.shortest_edge_length;
|
||||||
offset * def_arc_tolerance :
|
for (auto it_seed = seeds.begin(); it_seed != seeds.end();) {
|
||||||
arc_tolerance;
|
auto it = it_seed;
|
||||||
double steps = std::min(M_PI / std::acos(1. - y / offset), offset * M_PI);
|
paths.clear();
|
||||||
return offset * (1. - cos(M_PI / steps));
|
for (; it != seeds.end() && it->boundary == it_seed->boundary && it->src == it_seed->src; ++ it)
|
||||||
|
paths.emplace_back(it->path);
|
||||||
|
// Propagate the wavefront while clipping it with the trimmed boundary.
|
||||||
|
// Collect the expanded polygons, merge them with the source polygons.
|
||||||
|
RegionExpansion re;
|
||||||
|
for (Polygon &polygon : propagate_wave_from_boundary(co, paths, boundary[it_seed->boundary], params.initial_step, params.other_step, params.num_other_steps, params.max_inflation))
|
||||||
|
out.push_back({ std::move(polygon), it_seed->src, it_seed->boundary });
|
||||||
|
it_seed = it;
|
||||||
|
}
|
||||||
|
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<RegionExpansion> propagate_waves(const ExPolygons &src, const ExPolygons &boundary, const RegionExpansionParameters ¶ms)
|
||||||
|
{
|
||||||
|
return propagate_waves(wave_seeds(src, boundary, params.tiny_expansion, true), boundary, params);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<RegionExpansion> propagate_waves(const ExPolygons &src, const ExPolygons &boundary,
|
||||||
|
// Scaled expansion value
|
||||||
|
float expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_steps)
|
||||||
|
{
|
||||||
|
return propagate_waves(src, boundary, RegionExpansionParameters::build(expansion, expansion_step, max_nr_steps));
|
||||||
}
|
}
|
||||||
|
|
||||||
// Returns regions per source ExPolygon expanded into boundary.
|
// Returns regions per source ExPolygon expanded into boundary.
|
||||||
std::vector<Polygons> expand_expolygons(
|
std::vector<RegionExpansionEx> propagate_waves_ex(const WaveSeeds &seeds, const ExPolygons &boundary, const RegionExpansionParameters ¶ms)
|
||||||
|
{
|
||||||
|
std::vector<RegionExpansion> expanded = propagate_waves(seeds, boundary, params);
|
||||||
|
assert(std::is_sorted(seeds.begin(), seeds.end(), [](const auto &l, const auto &r){ return l.boundary < r.boundary || (l.boundary == r.boundary && l.src < r.src); }));
|
||||||
|
Polygons acc;
|
||||||
|
std::vector<RegionExpansionEx> out;
|
||||||
|
for (auto it = expanded.begin(); it != expanded.end(); ) {
|
||||||
|
auto it2 = it;
|
||||||
|
acc.clear();
|
||||||
|
for (; it2 != expanded.end() && it2->boundary_id == it->boundary_id && it2->src_id == it->src_id; ++ it2)
|
||||||
|
acc.emplace_back(std::move(it2->polygon));
|
||||||
|
size_t size = it2 - it;
|
||||||
|
if (size == 1)
|
||||||
|
out.push_back({ ExPolygon{std::move(acc.front())}, it->src_id, it->boundary_id });
|
||||||
|
else {
|
||||||
|
ExPolygons expolys = union_ex(acc);
|
||||||
|
reserve_more_power_of_2(out, expolys.size());
|
||||||
|
for (ExPolygon &ex : expolys)
|
||||||
|
out.push_back({ std::move(ex), it->src_id, it->boundary_id });
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Returns regions per source ExPolygon expanded into boundary.
|
||||||
|
std::vector<RegionExpansionEx> propagate_waves_ex(
|
||||||
// Source regions that are supposed to touch the boundary.
|
// Source regions that are supposed to touch the boundary.
|
||||||
// Boundaries of source regions touching the "boundary" regions will be expanded into the "boundary" region.
|
// Boundaries of source regions touching the "boundary" regions will be expanded into the "boundary" region.
|
||||||
const ExPolygons &src,
|
const ExPolygons &src,
|
||||||
@ -191,159 +448,53 @@ std::vector<Polygons> expand_expolygons(
|
|||||||
// Don't take more than max_nr_steps for small expansion_step.
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
size_t max_nr_expansion_steps)
|
size_t max_nr_expansion_steps)
|
||||||
{
|
{
|
||||||
assert(full_expansion > 0);
|
auto params = RegionExpansionParameters::build(full_expansion, expansion_step, max_nr_expansion_steps);
|
||||||
assert(expansion_step > 0);
|
return propagate_waves_ex(wave_seeds(src, boundary, params.tiny_expansion, true), boundary, params);
|
||||||
assert(max_nr_expansion_steps > 0);
|
}
|
||||||
|
|
||||||
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
|
||||||
float tiny_expansion;
|
|
||||||
// How much to inflate the seed lines to produce the first wave area.
|
|
||||||
float initial_step;
|
|
||||||
// How much to inflate the first wave area and the successive wave areas in each step.
|
|
||||||
float other_step;
|
|
||||||
// Number of inflate steps after the initial step.
|
|
||||||
size_t num_other_steps;
|
|
||||||
// Maximum inflation of seed contours over the boundary. Used to trim boundary to speed up
|
|
||||||
// clipping during wave propagation.
|
|
||||||
float max_inflation;
|
|
||||||
|
|
||||||
// Offsetter to be applied for all inflation waves. Its accuracy is set with the block below.
|
|
||||||
ClipperLib::ClipperOffset co;
|
|
||||||
|
|
||||||
|
std::vector<Polygons> expand_expolygons(const ExPolygons &src, const ExPolygons &boundary,
|
||||||
|
// Scaled expansion value
|
||||||
|
float expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_steps)
|
||||||
{
|
{
|
||||||
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
|
||||||
// The expansion should not be too tiny, but also small enough, so the following expansion will
|
|
||||||
// compensate for tiny_expansion and bring the wave back to the boundary without producing
|
|
||||||
// ugly cusps where it touches the boundary.
|
|
||||||
tiny_expansion = std::min(0.25f * full_expansion, scaled<float>(0.05f));
|
|
||||||
size_t nsteps = size_t(ceil((full_expansion - tiny_expansion) / expansion_step));
|
|
||||||
if (max_nr_expansion_steps > 0)
|
|
||||||
nsteps = std::min(nsteps, max_nr_expansion_steps);
|
|
||||||
assert(nsteps > 0);
|
|
||||||
initial_step = (full_expansion - tiny_expansion) / nsteps;
|
|
||||||
if (nsteps > 1 && 0.25 * initial_step < tiny_expansion) {
|
|
||||||
// Decrease the step size by lowering number of steps.
|
|
||||||
nsteps = std::max<size_t>(1, (floor((full_expansion - tiny_expansion) / (4. * tiny_expansion))));
|
|
||||||
initial_step = (full_expansion - tiny_expansion) / nsteps;
|
|
||||||
}
|
|
||||||
if (0.25 * initial_step < tiny_expansion || nsteps == 1) {
|
|
||||||
tiny_expansion = 0.2f * full_expansion;
|
|
||||||
initial_step = 0.8f * full_expansion;
|
|
||||||
}
|
|
||||||
other_step = initial_step;
|
|
||||||
num_other_steps = nsteps - 1;
|
|
||||||
|
|
||||||
// Accuracy of the offsetter for wave propagation.
|
|
||||||
co.ArcTolerance = float(scale_(0.1));
|
|
||||||
co.ShortestEdgeLength = std::abs(initial_step * ClipperOffsetShortestEdgeFactor);
|
|
||||||
|
|
||||||
// Maximum inflation of seed contours over the boundary. Used to trim boundary to speed up
|
|
||||||
// clipping during wave propagation. Needs to be in sync with the offsetter accuracy.
|
|
||||||
// Clipper positive round offset should rather offset less than more.
|
|
||||||
// Still a little bit of additional offset was added.
|
|
||||||
max_inflation = (tiny_expansion + nsteps * initial_step) * 1.1;
|
|
||||||
// (clipper_round_offset_error(tiny_expansion, co.ArcTolerance) + nsteps * clipper_round_offset_error(initial_step, co.ArcTolerance) * 1.5; // Account for uncertainty
|
|
||||||
}
|
|
||||||
|
|
||||||
using Intersection = ClipperZUtils::ClipperZIntersectionVisitor::Intersection;
|
|
||||||
using Intersections = ClipperZUtils::ClipperZIntersectionVisitor::Intersections;
|
|
||||||
|
|
||||||
ClipperLib_Z::Paths expansion_seeds;
|
|
||||||
Intersections intersections;
|
|
||||||
|
|
||||||
coord_t idx_boundary_begin = 1;
|
|
||||||
coord_t idx_boundary_end;
|
|
||||||
coord_t idx_src_end;
|
|
||||||
|
|
||||||
{
|
|
||||||
ClipperLib_Z::Clipper zclipper;
|
|
||||||
ClipperZUtils::ClipperZIntersectionVisitor visitor(intersections);
|
|
||||||
zclipper.ZFillFunction(visitor.clipper_callback());
|
|
||||||
// as closed contours
|
|
||||||
{
|
|
||||||
ClipperLib_Z::Paths zboundary = ClipperZUtils::expolygons_to_zpaths(boundary, idx_boundary_begin);
|
|
||||||
idx_boundary_end = idx_boundary_begin + coord_t(zboundary.size());
|
|
||||||
zclipper.AddPaths(zboundary, ClipperLib_Z::ptClip, true);
|
|
||||||
}
|
|
||||||
// as open contours
|
|
||||||
std::vector<std::pair<ClipperLib_Z::IntPoint, int>> zsrc_splits;
|
|
||||||
{
|
|
||||||
ClipperLib_Z::Paths zsrc = expolygons_to_zpaths_expanded_opened(src, tiny_expansion, idx_boundary_end);
|
|
||||||
zclipper.AddPaths(zsrc, ClipperLib_Z::ptSubject, false);
|
|
||||||
idx_src_end = idx_boundary_end + coord_t(zsrc.size());
|
|
||||||
zsrc_splits.reserve(zsrc.size());
|
|
||||||
for (const ClipperLib_Z::Path &path : zsrc) {
|
|
||||||
assert(path.size() >= 2);
|
|
||||||
assert(path.front() == path.back());
|
|
||||||
zsrc_splits.emplace_back(path.front(), -1);
|
|
||||||
}
|
|
||||||
std::sort(zsrc_splits.begin(), zsrc_splits.end(), [](const auto &l, const auto &r){ return ClipperZUtils::zpoint_lower(l.first, r.first); });
|
|
||||||
}
|
|
||||||
ClipperLib_Z::PolyTree polytree;
|
|
||||||
zclipper.Execute(ClipperLib_Z::ctIntersection, polytree, ClipperLib_Z::pftNonZero, ClipperLib_Z::pftNonZero);
|
|
||||||
ClipperLib_Z::PolyTreeToPaths(std::move(polytree), expansion_seeds);
|
|
||||||
merge_splits(expansion_seeds, zsrc_splits);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Sort paths into their respective islands.
|
|
||||||
// Each src x boundary will be processed (wave expanded) independently.
|
|
||||||
// Multiple pieces of a single src may intersect the same boundary.
|
|
||||||
struct SeedOrigin {
|
|
||||||
int src;
|
|
||||||
int boundary;
|
|
||||||
int seed;
|
|
||||||
};
|
|
||||||
std::vector<SeedOrigin> map_seeds;
|
|
||||||
map_seeds.reserve(expansion_seeds.size());
|
|
||||||
int iseed = 0;
|
|
||||||
for (const ClipperLib_Z::Path &path : expansion_seeds) {
|
|
||||||
assert(path.size() >= 2);
|
|
||||||
const ClipperLib_Z::IntPoint &front = path.front();
|
|
||||||
const ClipperLib_Z::IntPoint &back = path.back();
|
|
||||||
// Both ends of a seed segment are supposed to be inside a single boundary expolygon.
|
|
||||||
assert(front.z() < 0);
|
|
||||||
assert(back.z() < 0);
|
|
||||||
const Intersection *intersection = nullptr;
|
|
||||||
auto intersection_point_valid = [idx_boundary_end, idx_src_end](const Intersection &is) {
|
|
||||||
return is.first >= 1 && is.first < idx_boundary_end &&
|
|
||||||
is.second >= idx_boundary_end && is.second < idx_src_end;
|
|
||||||
};
|
|
||||||
if (front.z() < 0) {
|
|
||||||
const Intersection &is = intersections[- front.z() - 1];
|
|
||||||
assert(intersection_point_valid(is));
|
|
||||||
if (intersection_point_valid(is))
|
|
||||||
intersection = &is;
|
|
||||||
}
|
|
||||||
if (! intersection && back.z() < 0) {
|
|
||||||
const Intersection &is = intersections[- back.z() - 1];
|
|
||||||
assert(intersection_point_valid(is));
|
|
||||||
if (intersection_point_valid(is))
|
|
||||||
intersection = &is;
|
|
||||||
}
|
|
||||||
if (intersection) {
|
|
||||||
// The path intersects the boundary contour at least at one side.
|
|
||||||
map_seeds.push_back({ intersection->second - idx_boundary_end, intersection->first - 1, iseed });
|
|
||||||
}
|
|
||||||
++ iseed;
|
|
||||||
}
|
|
||||||
// Sort the seeds by their intersection boundary and source contour.
|
|
||||||
std::sort(map_seeds.begin(), map_seeds.end(), [](const auto &l, const auto &r){
|
|
||||||
return l.boundary < r.boundary || (l.boundary == r.boundary && l.src < r.src);
|
|
||||||
});
|
|
||||||
|
|
||||||
std::vector<Polygons> out(src.size(), Polygons{});
|
std::vector<Polygons> out(src.size(), Polygons{});
|
||||||
ClipperLib::Paths paths;
|
for (RegionExpansion &r : propagate_waves(src, boundary, expansion, expansion_step, max_nr_steps))
|
||||||
for (auto it_seed = map_seeds.begin(); it_seed != map_seeds.end();) {
|
out[r.src_id].emplace_back(std::move(r.polygon));
|
||||||
auto it = it_seed;
|
return out;
|
||||||
paths.clear();
|
|
||||||
for (; it != map_seeds.end() && it->boundary == it_seed->boundary && it->src == it_seed->src; ++ it)
|
|
||||||
paths.emplace_back(ClipperZUtils::from_zpath(expansion_seeds[it->seed]));
|
|
||||||
// Propagate the wavefront while clipping it with the trimmed boundary.
|
|
||||||
// Collect the expanded polygons, merge them with the source polygons.
|
|
||||||
append(out[it_seed->src], propagate_wave_from_boundary(co, paths, boundary[it_seed->boundary], initial_step, other_step, num_other_steps, max_inflation));
|
|
||||||
it_seed = it;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
std::vector<ExPolygon> expand_merge_expolygons(ExPolygons &&src, const ExPolygons &boundary, const RegionExpansionParameters ¶ms)
|
||||||
|
{
|
||||||
|
// expanded regions are sorted by boundary id and source id
|
||||||
|
std::vector<RegionExpansion> expanded = propagate_waves(src, boundary, params);
|
||||||
|
// expanded regions will be merged into source regions, thus they will be re-sorted by source id.
|
||||||
|
std::sort(expanded.begin(), expanded.end(), [](const auto &l, const auto &r) { return l.src_id < r.src_id; });
|
||||||
|
uint32_t last = 0;
|
||||||
|
Polygons acc;
|
||||||
|
ExPolygons out;
|
||||||
|
out.reserve(src.size());
|
||||||
|
for (auto it = expanded.begin(); it != expanded.end();) {
|
||||||
|
auto it2 = it;
|
||||||
|
acc.clear();
|
||||||
|
for (; it2 != expanded.end() && it->src_id == it2->src_id; ++ it2)
|
||||||
|
acc.emplace_back(std::move(it2->polygon));
|
||||||
|
for (; last < it->src_id; ++ last)
|
||||||
|
out.emplace_back(std::move(src[last]));
|
||||||
|
//FIXME offset & merging could be more efficient, for example one does not need to copy the source expolygon
|
||||||
|
append(acc, to_polygons(std::move(src[it->src_id])));
|
||||||
|
ExPolygons merged = union_safety_offset_ex(acc);
|
||||||
|
// Expanding one expolygon by waves should not change connectivity of the source expolygon:
|
||||||
|
// Single expolygon should be produced possibly with increased number of holes.
|
||||||
|
assert(merged.size() == 1);
|
||||||
|
if (! merged.empty())
|
||||||
|
out.emplace_back(std::move(merged.front()));
|
||||||
|
it = it2;
|
||||||
|
}
|
||||||
|
for (; last < uint32_t(src.size()); ++ last)
|
||||||
|
out.emplace_back(std::move(src[last]));
|
||||||
return out;
|
return out;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -2,16 +2,102 @@
|
|||||||
#define SRC_LIBSLIC3R_ALGORITHM_REGION_EXPANSION_HPP_
|
#define SRC_LIBSLIC3R_ALGORITHM_REGION_EXPANSION_HPP_
|
||||||
|
|
||||||
#include <cstdint>
|
#include <cstdint>
|
||||||
|
#include <libslic3r/Point.hpp>
|
||||||
|
#include <libslic3r/Polygon.hpp>
|
||||||
|
#include <libslic3r/ExPolygon.hpp>
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
|
|
||||||
class Polygon;
|
|
||||||
using Polygons = std::vector<Polygon>;
|
|
||||||
class ExPolygon;
|
|
||||||
using ExPolygons = std::vector<ExPolygon>;
|
|
||||||
|
|
||||||
namespace Algorithm {
|
namespace Algorithm {
|
||||||
|
|
||||||
|
struct RegionExpansionParameters
|
||||||
|
{
|
||||||
|
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
||||||
|
float tiny_expansion;
|
||||||
|
// How much to inflate the seed lines to produce the first wave area.
|
||||||
|
float initial_step;
|
||||||
|
// How much to inflate the first wave area and the successive wave areas in each step.
|
||||||
|
float other_step;
|
||||||
|
// Number of inflate steps after the initial step.
|
||||||
|
size_t num_other_steps;
|
||||||
|
// Maximum inflation of seed contours over the boundary. Used to trim boundary to speed up
|
||||||
|
// clipping during wave propagation.
|
||||||
|
float max_inflation;
|
||||||
|
|
||||||
|
// Accuracy of the offsetter for wave propagation.
|
||||||
|
double arc_tolerance;
|
||||||
|
double shortest_edge_length;
|
||||||
|
|
||||||
|
static RegionExpansionParameters build(
|
||||||
|
// Scaled expansion value
|
||||||
|
float full_expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_expansion_steps);
|
||||||
|
};
|
||||||
|
|
||||||
|
struct WaveSeed {
|
||||||
|
uint32_t src;
|
||||||
|
uint32_t boundary;
|
||||||
|
Points path;
|
||||||
|
};
|
||||||
|
using WaveSeeds = std::vector<WaveSeed>;
|
||||||
|
|
||||||
|
inline bool lower_by_boundary_and_src(const WaveSeed &l, const WaveSeed &r)
|
||||||
|
{
|
||||||
|
return l.boundary < r.boundary || (l.boundary == r.boundary && l.src < r.src);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline bool lower_by_src_and_boundary(const WaveSeed &l, const WaveSeed &r)
|
||||||
|
{
|
||||||
|
return l.src < r.src || (l.src == r.src && l.boundary < r.boundary);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Expand src slightly outwards to intersect boundaries, trim the offsetted src polylines by the boundaries.
|
||||||
|
// Return the trimmed paths annotated with their origin (source of the path, index of the boundary region).
|
||||||
|
WaveSeeds wave_seeds(
|
||||||
|
// Source regions that are supposed to touch the boundary.
|
||||||
|
const ExPolygons &src,
|
||||||
|
// Boundaries of source regions touching the "boundary" regions will be expanded into the "boundary" region.
|
||||||
|
const ExPolygons &boundary,
|
||||||
|
// Initial expansion of src to make the source regions intersect with boundary regions just a bit.
|
||||||
|
float tiny_expansion,
|
||||||
|
bool sorted);
|
||||||
|
|
||||||
|
struct RegionExpansion
|
||||||
|
{
|
||||||
|
Polygon polygon;
|
||||||
|
uint32_t src_id;
|
||||||
|
uint32_t boundary_id;
|
||||||
|
};
|
||||||
|
|
||||||
|
std::vector<RegionExpansion> propagate_waves(const WaveSeeds &seeds, const ExPolygons &boundary, const RegionExpansionParameters ¶ms);
|
||||||
|
|
||||||
|
std::vector<RegionExpansion> propagate_waves(const ExPolygons &src, const ExPolygons &boundary,
|
||||||
|
// Scaled expansion value
|
||||||
|
float expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_steps);
|
||||||
|
|
||||||
|
struct RegionExpansionEx
|
||||||
|
{
|
||||||
|
ExPolygon expolygon;
|
||||||
|
uint32_t src_id;
|
||||||
|
uint32_t boundary_id;
|
||||||
|
};
|
||||||
|
|
||||||
|
std::vector<RegionExpansionEx> propagate_waves_ex(const WaveSeeds &seeds, const ExPolygons &boundary, const RegionExpansionParameters ¶ms);
|
||||||
|
|
||||||
|
std::vector<RegionExpansionEx> propagate_waves_ex(const ExPolygons &src, const ExPolygons &boundary,
|
||||||
|
// Scaled expansion value
|
||||||
|
float expansion,
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled).
|
||||||
|
float expansion_step,
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
size_t max_nr_steps);
|
||||||
|
|
||||||
std::vector<Polygons> expand_expolygons(const ExPolygons &src, const ExPolygons &boundary,
|
std::vector<Polygons> expand_expolygons(const ExPolygons &src, const ExPolygons &boundary,
|
||||||
// Scaled expansion value
|
// Scaled expansion value
|
||||||
float expansion,
|
float expansion,
|
||||||
@ -20,6 +106,8 @@ std::vector<Polygons> expand_expolygons(const ExPolygons &src, const ExPolygons
|
|||||||
// Don't take more than max_nr_steps for small expansion_step.
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
size_t max_nr_steps);
|
size_t max_nr_steps);
|
||||||
|
|
||||||
|
std::vector<ExPolygon> expand_merge_expolygons(ExPolygons &&src, const ExPolygons &boundary, const RegionExpansionParameters ¶ms);
|
||||||
|
|
||||||
} // Algorithm
|
} // Algorithm
|
||||||
} // Slic3r
|
} // Slic3r
|
||||||
|
|
||||||
|
@ -75,12 +75,9 @@ private:
|
|||||||
|
|
||||||
|
|
||||||
//return ideal bridge direction and unsupported bridge endpoints distance.
|
//return ideal bridge direction and unsupported bridge endpoints distance.
|
||||||
inline std::tuple<Vec2d, double> detect_bridging_direction(const Polygons &to_cover, const Polygons &anchors_area)
|
inline std::tuple<Vec2d, double> detect_bridging_direction(const Lines &floating_edges, const Polygons &overhang_area)
|
||||||
{
|
{
|
||||||
Polygons overhang_area = diff(to_cover, anchors_area);
|
if (floating_edges.empty()) {
|
||||||
Polylines floating_polylines = diff_pl(to_polylines(overhang_area), expand(anchors_area, float(SCALED_EPSILON)));
|
|
||||||
|
|
||||||
if (floating_polylines.empty()) {
|
|
||||||
// consider this area anchored from all sides, pick bridging direction that will likely yield shortest bridges
|
// consider this area anchored from all sides, pick bridging direction that will likely yield shortest bridges
|
||||||
//use 3mm resolution (should be quite fast, and rough estimation should not cause any problems here)
|
//use 3mm resolution (should be quite fast, and rough estimation should not cause any problems here)
|
||||||
auto [pc1, pc2] = compute_principal_components(overhang_area, 3.0);
|
auto [pc1, pc2] = compute_principal_components(overhang_area, 3.0);
|
||||||
@ -92,7 +89,6 @@ inline std::tuple<Vec2d, double> detect_bridging_direction(const Polygons &to_co
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Overhang is not fully surrounded by anchors, in that case, find such direction that will minimize the number of bridge ends/180turns in the air
|
// Overhang is not fully surrounded by anchors, in that case, find such direction that will minimize the number of bridge ends/180turns in the air
|
||||||
Lines floating_edges = to_lines(floating_polylines);
|
|
||||||
std::unordered_map<double, Vec2d> directions{};
|
std::unordered_map<double, Vec2d> directions{};
|
||||||
for (const Line &l : floating_edges) {
|
for (const Line &l : floating_edges) {
|
||||||
Vec2d normal = l.normal().cast<double>().normalized();
|
Vec2d normal = l.normal().cast<double>().normalized();
|
||||||
@ -126,6 +122,13 @@ inline std::tuple<Vec2d, double> detect_bridging_direction(const Polygons &to_co
|
|||||||
return {result_dir, min_cost};
|
return {result_dir, min_cost};
|
||||||
};
|
};
|
||||||
|
|
||||||
|
//return ideal bridge direction and unsupported bridge endpoints distance.
|
||||||
|
inline std::tuple<Vec2d, double> detect_bridging_direction(const Polygons &to_cover, const Polygons &anchors_area)
|
||||||
|
{
|
||||||
|
Polygons overhang_area = diff(to_cover, anchors_area);
|
||||||
|
Lines floating_edges = to_lines(diff_pl(to_polylines(overhang_area), expand(anchors_area, float(SCALED_EPSILON))));
|
||||||
|
return detect_bridging_direction(floating_edges, overhang_area);
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -19,20 +19,7 @@ bool RetractWhenCrossingPerimeters::travel_inside_internal_regions(const Layer &
|
|||||||
if (surface.is_internal())
|
if (surface.is_internal())
|
||||||
m_internal_islands.emplace_back(&surface.expolygon);
|
m_internal_islands.emplace_back(&surface.expolygon);
|
||||||
// Calculate bounding boxes of internal slices.
|
// Calculate bounding boxes of internal slices.
|
||||||
class BBoxWrapper {
|
std::vector<AABBTreeIndirect::BoundingBoxWrapper> bboxes;
|
||||||
public:
|
|
||||||
BBoxWrapper(const size_t idx, const BoundingBox &bbox) :
|
|
||||||
m_idx(idx),
|
|
||||||
// Inflate the bounding box a bit to account for numerical issues.
|
|
||||||
m_bbox(bbox.min - Point(SCALED_EPSILON, SCALED_EPSILON), bbox.max + Point(SCALED_EPSILON, SCALED_EPSILON)) {}
|
|
||||||
size_t idx() const { return m_idx; }
|
|
||||||
const AABBTree::BoundingBox& bbox() const { return m_bbox; }
|
|
||||||
Point centroid() const { return ((m_bbox.min().cast<int64_t>() + m_bbox.max().cast<int64_t>()) / 2).cast<int32_t>(); }
|
|
||||||
private:
|
|
||||||
size_t m_idx;
|
|
||||||
AABBTree::BoundingBox m_bbox;
|
|
||||||
};
|
|
||||||
std::vector<BBoxWrapper> bboxes;
|
|
||||||
bboxes.reserve(m_internal_islands.size());
|
bboxes.reserve(m_internal_islands.size());
|
||||||
for (size_t i = 0; i < m_internal_islands.size(); ++ i)
|
for (size_t i = 0; i < m_internal_islands.size(); ++ i)
|
||||||
bboxes.emplace_back(i, get_extents(*m_internal_islands[i]));
|
bboxes.emplace_back(i, get_extents(*m_internal_islands[i]));
|
||||||
|
@ -8,6 +8,7 @@
|
|||||||
#include "Surface.hpp"
|
#include "Surface.hpp"
|
||||||
#include "BoundingBox.hpp"
|
#include "BoundingBox.hpp"
|
||||||
#include "SVG.hpp"
|
#include "SVG.hpp"
|
||||||
|
#include "Algorithm/RegionExpansion.hpp"
|
||||||
|
|
||||||
#include <string>
|
#include <string>
|
||||||
#include <map>
|
#include <map>
|
||||||
@ -139,6 +140,252 @@ void LayerRegion::make_perimeters(
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if 1
|
||||||
|
|
||||||
|
// Extract surfaces of given type from surfaces, extract fill (layer) thickness of one of the surfaces.
|
||||||
|
static ExPolygons fill_surfaces_extract_expolygons(Surfaces &surfaces, SurfaceType surface_type, double &thickness)
|
||||||
|
{
|
||||||
|
size_t cnt = 0;
|
||||||
|
for (const Surface &surface : surfaces)
|
||||||
|
if (surface.surface_type == surface_type) {
|
||||||
|
++ cnt;
|
||||||
|
thickness = surface.thickness;
|
||||||
|
}
|
||||||
|
if (cnt == 0)
|
||||||
|
return {};
|
||||||
|
|
||||||
|
ExPolygons out;
|
||||||
|
out.reserve(cnt);
|
||||||
|
for (Surface &surface : surfaces)
|
||||||
|
if (surface.surface_type == surface_type)
|
||||||
|
out.emplace_back(std::move(surface.expolygon));
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract bridging surfaces from "surfaces", expand them into "shells" using expansion_params,
|
||||||
|
// detect bridges.
|
||||||
|
// Trim "shells" by the expanded bridges.
|
||||||
|
Surfaces expand_bridges_detect_orientations(
|
||||||
|
Surfaces &surfaces,
|
||||||
|
ExPolygons &shells,
|
||||||
|
const Algorithm::RegionExpansionParameters &expansion_params)
|
||||||
|
{
|
||||||
|
using namespace Slic3r::Algorithm;
|
||||||
|
|
||||||
|
double thickness;
|
||||||
|
ExPolygons bridges_ex = fill_surfaces_extract_expolygons(surfaces, stBottomBridge, thickness);
|
||||||
|
if (bridges_ex.empty())
|
||||||
|
return {};
|
||||||
|
|
||||||
|
// Calculate bridge anchors and their expansions in their respective shell region.
|
||||||
|
WaveSeeds bridge_anchors = wave_seeds(bridges_ex, shells, expansion_params.tiny_expansion, true);
|
||||||
|
std::vector<RegionExpansionEx> bridge_expansions = propagate_waves_ex(bridge_anchors, shells, expansion_params);
|
||||||
|
|
||||||
|
// Cache for detecting bridge orientation and merging regions with overlapping expansions.
|
||||||
|
struct Bridge {
|
||||||
|
ExPolygon expolygon;
|
||||||
|
uint32_t group_id;
|
||||||
|
double angle = -1;
|
||||||
|
};
|
||||||
|
std::vector<Bridge> bridges;
|
||||||
|
{
|
||||||
|
bridges.reserve(bridges_ex.size());
|
||||||
|
uint32_t group_id = 0;
|
||||||
|
for (ExPolygon &ex : bridges_ex)
|
||||||
|
bridges.push_back({ std::move(ex), group_id ++ });
|
||||||
|
bridges_ex.clear();
|
||||||
|
}
|
||||||
|
|
||||||
|
// Group the bridge surfaces by overlaps.
|
||||||
|
auto group_id = [&bridges](uint32_t src_id) {
|
||||||
|
uint32_t group_id = bridges[src_id].group_id;
|
||||||
|
while (group_id != src_id) {
|
||||||
|
src_id = group_id;
|
||||||
|
group_id = bridges[src_id].group_id;
|
||||||
|
}
|
||||||
|
bridges[src_id].group_id = group_id;
|
||||||
|
return group_id;
|
||||||
|
};
|
||||||
|
|
||||||
|
{
|
||||||
|
// Cache of bboxes per expansion boundary.
|
||||||
|
std::vector<BoundingBox> bboxes;
|
||||||
|
// Detect overlaps of bridge anchors inside their respective shell regions.
|
||||||
|
// bridge_expansions are sorted by boundary id and source id.
|
||||||
|
for (auto it = bridge_expansions.begin(); it != bridge_expansions.end();) {
|
||||||
|
// For each boundary region:
|
||||||
|
auto it2 = it;
|
||||||
|
for (++ it2; it2 != bridge_expansions.end() && it2->boundary_id == it->boundary_id; ++ it2);
|
||||||
|
bboxes.clear();
|
||||||
|
bboxes.reserve(it2 - it);
|
||||||
|
for (it2 = it; it2 != bridge_expansions.end() && it2->boundary_id == it->boundary_id; ++ it2)
|
||||||
|
bboxes.emplace_back(get_extents(it2->expolygon.contour));
|
||||||
|
auto it_end = it2;
|
||||||
|
// For each bridge anchor of the current source:
|
||||||
|
for (; it != it_end; ++ it) {
|
||||||
|
// A grup id for this bridge.
|
||||||
|
for (it2 = std::next(it); it2 != it_end; ++ it2)
|
||||||
|
if (it->src_id != it2->src_id &&
|
||||||
|
bboxes[it - bridge_expansions.begin()].overlap(bboxes[it2 - bridge_expansions.begin()]) &&
|
||||||
|
// One may ignore holes, they are irrelevant for intersection test.
|
||||||
|
! intersection(it->expolygon.contour, it2->expolygon.contour).empty()) {
|
||||||
|
// The two bridge regions intersect. Give them the same group id.
|
||||||
|
uint32_t id = group_id(it->src_id);
|
||||||
|
uint32_t id2 = group_id(it2->src_id);
|
||||||
|
bridges[it->src_id].group_id = bridges[it2->src_id].group_id = std::min(id, id2);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Detect bridge directions.
|
||||||
|
{
|
||||||
|
std::sort(bridge_anchors.begin(), bridge_anchors.end(), Algorithm::lower_by_src_and_boundary);
|
||||||
|
auto it_bridge_anchor = bridge_anchors.begin();
|
||||||
|
Lines lines;
|
||||||
|
for (uint32_t bridge_id = 0; bridge_id < uint32_t(bridges.size()); ++ bridge_id) {
|
||||||
|
Bridge &bridge = bridges[bridge_id];
|
||||||
|
lines.clear();
|
||||||
|
for (++ it_bridge_anchor; it_bridge_anchor != bridge_anchors.end() && it_bridge_anchor->src == bridge_id; ++ it_bridge_anchor)
|
||||||
|
if (Points &polyline = it_bridge_anchor->path; polyline.size() >= 2) {
|
||||||
|
reserve_more_power_of_2(lines, polyline.size() - 1);
|
||||||
|
for (size_t i = 1; i < polyline.size(); ++ i)
|
||||||
|
lines.push_back({ polyline[i - 1], polyline[1] });
|
||||||
|
}
|
||||||
|
auto [bridging_dir, unsupported_dist] = detect_bridging_direction(lines, to_polygons(bridge.expolygon));
|
||||||
|
bridge.angle = M_PI + std::atan2(bridging_dir.y(), bridging_dir.x());
|
||||||
|
// #if 1
|
||||||
|
// coordf_t stroke_width = scale_(0.06);
|
||||||
|
// BoundingBox bbox = get_extents(initial);
|
||||||
|
// bbox.offset(scale_(1.));
|
||||||
|
// ::Slic3r::SVG
|
||||||
|
// svg(debug_out_path(("bridge"+std::to_string(bridges[idx_last].bridge_angle)+"_"+std::to_string(this->layer()->bottom_z())).c_str()),
|
||||||
|
// bbox);
|
||||||
|
|
||||||
|
// svg.draw(initial, "cyan");
|
||||||
|
// svg.draw(to_lines(lower_layer->lslices), "green", stroke_width);
|
||||||
|
// #endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Merge the groups with the same group id, produce surfaces by merging source overhangs with their newly expanded anchors.
|
||||||
|
Surfaces out;
|
||||||
|
{
|
||||||
|
Polygons acc;
|
||||||
|
Surface templ{ stBottomBridge, {} };
|
||||||
|
for (uint32_t bridge_id = 0; bridge_id < uint32_t(bridges.size()); ++ bridge_id) {
|
||||||
|
acc.clear();
|
||||||
|
for (uint32_t bridge_id2 = bridge_id; bridge_id2 < uint32_t(bridges.size()); ++ bridge_id2)
|
||||||
|
if (group_id(bridge_id) == bridge_id) {
|
||||||
|
append(acc, to_polygons(std::move(bridges[bridge_id2].expolygon)));
|
||||||
|
append(acc, to_polygons(std::move(bridge_expansions[bridge_id2].expolygon)));
|
||||||
|
}
|
||||||
|
//FIXME try to be smart and pick the best bridging angle for all?
|
||||||
|
templ.bridge_angle = bridges[bridge_id].angle;
|
||||||
|
// without safety offset, artifacts are generated (GH #2494)
|
||||||
|
for (ExPolygon &ex : union_safety_offset_ex(acc))
|
||||||
|
out.emplace_back(templ, std::move(ex));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Clip the shells by the expanded bridges.
|
||||||
|
shells = diff_ex(shells, out);
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Extract bridging surfaces from "surfaces", expand them into "shells" using expansion_params.
|
||||||
|
// Trim "shells" by the expanded bridges.
|
||||||
|
static Surfaces expand_merge_surfaces(
|
||||||
|
Surfaces &surfaces,
|
||||||
|
SurfaceType surface_type,
|
||||||
|
ExPolygons &shells,
|
||||||
|
const Algorithm::RegionExpansionParameters ¶ms,
|
||||||
|
const double bridge_angle = -1.)
|
||||||
|
{
|
||||||
|
double thickness;
|
||||||
|
ExPolygons src = fill_surfaces_extract_expolygons(surfaces, surface_type, thickness);
|
||||||
|
if (src.empty())
|
||||||
|
return {};
|
||||||
|
|
||||||
|
std::vector<ExPolygon> expanded = expand_merge_expolygons(std::move(src), shells, params);
|
||||||
|
// Trim the shells by the expanded expolygons.
|
||||||
|
shells = diff_ex(shells, expanded);
|
||||||
|
|
||||||
|
Surface templ{ surface_type, {} };
|
||||||
|
templ.bridge_angle = bridge_angle;
|
||||||
|
Surfaces out;
|
||||||
|
out.reserve(expanded.size());
|
||||||
|
for (auto &expoly : expanded)
|
||||||
|
out.emplace_back(templ, std::move(expoly));
|
||||||
|
return out;
|
||||||
|
}
|
||||||
|
|
||||||
|
void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Polygons *lower_layer_covered)
|
||||||
|
{
|
||||||
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
|
export_region_fill_surfaces_to_svg_debug("4_process_external_surfaces-initial");
|
||||||
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
|
// Width of the perimeters.
|
||||||
|
float shell_width = 0;
|
||||||
|
if (int num_perimeters = this->region().config().perimeters; num_perimeters > 0) {
|
||||||
|
Flow external_perimeter_flow = this->flow(frExternalPerimeter);
|
||||||
|
Flow perimeter_flow = this->flow(frPerimeter);
|
||||||
|
shell_width += 0.5f * external_perimeter_flow.scaled_width() + external_perimeter_flow.scaled_spacing();
|
||||||
|
shell_width += perimeter_flow.scaled_spacing() * (num_perimeters - 1);
|
||||||
|
} else {
|
||||||
|
}
|
||||||
|
|
||||||
|
// Scaled expansions of the respective external surfaces.
|
||||||
|
float expansion_top = shell_width * sqrt(2.);
|
||||||
|
float expansion_bottom = expansion_top;
|
||||||
|
float expansion_bottom_bridge = expansion_top;
|
||||||
|
// Expand by waves of expansion_step size (expansion_step is scaled), but with no more steps than max_nr_expansion_steps.
|
||||||
|
static constexpr const float expansion_step = scaled<float>(0.1);
|
||||||
|
// Don't take more than max_nr_steps for small expansion_step.
|
||||||
|
static constexpr const size_t max_nr_expansion_steps = 5;
|
||||||
|
|
||||||
|
// Expand the top / bottom / bridge surfaces into the shell thickness solid infills.
|
||||||
|
double layer_thickness;
|
||||||
|
ExPolygons shells = union_ex(fill_surfaces_extract_expolygons(m_fill_surfaces.surfaces, stInternalSolid, layer_thickness));
|
||||||
|
|
||||||
|
SurfaceCollection bridges;
|
||||||
|
{
|
||||||
|
BOOST_LOG_TRIVIAL(trace) << "Processing external surface, detecting bridges. layer" << this->layer()->print_z;
|
||||||
|
const double custom_angle = this->region().config().bridge_angle.value;
|
||||||
|
const auto params = Algorithm::RegionExpansionParameters::build(expansion_bottom_bridge, expansion_step, max_nr_expansion_steps);
|
||||||
|
bridges.surfaces = custom_angle > 0 ?
|
||||||
|
expand_bridges_detect_orientations(m_fill_surfaces.surfaces, shells, params) :
|
||||||
|
expand_merge_surfaces(m_fill_surfaces.surfaces, stBottomBridge, shells, params, custom_angle);
|
||||||
|
BOOST_LOG_TRIVIAL(trace) << "Processing external surface, detecting bridges - done";
|
||||||
|
#if 0
|
||||||
|
{
|
||||||
|
static int iRun = 0;
|
||||||
|
bridges.export_to_svg(debug_out_path("bridges-after-grouping-%d.svg", iRun++), true);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
Surfaces bottoms = expand_merge_surfaces(m_fill_surfaces.surfaces, stBottom, shells,
|
||||||
|
Algorithm::RegionExpansionParameters::build(expansion_bottom, expansion_step, max_nr_expansion_steps));
|
||||||
|
Surfaces tops = expand_merge_surfaces(m_fill_surfaces.surfaces, stTop, shells,
|
||||||
|
Algorithm::RegionExpansionParameters::build(expansion_top, expansion_step, max_nr_expansion_steps));
|
||||||
|
|
||||||
|
m_fill_surfaces.remove_types({ stBottomBridge, stBottom, stTop, stInternalSolid });
|
||||||
|
reserve_more(m_fill_surfaces.surfaces, shells.size() + bridges.size() + bottoms.size() + tops.size());
|
||||||
|
Surface solid_templ(stInternalSolid, {});
|
||||||
|
solid_templ.thickness = layer_thickness;
|
||||||
|
m_fill_surfaces.append(std::move(shells), solid_templ);
|
||||||
|
m_fill_surfaces.append(std::move(bridges.surfaces));
|
||||||
|
m_fill_surfaces.append(std::move(bottoms));
|
||||||
|
m_fill_surfaces.append(std::move(tops));
|
||||||
|
|
||||||
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
|
export_region_fill_surfaces_to_svg_debug("4_process_external_surfaces-final");
|
||||||
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
|
||||||
//#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtMiter, 3.
|
//#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtMiter, 3.
|
||||||
//#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtMiter, 1.5
|
//#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtMiter, 1.5
|
||||||
#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtSquare, 0.
|
#define EXTERNAL_SURFACES_OFFSET_PARAMETERS ClipperLib::jtSquare, 0.
|
||||||
@ -146,10 +393,11 @@ void LayerRegion::make_perimeters(
|
|||||||
void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Polygons *lower_layer_covered)
|
void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Polygons *lower_layer_covered)
|
||||||
{
|
{
|
||||||
const bool has_infill = this->region().config().fill_density.value > 0.;
|
const bool has_infill = this->region().config().fill_density.value > 0.;
|
||||||
|
// const float margin = scaled<float>(0.1); // float(scale_(EXTERNAL_INFILL_MARGIN));
|
||||||
const float margin = float(scale_(EXTERNAL_INFILL_MARGIN));
|
const float margin = float(scale_(EXTERNAL_INFILL_MARGIN));
|
||||||
|
|
||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
export_region_fill_surfaces_to_svg_debug("3_process_external_surfaces-initial");
|
export_region_fill_surfaces_to_svg_debug("4_process_external_surfaces-initial");
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
// 1) Collect bottom and bridge surfaces, each of them grown by a fixed 3mm offset
|
// 1) Collect bottom and bridge surfaces, each of them grown by a fixed 3mm offset
|
||||||
@ -164,7 +412,6 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
Surfaces internal;
|
Surfaces internal;
|
||||||
// Areas, where an infill of various types (top, bottom, bottom bride, sparse, void) could be placed.
|
// Areas, where an infill of various types (top, bottom, bottom bride, sparse, void) could be placed.
|
||||||
Polygons fill_boundaries = to_polygons(this->fill_expolygons());
|
Polygons fill_boundaries = to_polygons(this->fill_expolygons());
|
||||||
Polygons lower_layer_covered_tmp;
|
|
||||||
|
|
||||||
// Collect top surfaces and internal surfaces.
|
// Collect top surfaces and internal surfaces.
|
||||||
// Collect fill_boundaries: If we're slicing with no infill, we can't extend external surfaces over non-existent infill.
|
// Collect fill_boundaries: If we're slicing with no infill, we can't extend external surfaces over non-existent infill.
|
||||||
@ -174,6 +421,8 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
// Voids are sparse infills if infill rate is zero.
|
// Voids are sparse infills if infill rate is zero.
|
||||||
Polygons voids;
|
Polygons voids;
|
||||||
for (const Surface &surface : this->fill_surfaces()) {
|
for (const Surface &surface : this->fill_surfaces()) {
|
||||||
|
assert(! surface.empty());
|
||||||
|
if (! surface.empty()) {
|
||||||
if (surface.is_top()) {
|
if (surface.is_top()) {
|
||||||
// Collect the top surfaces, inflate them and trim them by the bottom surfaces.
|
// Collect the top surfaces, inflate them and trim them by the bottom surfaces.
|
||||||
// This gives the priority to bottom surfaces.
|
// This gives the priority to bottom surfaces.
|
||||||
@ -182,24 +431,31 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
// Grown by 3mm.
|
// Grown by 3mm.
|
||||||
surfaces_append(bottom, offset_ex(surface.expolygon, margin, EXTERNAL_SURFACES_OFFSET_PARAMETERS), surface);
|
surfaces_append(bottom, offset_ex(surface.expolygon, margin, EXTERNAL_SURFACES_OFFSET_PARAMETERS), surface);
|
||||||
} else if (surface.surface_type == stBottomBridge) {
|
} else if (surface.surface_type == stBottomBridge) {
|
||||||
if (! surface.empty())
|
|
||||||
bridges.emplace_back(surface);
|
bridges.emplace_back(surface);
|
||||||
}
|
} else {
|
||||||
if (surface.is_internal()) {
|
assert(surface.is_internal());
|
||||||
assert(surface.surface_type == stInternal || surface.surface_type == stInternalSolid);
|
assert(surface.surface_type == stInternal || surface.surface_type == stInternalSolid);
|
||||||
if (! has_infill && lower_layer != nullptr)
|
if (! has_infill && lower_layer != nullptr)
|
||||||
polygons_append(voids, surface.expolygon);
|
polygons_append(voids, surface.expolygon);
|
||||||
internal.emplace_back(std::move(surface));
|
internal.emplace_back(std::move(surface));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if (! has_infill && lower_layer != nullptr && ! voids.empty()) {
|
}
|
||||||
|
if (! voids.empty()) {
|
||||||
|
// There are some voids (empty infill regions) on this layer. Usually one does not want to expand
|
||||||
|
// any infill into these voids, with the exception the expanded infills are supported by layers below
|
||||||
|
// with nonzero inill.
|
||||||
|
assert(! has_infill && lower_layer != nullptr);
|
||||||
// Remove voids from fill_boundaries, that are not supported by the layer below.
|
// Remove voids from fill_boundaries, that are not supported by the layer below.
|
||||||
|
Polygons lower_layer_covered_tmp;
|
||||||
if (lower_layer_covered == nullptr) {
|
if (lower_layer_covered == nullptr) {
|
||||||
lower_layer_covered = &lower_layer_covered_tmp;
|
lower_layer_covered = &lower_layer_covered_tmp;
|
||||||
lower_layer_covered_tmp = to_polygons(lower_layer->lslices);
|
lower_layer_covered_tmp = to_polygons(lower_layer->lslices);
|
||||||
}
|
}
|
||||||
if (! lower_layer_covered->empty())
|
if (! lower_layer_covered->empty())
|
||||||
|
// Allow the top / bottom surfaces to expand into the voids of this layer if supported by the layer below.
|
||||||
voids = diff(voids, *lower_layer_covered);
|
voids = diff(voids, *lower_layer_covered);
|
||||||
|
if (! voids.empty())
|
||||||
fill_boundaries = diff(fill_boundaries, voids);
|
fill_boundaries = diff(fill_boundaries, voids);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -224,13 +480,12 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
{
|
{
|
||||||
static int iRun = 0;
|
static int iRun = 0;
|
||||||
SVG svg(debug_out_path("3_process_external_surfaces-fill_regions-%d.svg", iRun ++).c_str(), get_extents(fill_boundaries_ex));
|
SVG svg(debug_out_path("4_process_external_surfaces-fill_regions-%d.svg", iRun ++).c_str(), get_extents(fill_boundaries_ex));
|
||||||
svg.draw(fill_boundaries_ex);
|
svg.draw(fill_boundaries_ex);
|
||||||
svg.draw_outline(fill_boundaries_ex, "black", "blue", scale_(0.05));
|
svg.draw_outline(fill_boundaries_ex, "black", "blue", scale_(0.05));
|
||||||
svg.Close();
|
svg.Close();
|
||||||
}
|
}
|
||||||
|
// export_region_fill_surfaces_to_svg_debug("4_process_external_surfaces-initial");
|
||||||
// export_region_fill_surfaces_to_svg_debug("3_process_external_surfaces-initial");
|
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
{
|
{
|
||||||
@ -253,7 +508,8 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
if (idx_island == -1) {
|
if (idx_island == -1) {
|
||||||
BOOST_LOG_TRIVIAL(trace) << "Bridge did not fall into the source region!";
|
BOOST_LOG_TRIVIAL(trace) << "Bridge did not fall into the source region!";
|
||||||
} else {
|
} else {
|
||||||
// Found an island, to which this bridge region belongs. Trim it,
|
// Found an island, to which this bridge region belongs. Trim the expanded bridging region
|
||||||
|
// with its source region, so it does not overflow into a neighbor region.
|
||||||
polys = intersection(polys, fill_boundaries_ex[idx_island]);
|
polys = intersection(polys, fill_boundaries_ex[idx_island]);
|
||||||
}
|
}
|
||||||
bridge_bboxes.push_back(get_extents(polys));
|
bridge_bboxes.push_back(get_extents(polys));
|
||||||
@ -371,10 +627,10 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
|
|
||||||
Surfaces new_surfaces;
|
Surfaces new_surfaces;
|
||||||
{
|
{
|
||||||
// Merge top and bottom in a single collection.
|
|
||||||
surfaces_append(top, std::move(bottom));
|
|
||||||
// Intersect the grown surfaces with the actual fill boundaries.
|
// Intersect the grown surfaces with the actual fill boundaries.
|
||||||
Polygons bottom_polygons = to_polygons(bottom);
|
Polygons bottom_polygons = to_polygons(bottom);
|
||||||
|
// Merge top and bottom in a single collection.
|
||||||
|
surfaces_append(top, std::move(bottom));
|
||||||
for (size_t i = 0; i < top.size(); ++ i) {
|
for (size_t i = 0; i < top.size(); ++ i) {
|
||||||
Surface &s1 = top[i];
|
Surface &s1 = top[i];
|
||||||
if (s1.empty())
|
if (s1.empty())
|
||||||
@ -422,9 +678,10 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
|
|||||||
m_fill_surfaces.surfaces = std::move(new_surfaces);
|
m_fill_surfaces.surfaces = std::move(new_surfaces);
|
||||||
|
|
||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
export_region_fill_surfaces_to_svg_debug("3_process_external_surfaces-final");
|
export_region_fill_surfaces_to_svg_debug("4_process_external_surfaces-final");
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void LayerRegion::prepare_fill_surfaces()
|
void LayerRegion::prepare_fill_surfaces()
|
||||||
{
|
{
|
||||||
|
@ -260,6 +260,22 @@ void PrintObject::prepare_infill()
|
|||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// Add solid fills to ensure the shell vertical thickness.
|
||||||
|
this->discover_vertical_shells();
|
||||||
|
m_print->throw_if_canceled();
|
||||||
|
|
||||||
|
// Debugging output.
|
||||||
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
|
for (size_t region_id = 0; region_id < this->num_printing_regions(); ++ region_id) {
|
||||||
|
for (const Layer *layer : m_layers) {
|
||||||
|
LayerRegion *layerm = layer->m_regions[region_id];
|
||||||
|
layerm->export_region_slices_to_svg_debug("3_discover_vertical_shells-final");
|
||||||
|
layerm->export_region_fill_surfaces_to_svg_debug("3_discover_vertical_shells-final");
|
||||||
|
} // for each layer
|
||||||
|
} // for each region
|
||||||
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
// this will detect bridges and reverse bridges
|
// this will detect bridges and reverse bridges
|
||||||
// and rearrange top/bottom/internal surfaces
|
// and rearrange top/bottom/internal surfaces
|
||||||
// It produces enlarged overlapping bridging areas.
|
// It produces enlarged overlapping bridging areas.
|
||||||
@ -272,17 +288,13 @@ void PrintObject::prepare_infill()
|
|||||||
this->process_external_surfaces();
|
this->process_external_surfaces();
|
||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
|
|
||||||
// Add solid fills to ensure the shell vertical thickness.
|
|
||||||
this->discover_vertical_shells();
|
|
||||||
m_print->throw_if_canceled();
|
|
||||||
|
|
||||||
// Debugging output.
|
// Debugging output.
|
||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
for (size_t region_id = 0; region_id < this->num_printing_regions(); ++ region_id) {
|
for (size_t region_id = 0; region_id < this->num_printing_regions(); ++ region_id) {
|
||||||
for (const Layer *layer : m_layers) {
|
for (const Layer *layer : m_layers) {
|
||||||
LayerRegion *layerm = layer->m_regions[region_id];
|
LayerRegion *layerm = layer->m_regions[region_id];
|
||||||
layerm->export_region_slices_to_svg_debug("6_discover_vertical_shells-final");
|
layerm->export_region_slices_to_svg_debug("3_process_external_surfaces-final");
|
||||||
layerm->export_region_fill_surfaces_to_svg_debug("6_discover_vertical_shells-final");
|
layerm->export_region_fill_surfaces_to_svg_debug("3_process_external_surfaces-final");
|
||||||
} // for each layer
|
} // for each layer
|
||||||
} // for each region
|
} // for each region
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
@ -1042,7 +1054,7 @@ void PrintObject::process_external_surfaces()
|
|||||||
if (has_voids && m_layers.size() > 1) {
|
if (has_voids && m_layers.size() > 1) {
|
||||||
// All but stInternal fill surfaces will get expanded and possibly trimmed.
|
// All but stInternal fill surfaces will get expanded and possibly trimmed.
|
||||||
std::vector<unsigned char> layer_expansions_and_voids(m_layers.size(), false);
|
std::vector<unsigned char> layer_expansions_and_voids(m_layers.size(), false);
|
||||||
for (size_t layer_idx = 0; layer_idx < m_layers.size(); ++ layer_idx) {
|
for (size_t layer_idx = 1; layer_idx < m_layers.size(); ++ layer_idx) {
|
||||||
const Layer *layer = m_layers[layer_idx];
|
const Layer *layer = m_layers[layer_idx];
|
||||||
bool expansions = false;
|
bool expansions = false;
|
||||||
bool voids = false;
|
bool voids = false;
|
||||||
@ -1068,6 +1080,8 @@ void PrintObject::process_external_surfaces()
|
|||||||
[this, &surfaces_covered, &layer_expansions_and_voids, unsupported_width](const tbb::blocked_range<size_t>& range) {
|
[this, &surfaces_covered, &layer_expansions_and_voids, unsupported_width](const tbb::blocked_range<size_t>& range) {
|
||||||
for (size_t layer_idx = range.begin(); layer_idx < range.end(); ++ layer_idx)
|
for (size_t layer_idx = range.begin(); layer_idx < range.end(); ++ layer_idx)
|
||||||
if (layer_expansions_and_voids[layer_idx + 1]) {
|
if (layer_expansions_and_voids[layer_idx + 1]) {
|
||||||
|
// Layer above is partially filled with solid infill (top, bottom, bridging...),
|
||||||
|
// while some sparse inill regions are empty (0% infill).
|
||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
Polygons voids;
|
Polygons voids;
|
||||||
for (const LayerRegion *layerm : m_layers[layer_idx]->regions()) {
|
for (const LayerRegion *layerm : m_layers[layer_idx]->regions()) {
|
||||||
@ -1093,7 +1107,9 @@ void PrintObject::process_external_surfaces()
|
|||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
// BOOST_LOG_TRIVIAL(trace) << "Processing external surface, layer" << m_layers[layer_idx]->print_z;
|
// BOOST_LOG_TRIVIAL(trace) << "Processing external surface, layer" << m_layers[layer_idx]->print_z;
|
||||||
m_layers[layer_idx]->get_region(int(region_id))->process_external_surfaces(
|
m_layers[layer_idx]->get_region(int(region_id))->process_external_surfaces(
|
||||||
|
// lower layer
|
||||||
(layer_idx == 0) ? nullptr : m_layers[layer_idx - 1],
|
(layer_idx == 0) ? nullptr : m_layers[layer_idx - 1],
|
||||||
|
// lower layer polygons with density > 0%
|
||||||
(layer_idx == 0 || surfaces_covered.empty() || surfaces_covered[layer_idx - 1].empty()) ? nullptr : &surfaces_covered[layer_idx - 1]);
|
(layer_idx == 0 || surfaces_covered.empty() || surfaces_covered[layer_idx - 1].empty()) ? nullptr : &surfaces_covered[layer_idx - 1]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -1152,7 +1168,7 @@ void PrintObject::discover_vertical_shells()
|
|||||||
tbb::parallel_for(
|
tbb::parallel_for(
|
||||||
tbb::blocked_range<size_t>(0, num_layers, grain_size),
|
tbb::blocked_range<size_t>(0, num_layers, grain_size),
|
||||||
[this, &cache_top_botom_regions](const tbb::blocked_range<size_t>& range) {
|
[this, &cache_top_botom_regions](const tbb::blocked_range<size_t>& range) {
|
||||||
const SurfaceType surfaces_bottom[2] = { stBottom, stBottomBridge };
|
const std::initializer_list<SurfaceType> surfaces_bottom { stBottom, stBottomBridge };
|
||||||
const size_t num_regions = this->num_printing_regions();
|
const size_t num_regions = this->num_printing_regions();
|
||||||
for (size_t idx_layer = range.begin(); idx_layer < range.end(); ++ idx_layer) {
|
for (size_t idx_layer = range.begin(); idx_layer < range.end(); ++ idx_layer) {
|
||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
@ -1172,8 +1188,8 @@ void PrintObject::discover_vertical_shells()
|
|||||||
append(cache.top_surfaces, offset(layerm.slices().filter_by_type(stTop), min_perimeter_infill_spacing));
|
append(cache.top_surfaces, offset(layerm.slices().filter_by_type(stTop), min_perimeter_infill_spacing));
|
||||||
append(cache.top_surfaces, offset(layerm.fill_surfaces().filter_by_type(stTop), min_perimeter_infill_spacing));
|
append(cache.top_surfaces, offset(layerm.fill_surfaces().filter_by_type(stTop), min_perimeter_infill_spacing));
|
||||||
// Bottom surfaces.
|
// Bottom surfaces.
|
||||||
append(cache.bottom_surfaces, offset(layerm.slices().filter_by_types(surfaces_bottom, 2), min_perimeter_infill_spacing));
|
append(cache.bottom_surfaces, offset(layerm.slices().filter_by_types(surfaces_bottom), min_perimeter_infill_spacing));
|
||||||
append(cache.bottom_surfaces, offset(layerm.fill_surfaces().filter_by_types(surfaces_bottom, 2), min_perimeter_infill_spacing));
|
append(cache.bottom_surfaces, offset(layerm.fill_surfaces().filter_by_types(surfaces_bottom), min_perimeter_infill_spacing));
|
||||||
// Calculate the maximum perimeter offset as if the slice was extruded with a single extruder only.
|
// Calculate the maximum perimeter offset as if the slice was extruded with a single extruder only.
|
||||||
// First find the maxium number of perimeters per region slice.
|
// First find the maxium number of perimeters per region slice.
|
||||||
unsigned int perimeters = 0;
|
unsigned int perimeters = 0;
|
||||||
@ -1233,7 +1249,7 @@ void PrintObject::discover_vertical_shells()
|
|||||||
tbb::parallel_for(
|
tbb::parallel_for(
|
||||||
tbb::blocked_range<size_t>(0, num_layers, grain_size),
|
tbb::blocked_range<size_t>(0, num_layers, grain_size),
|
||||||
[this, region_id, &cache_top_botom_regions](const tbb::blocked_range<size_t>& range) {
|
[this, region_id, &cache_top_botom_regions](const tbb::blocked_range<size_t>& range) {
|
||||||
const SurfaceType surfaces_bottom[2] = { stBottom, stBottomBridge };
|
const std::initializer_list<SurfaceType> surfaces_bottom { stBottom, stBottomBridge };
|
||||||
for (size_t idx_layer = range.begin(); idx_layer < range.end(); ++ idx_layer) {
|
for (size_t idx_layer = range.begin(); idx_layer < range.end(); ++ idx_layer) {
|
||||||
m_print->throw_if_canceled();
|
m_print->throw_if_canceled();
|
||||||
Layer &layer = *m_layers[idx_layer];
|
Layer &layer = *m_layers[idx_layer];
|
||||||
@ -1244,8 +1260,8 @@ void PrintObject::discover_vertical_shells()
|
|||||||
cache.top_surfaces = offset(layerm.slices().filter_by_type(stTop), min_perimeter_infill_spacing);
|
cache.top_surfaces = offset(layerm.slices().filter_by_type(stTop), min_perimeter_infill_spacing);
|
||||||
append(cache.top_surfaces, offset(layerm.fill_surfaces().filter_by_type(stTop), min_perimeter_infill_spacing));
|
append(cache.top_surfaces, offset(layerm.fill_surfaces().filter_by_type(stTop), min_perimeter_infill_spacing));
|
||||||
// Bottom surfaces.
|
// Bottom surfaces.
|
||||||
cache.bottom_surfaces = offset(layerm.slices().filter_by_types(surfaces_bottom, 2), min_perimeter_infill_spacing);
|
cache.bottom_surfaces = offset(layerm.slices().filter_by_types(surfaces_bottom), min_perimeter_infill_spacing);
|
||||||
append(cache.bottom_surfaces, offset(layerm.fill_surfaces().filter_by_types(surfaces_bottom, 2), min_perimeter_infill_spacing));
|
append(cache.bottom_surfaces, offset(layerm.fill_surfaces().filter_by_types(surfaces_bottom), min_perimeter_infill_spacing));
|
||||||
// Holes over all regions. Only collect them once, they are valid for all region_id iterations.
|
// Holes over all regions. Only collect them once, they are valid for all region_id iterations.
|
||||||
if (cache.holes.empty()) {
|
if (cache.holes.empty()) {
|
||||||
for (size_t region_id = 0; region_id < layer.regions().size(); ++ region_id)
|
for (size_t region_id = 0; region_id < layer.regions().size(); ++ region_id)
|
||||||
@ -1275,8 +1291,8 @@ void PrintObject::discover_vertical_shells()
|
|||||||
const PrintRegionConfig ®ion_config = layerm->region().config();
|
const PrintRegionConfig ®ion_config = layerm->region().config();
|
||||||
|
|
||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
layerm->export_region_slices_to_svg_debug("4_discover_vertical_shells-initial");
|
layerm->export_region_slices_to_svg_debug("3_discover_vertical_shells-initial");
|
||||||
layerm->export_region_fill_surfaces_to_svg_debug("4_discover_vertical_shells-initial");
|
layerm->export_region_fill_surfaces_to_svg_debug("3_discover_vertical_shells-initial");
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
Flow solid_infill_flow = layerm->flow(frSolidInfill);
|
Flow solid_infill_flow = layerm->flow(frSolidInfill);
|
||||||
@ -1405,8 +1421,7 @@ void PrintObject::discover_vertical_shells()
|
|||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
// Trim the shells region by the internal & internal void surfaces.
|
// Trim the shells region by the internal & internal void surfaces.
|
||||||
const SurfaceType surfaceTypesInternal[] = { stInternal, stInternalVoid, stInternalSolid };
|
const Polygons polygonsInternal = to_polygons(layerm->fill_surfaces().filter_by_types({ stInternal, stInternalVoid, stInternalSolid }));
|
||||||
const Polygons polygonsInternal = to_polygons(layerm->fill_surfaces().filter_by_types(surfaceTypesInternal, 3));
|
|
||||||
shell = intersection(shell, polygonsInternal, ApplySafetyOffset::Yes);
|
shell = intersection(shell, polygonsInternal, ApplySafetyOffset::Yes);
|
||||||
polygons_append(shell, diff(polygonsInternal, holes));
|
polygons_append(shell, diff(polygonsInternal, holes));
|
||||||
if (shell.empty())
|
if (shell.empty())
|
||||||
@ -1472,8 +1487,7 @@ void PrintObject::discover_vertical_shells()
|
|||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
|
|
||||||
// Assign resulting internal surfaces to layer.
|
// Assign resulting internal surfaces to layer.
|
||||||
const SurfaceType surfaceTypesKeep[] = { stTop, stBottom, stBottomBridge };
|
layerm->m_fill_surfaces.keep_types({ stTop, stBottom, stBottomBridge });
|
||||||
layerm->m_fill_surfaces.keep_types(surfaceTypesKeep, sizeof(surfaceTypesKeep)/sizeof(SurfaceType));
|
|
||||||
layerm->m_fill_surfaces.append(new_internal, stInternal);
|
layerm->m_fill_surfaces.append(new_internal, stInternal);
|
||||||
layerm->m_fill_surfaces.append(new_internal_void, stInternalVoid);
|
layerm->m_fill_surfaces.append(new_internal_void, stInternalVoid);
|
||||||
layerm->m_fill_surfaces.append(new_internal_solid, stInternalSolid);
|
layerm->m_fill_surfaces.append(new_internal_solid, stInternalSolid);
|
||||||
@ -1485,8 +1499,8 @@ void PrintObject::discover_vertical_shells()
|
|||||||
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
#ifdef SLIC3R_DEBUG_SLICE_PROCESSING
|
||||||
for (size_t idx_layer = 0; idx_layer < m_layers.size(); ++idx_layer) {
|
for (size_t idx_layer = 0; idx_layer < m_layers.size(); ++idx_layer) {
|
||||||
LayerRegion *layerm = m_layers[idx_layer]->get_region(region_id);
|
LayerRegion *layerm = m_layers[idx_layer]->get_region(region_id);
|
||||||
layerm->export_region_slices_to_svg_debug("4_discover_vertical_shells-final");
|
layerm->export_region_slices_to_svg_debug("3_discover_vertical_shells-final");
|
||||||
layerm->export_region_fill_surfaces_to_svg_debug("4_discover_vertical_shells-final");
|
layerm->export_region_fill_surfaces_to_svg_debug("3_discover_vertical_shells-final");
|
||||||
}
|
}
|
||||||
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
#endif /* SLIC3R_DEBUG_SLICE_PROCESSING */
|
||||||
} // for each region
|
} // for each region
|
||||||
@ -1870,12 +1884,11 @@ void PrintObject::clip_fill_surfaces()
|
|||||||
for (LayerRegion *layerm : lower_layer->m_regions) {
|
for (LayerRegion *layerm : lower_layer->m_regions) {
|
||||||
if (layerm->region().config().fill_density.value == 0)
|
if (layerm->region().config().fill_density.value == 0)
|
||||||
continue;
|
continue;
|
||||||
SurfaceType internal_surface_types[] = { stInternal, stInternalVoid };
|
|
||||||
Polygons internal;
|
Polygons internal;
|
||||||
for (Surface &surface : layerm->m_fill_surfaces.surfaces)
|
for (Surface &surface : layerm->m_fill_surfaces.surfaces)
|
||||||
if (surface.surface_type == stInternal || surface.surface_type == stInternalVoid)
|
if (surface.surface_type == stInternal || surface.surface_type == stInternalVoid)
|
||||||
polygons_append(internal, std::move(surface.expolygon));
|
polygons_append(internal, std::move(surface.expolygon));
|
||||||
layerm->m_fill_surfaces.remove_types(internal_surface_types, 2);
|
layerm->m_fill_surfaces.remove_types({ stInternal, stInternalVoid });
|
||||||
layerm->m_fill_surfaces.append(intersection_ex(internal, upper_internal, ApplySafetyOffset::Yes), stInternal);
|
layerm->m_fill_surfaces.append(intersection_ex(internal, upper_internal, ApplySafetyOffset::Yes), stInternal);
|
||||||
layerm->m_fill_surfaces.append(diff_ex (internal, upper_internal, ApplySafetyOffset::Yes), stInternalVoid);
|
layerm->m_fill_surfaces.append(diff_ex (internal, upper_internal, ApplySafetyOffset::Yes), stInternalVoid);
|
||||||
// If there are voids it means that our internal infill is not adjacent to
|
// If there are voids it means that our internal infill is not adjacent to
|
||||||
@ -2058,8 +2071,7 @@ void PrintObject::discover_horizontal_shells()
|
|||||||
neighbor_layerm->m_fill_surfaces.append(internal, stInternal);
|
neighbor_layerm->m_fill_surfaces.append(internal, stInternal);
|
||||||
polygons_append(polygons_internal, to_polygons(std::move(internal)));
|
polygons_append(polygons_internal, to_polygons(std::move(internal)));
|
||||||
// assign top and bottom surfaces to layer
|
// assign top and bottom surfaces to layer
|
||||||
SurfaceType surface_types_solid[] = { stTop, stBottom, stBottomBridge };
|
backup.keep_types({ stTop, stBottom, stBottomBridge });
|
||||||
backup.keep_types(surface_types_solid, 3);
|
|
||||||
std::vector<SurfacesPtr> top_bottom_groups;
|
std::vector<SurfacesPtr> top_bottom_groups;
|
||||||
backup.group(&top_bottom_groups);
|
backup.group(&top_bottom_groups);
|
||||||
for (SurfacesPtr &group : top_bottom_groups)
|
for (SurfacesPtr &group : top_bottom_groups)
|
||||||
|
@ -33,40 +33,31 @@ class Surface
|
|||||||
public:
|
public:
|
||||||
SurfaceType surface_type;
|
SurfaceType surface_type;
|
||||||
ExPolygon expolygon;
|
ExPolygon expolygon;
|
||||||
double thickness; // in mm
|
double thickness { -1 }; // in mm
|
||||||
unsigned short thickness_layers; // in layers
|
unsigned short thickness_layers { 1 }; // in layers
|
||||||
double bridge_angle; // in radians, ccw, 0 = East, only 0+ (negative means undefined)
|
double bridge_angle { -1. }; // in radians, ccw, 0 = East, only 0+ (negative means undefined)
|
||||||
unsigned short extra_perimeters;
|
unsigned short extra_perimeters { 0 };
|
||||||
|
|
||||||
Surface(const Slic3r::Surface &rhs)
|
Surface(const Slic3r::Surface &rhs) :
|
||||||
: surface_type(rhs.surface_type), expolygon(rhs.expolygon),
|
surface_type(rhs.surface_type), expolygon(rhs.expolygon),
|
||||||
thickness(rhs.thickness), thickness_layers(rhs.thickness_layers),
|
thickness(rhs.thickness), thickness_layers(rhs.thickness_layers),
|
||||||
bridge_angle(rhs.bridge_angle), extra_perimeters(rhs.extra_perimeters)
|
bridge_angle(rhs.bridge_angle), extra_perimeters(rhs.extra_perimeters) {}
|
||||||
{};
|
Surface(SurfaceType surface_type, const ExPolygon &expolygon) :
|
||||||
|
surface_type(surface_type), expolygon(expolygon) {}
|
||||||
Surface(SurfaceType _surface_type, const ExPolygon &_expolygon)
|
Surface(const Surface &templ, const ExPolygon &expolygon) :
|
||||||
: surface_type(_surface_type), expolygon(_expolygon),
|
surface_type(templ.surface_type), expolygon(expolygon),
|
||||||
thickness(-1), thickness_layers(1), bridge_angle(-1), extra_perimeters(0)
|
thickness(templ.thickness), thickness_layers(templ.thickness_layers),
|
||||||
{};
|
bridge_angle(templ.bridge_angle), extra_perimeters(templ.extra_perimeters) {}
|
||||||
Surface(const Surface &other, const ExPolygon &_expolygon)
|
Surface(Surface &&rhs) :
|
||||||
: surface_type(other.surface_type), expolygon(_expolygon),
|
surface_type(rhs.surface_type), expolygon(std::move(rhs.expolygon)),
|
||||||
thickness(other.thickness), thickness_layers(other.thickness_layers),
|
|
||||||
bridge_angle(other.bridge_angle), extra_perimeters(other.extra_perimeters)
|
|
||||||
{};
|
|
||||||
Surface(Surface &&rhs)
|
|
||||||
: surface_type(rhs.surface_type), expolygon(std::move(rhs.expolygon)),
|
|
||||||
thickness(rhs.thickness), thickness_layers(rhs.thickness_layers),
|
thickness(rhs.thickness), thickness_layers(rhs.thickness_layers),
|
||||||
bridge_angle(rhs.bridge_angle), extra_perimeters(rhs.extra_perimeters)
|
bridge_angle(rhs.bridge_angle), extra_perimeters(rhs.extra_perimeters) {}
|
||||||
{};
|
Surface(SurfaceType surface_type, ExPolygon &&expolygon) :
|
||||||
Surface(SurfaceType _surface_type, ExPolygon &&_expolygon)
|
surface_type(surface_type), expolygon(std::move(expolygon)) {}
|
||||||
: surface_type(_surface_type), expolygon(std::move(_expolygon)),
|
Surface(const Surface &templ, ExPolygon &&expolygon) :
|
||||||
thickness(-1), thickness_layers(1), bridge_angle(-1), extra_perimeters(0)
|
surface_type(templ.surface_type), expolygon(std::move(expolygon)),
|
||||||
{};
|
thickness(templ.thickness), thickness_layers(templ.thickness_layers),
|
||||||
Surface(const Surface &other, ExPolygon &&_expolygon)
|
bridge_angle(templ.bridge_angle), extra_perimeters(templ.extra_perimeters) {}
|
||||||
: surface_type(other.surface_type), expolygon(std::move(_expolygon)),
|
|
||||||
thickness(other.thickness), thickness_layers(other.thickness_layers),
|
|
||||||
bridge_angle(other.bridge_angle), extra_perimeters(other.extra_perimeters)
|
|
||||||
{};
|
|
||||||
|
|
||||||
Surface& operator=(const Surface &rhs)
|
Surface& operator=(const Surface &rhs)
|
||||||
{
|
{
|
||||||
|
@ -51,16 +51,12 @@ SurfacesPtr SurfaceCollection::filter_by_type(const SurfaceType type) const
|
|||||||
return ss;
|
return ss;
|
||||||
}
|
}
|
||||||
|
|
||||||
SurfacesPtr SurfaceCollection::filter_by_types(const SurfaceType *types, int ntypes) const
|
SurfacesPtr SurfaceCollection::filter_by_types(std::initializer_list<SurfaceType> types) const
|
||||||
{
|
{
|
||||||
SurfacesPtr ss;
|
SurfacesPtr ss;
|
||||||
for (const Surface &surface : this->surfaces)
|
for (const Surface &surface : this->surfaces)
|
||||||
for (int i = 0; i < ntypes; ++ i) {
|
if (std::find(types.begin(), types.end(), surface.surface_type) != types.end())
|
||||||
if (surface.surface_type == types[i]) {
|
|
||||||
ss.push_back(&surface);
|
ss.push_back(&surface);
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return ss;
|
return ss;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -85,23 +81,15 @@ void SurfaceCollection::keep_type(const SurfaceType type)
|
|||||||
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
||||||
}
|
}
|
||||||
|
|
||||||
void SurfaceCollection::keep_types(const SurfaceType *types, int ntypes)
|
void SurfaceCollection::keep_types(std::initializer_list<SurfaceType> types)
|
||||||
{
|
{
|
||||||
size_t j = 0;
|
size_t j = 0;
|
||||||
for (size_t i = 0; i < surfaces.size(); ++ i) {
|
for (size_t i = 0; i < surfaces.size(); ++ i)
|
||||||
bool keep = false;
|
if (std::find(types.begin(), types.end(), surfaces[i].surface_type) != types.end()) {
|
||||||
for (int k = 0; k < ntypes; ++ k) {
|
|
||||||
if (surfaces[i].surface_type == types[k]) {
|
|
||||||
keep = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (keep) {
|
|
||||||
if (j < i)
|
if (j < i)
|
||||||
std::swap(surfaces[i], surfaces[j]);
|
std::swap(surfaces[i], surfaces[j]);
|
||||||
++ j;
|
++ j;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
if (j < surfaces.size())
|
if (j < surfaces.size())
|
||||||
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
||||||
}
|
}
|
||||||
@ -136,23 +124,15 @@ void SurfaceCollection::remove_type(const SurfaceType type, ExPolygons *polygons
|
|||||||
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
||||||
}
|
}
|
||||||
|
|
||||||
void SurfaceCollection::remove_types(const SurfaceType *types, int ntypes)
|
void SurfaceCollection::remove_types(std::initializer_list<SurfaceType> types)
|
||||||
{
|
{
|
||||||
size_t j = 0;
|
size_t j = 0;
|
||||||
for (size_t i = 0; i < surfaces.size(); ++ i) {
|
for (size_t i = 0; i < surfaces.size(); ++ i)
|
||||||
bool remove = false;
|
if (std::find(types.begin(), types.end(), surfaces[i].surface_type) == types.end()) {
|
||||||
for (int k = 0; k < ntypes; ++ k) {
|
|
||||||
if (surfaces[i].surface_type == types[k]) {
|
|
||||||
remove = true;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (! remove) {
|
|
||||||
if (j < i)
|
if (j < i)
|
||||||
std::swap(surfaces[i], surfaces[j]);
|
std::swap(surfaces[i], surfaces[j]);
|
||||||
++ j;
|
++ j;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
if (j < surfaces.size())
|
if (j < surfaces.size())
|
||||||
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
surfaces.erase(surfaces.begin() + j, surfaces.end());
|
||||||
}
|
}
|
||||||
|
@ -3,6 +3,7 @@
|
|||||||
|
|
||||||
#include "libslic3r.h"
|
#include "libslic3r.h"
|
||||||
#include "Surface.hpp"
|
#include "Surface.hpp"
|
||||||
|
#include <initializer_list>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
@ -27,11 +28,11 @@ public:
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
SurfacesPtr filter_by_type(const SurfaceType type) const;
|
SurfacesPtr filter_by_type(const SurfaceType type) const;
|
||||||
SurfacesPtr filter_by_types(const SurfaceType *types, int ntypes) const;
|
SurfacesPtr filter_by_types(std::initializer_list<SurfaceType> types) const;
|
||||||
void keep_type(const SurfaceType type);
|
void keep_type(const SurfaceType type);
|
||||||
void keep_types(const SurfaceType *types, int ntypes);
|
void keep_types(std::initializer_list<SurfaceType> types);
|
||||||
void remove_type(const SurfaceType type);
|
void remove_type(const SurfaceType type);
|
||||||
void remove_types(const SurfaceType *types, int ntypes);
|
void remove_types(std::initializer_list<SurfaceType> types);
|
||||||
void filter_by_type(SurfaceType type, Polygons *polygons) const;
|
void filter_by_type(SurfaceType type, Polygons *polygons) const;
|
||||||
void remove_type(const SurfaceType type, ExPolygons *polygons);
|
void remove_type(const SurfaceType type, ExPolygons *polygons);
|
||||||
void set_type(SurfaceType type) {
|
void set_type(SurfaceType type) {
|
||||||
|
@ -176,6 +176,21 @@ template<class T> size_t next_highest_power_of_2(T v,
|
|||||||
return next_highest_power_of_2(uint32_t(v));
|
return next_highest_power_of_2(uint32_t(v));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
template<class VectorType> void reserve_power_of_2(VectorType &vector, size_t n)
|
||||||
|
{
|
||||||
|
vector.reserve(next_highest_power_of_2(n));
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class VectorType> void reserve_more(VectorType &vector, size_t n)
|
||||||
|
{
|
||||||
|
vector.reserve(vector.size() + n);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class VectorType> void reserve_more_power_of_2(VectorType &vector, size_t n)
|
||||||
|
{
|
||||||
|
vector.reserve(next_highest_power_of_2(vector.size() + n));
|
||||||
|
}
|
||||||
|
|
||||||
template<typename INDEX_TYPE>
|
template<typename INDEX_TYPE>
|
||||||
inline INDEX_TYPE prev_idx_modulo(INDEX_TYPE idx, const INDEX_TYPE count)
|
inline INDEX_TYPE prev_idx_modulo(INDEX_TYPE idx, const INDEX_TYPE count)
|
||||||
{
|
{
|
||||||
|
@ -251,4 +251,34 @@ SCENARIO("Region expansion basics", "[RegionExpansion]") {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
GIVEN("square with hole, hole edge anchored") {
|
||||||
|
Polygon outer{ { -1 * ten, -1 * ten }, { 2 * ten, -1 * ten }, { 2 * ten, 2 * ten }, { -1 * ten, 2 * ten } };
|
||||||
|
Polygon hole { { 0, ten }, { ten, ten }, { ten, 0 }, { 0, 0 } };
|
||||||
|
Polygon anchor{ { 0, 0 }, { ten, 0 }, { ten, ten }, { 0, ten } };
|
||||||
|
ExPolygon boundary(outer);
|
||||||
|
boundary.holes = { hole };
|
||||||
|
|
||||||
|
WHEN("expanded") {
|
||||||
|
static constexpr const float expansion = scaled<float>(5.);
|
||||||
|
std::vector<Polygons> expanded = Algorithm::expand_expolygons({ ExPolygon{anchor} }, { boundary },
|
||||||
|
expansion,
|
||||||
|
scaled<float>(0.4), // expansion step
|
||||||
|
15); // max num steps
|
||||||
|
#if 0
|
||||||
|
SVG::export_expolygons(DEBUG_TEMP_DIR "square_with_hole_anchored-out.svg",
|
||||||
|
{ { { { ExPolygon{anchor} } }, { "anchor", "orange", 0.5f } },
|
||||||
|
{ { { boundary } }, { "boundary", "blue", 0.5f } },
|
||||||
|
{ { union_ex(expanded.front()) }, { "expanded", "red", "black", "", scaled<coord_t>(0.1f), 0.5f } } });
|
||||||
|
#endif
|
||||||
|
THEN("The anchor expands into a single region with a hole") {
|
||||||
|
REQUIRE(expanded.size() == 1);
|
||||||
|
REQUIRE(expanded.front().size() == 2);
|
||||||
|
}
|
||||||
|
THEN("The area of anchor is correct") {
|
||||||
|
double area_calculated = area(expanded.front());
|
||||||
|
double area_expected = double(expansion) * 4. * double(ten) + M_PI * sqr(expansion);
|
||||||
|
REQUIRE(is_approx(area_expected, area_calculated, sqr(scaled<double>(0.6))));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user