ENH: support hole compensation for Arachne
jira:NONE Signed-off-by: xun.zhang <xun.zhang@bambulab.com> Change-Id: Iaaca3a27f44e13049088480a9946117e984d5b5a
This commit is contained in:
parent
ce30dad82c
commit
cf00527ef0
|
@ -104,7 +104,7 @@ SkeletalTrapezoidation::node_t &SkeletalTrapezoidation::makeNode(const VD::verte
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments) {
|
void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments, const bool hole_compensation_flag) {
|
||||||
auto he_edge_it = vd_edge_to_he_edge.find(vd_edge.twin());
|
auto he_edge_it = vd_edge_to_he_edge.find(vd_edge.twin());
|
||||||
if (he_edge_it != vd_edge_to_he_edge.end())
|
if (he_edge_it != vd_edge_to_he_edge.end())
|
||||||
{ // Twin segment(s) have already been made
|
{ // Twin segment(s) have already been made
|
||||||
|
@ -128,7 +128,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_t
|
||||||
edge->twin = twin;
|
edge->twin = twin;
|
||||||
twin->twin = edge;
|
twin->twin = edge;
|
||||||
edge->from->incident_edge = edge;
|
edge->from->incident_edge = edge;
|
||||||
|
edge->data.setHoleCompensationFlag(hole_compensation_flag);
|
||||||
if (prev_edge)
|
if (prev_edge)
|
||||||
{
|
{
|
||||||
edge->prev = prev_edge;
|
edge->prev = prev_edge;
|
||||||
|
@ -192,6 +192,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_t
|
||||||
edge->from = v0;
|
edge->from = v0;
|
||||||
edge->to = v1;
|
edge->to = v1;
|
||||||
edge->from->incident_edge = edge;
|
edge->from->incident_edge = edge;
|
||||||
|
edge->data.setHoleCompensationFlag(hole_compensation_flag);
|
||||||
|
|
||||||
if (prev_edge)
|
if (prev_edge)
|
||||||
{
|
{
|
||||||
|
@ -373,13 +374,16 @@ bool SkeletalTrapezoidation::computePointCellRange(const VD::cell_type &cell, Po
|
||||||
SkeletalTrapezoidation::SkeletalTrapezoidation(const Polygons& polys, const BeadingStrategy& beading_strategy,
|
SkeletalTrapezoidation::SkeletalTrapezoidation(const Polygons& polys, const BeadingStrategy& beading_strategy,
|
||||||
double transitioning_angle, coord_t discretization_step_size,
|
double transitioning_angle, coord_t discretization_step_size,
|
||||||
coord_t transition_filter_dist, coord_t allowed_filter_deviation,
|
coord_t transition_filter_dist, coord_t allowed_filter_deviation,
|
||||||
coord_t beading_propagation_transition_dist
|
coord_t beading_propagation_transition_dist, bool enable_hole_compensation,
|
||||||
|
const std::vector<int>& hole_indices
|
||||||
): transitioning_angle(transitioning_angle),
|
): transitioning_angle(transitioning_angle),
|
||||||
discretization_step_size(discretization_step_size),
|
discretization_step_size(discretization_step_size),
|
||||||
transition_filter_dist(transition_filter_dist),
|
transition_filter_dist(transition_filter_dist),
|
||||||
allowed_filter_deviation(allowed_filter_deviation),
|
allowed_filter_deviation(allowed_filter_deviation),
|
||||||
beading_propagation_transition_dist(beading_propagation_transition_dist),
|
beading_propagation_transition_dist(beading_propagation_transition_dist),
|
||||||
beading_strategy(beading_strategy)
|
beading_strategy(beading_strategy),
|
||||||
|
enable_hole_compensation(enable_hole_compensation),
|
||||||
|
hole_indices(hole_indices)
|
||||||
{
|
{
|
||||||
constructFromPolygons(polys);
|
constructFromPolygons(polys);
|
||||||
}
|
}
|
||||||
|
@ -390,6 +394,8 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
|
||||||
this->outline = polys;
|
this->outline = polys;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
std::set<int> hole_indices_(this->hole_indices.begin(), this->hole_indices.end());
|
||||||
|
|
||||||
// Check self intersections.
|
// Check self intersections.
|
||||||
assert([&polys]() -> bool {
|
assert([&polys]() -> bool {
|
||||||
EdgeGrid::Grid grid;
|
EdgeGrid::Grid grid;
|
||||||
|
@ -436,10 +442,15 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
|
||||||
const VD::edge_type *ending_voronoi_edge = nullptr;
|
const VD::edge_type *ending_voronoi_edge = nullptr;
|
||||||
// Compute and store result in above variables
|
// Compute and store result in above variables
|
||||||
|
|
||||||
|
bool apply_hole_compensation = this->enable_hole_compensation;
|
||||||
|
|
||||||
if (cell.contains_point()) {
|
if (cell.contains_point()) {
|
||||||
const bool keep_going = computePointCellRange(cell, start_source_point, end_source_point, starting_voronoi_edge, ending_voronoi_edge, segments);
|
const bool keep_going = computePointCellRange(cell, start_source_point, end_source_point, starting_voronoi_edge, ending_voronoi_edge, segments);
|
||||||
if (!keep_going)
|
if (!keep_going)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
|
const PolygonsPointIndex source_point_idx = Geometry::VoronoiUtils::get_source_point_index(cell, segments.begin(), segments.end());
|
||||||
|
apply_hole_compensation &= hole_indices_.find(source_point_idx.poly_idx) != hole_indices_.end();
|
||||||
} else {
|
} else {
|
||||||
assert(cell.contains_segment());
|
assert(cell.contains_segment());
|
||||||
Geometry::SegmentCellRange<Point> cell_range = Geometry::VoronoiUtils::compute_segment_cell_range(cell, segments.cbegin(), segments.cend());
|
Geometry::SegmentCellRange<Point> cell_range = Geometry::VoronoiUtils::compute_segment_cell_range(cell, segments.cbegin(), segments.cend());
|
||||||
|
@ -448,6 +459,9 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
|
||||||
end_source_point = cell_range.segment_end_point;
|
end_source_point = cell_range.segment_end_point;
|
||||||
starting_voronoi_edge = cell_range.edge_begin;
|
starting_voronoi_edge = cell_range.edge_begin;
|
||||||
ending_voronoi_edge = cell_range.edge_end;
|
ending_voronoi_edge = cell_range.edge_end;
|
||||||
|
|
||||||
|
const Segment& source_segment = Geometry::VoronoiUtils::get_source_segment(cell, segments.cbegin(), segments.cend());
|
||||||
|
apply_hole_compensation &= hole_indices_.find(source_segment.poly_idx) != hole_indices_.end();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!starting_voronoi_edge || !ending_voronoi_edge) {
|
if (!starting_voronoi_edge || !ending_voronoi_edge) {
|
||||||
|
@ -458,7 +472,7 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
|
||||||
// Copy start to end edge to graph
|
// Copy start to end edge to graph
|
||||||
assert(Geometry::VoronoiUtils::is_in_range<coord_t>(*starting_voronoi_edge));
|
assert(Geometry::VoronoiUtils::is_in_range<coord_t>(*starting_voronoi_edge));
|
||||||
edge_t *prev_edge = nullptr;
|
edge_t *prev_edge = nullptr;
|
||||||
transferEdge(start_source_point, Geometry::VoronoiUtils::to_point(starting_voronoi_edge->vertex1()).cast<coord_t>(), *starting_voronoi_edge, prev_edge, start_source_point, end_source_point, segments);
|
transferEdge(start_source_point, Geometry::VoronoiUtils::to_point(starting_voronoi_edge->vertex1()).cast<coord_t>(), *starting_voronoi_edge, prev_edge, start_source_point, end_source_point, segments,apply_hole_compensation);
|
||||||
node_t *starting_node = vd_node_to_he_node[starting_voronoi_edge->vertex0()];
|
node_t *starting_node = vd_node_to_he_node[starting_voronoi_edge->vertex0()];
|
||||||
starting_node->data.distance_to_boundary = 0;
|
starting_node->data.distance_to_boundary = 0;
|
||||||
|
|
||||||
|
@ -470,11 +484,11 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
|
||||||
|
|
||||||
Point v1 = Geometry::VoronoiUtils::to_point(vd_edge->vertex0()).cast<coord_t>();
|
Point v1 = Geometry::VoronoiUtils::to_point(vd_edge->vertex0()).cast<coord_t>();
|
||||||
Point v2 = Geometry::VoronoiUtils::to_point(vd_edge->vertex1()).cast<coord_t>();
|
Point v2 = Geometry::VoronoiUtils::to_point(vd_edge->vertex1()).cast<coord_t>();
|
||||||
transferEdge(v1, v2, *vd_edge, prev_edge, start_source_point, end_source_point, segments);
|
transferEdge(v1, v2, *vd_edge, prev_edge, start_source_point, end_source_point, segments,apply_hole_compensation);
|
||||||
graph.makeRib(prev_edge, start_source_point, end_source_point, vd_edge->next() == ending_voronoi_edge);
|
graph.makeRib(prev_edge, start_source_point, end_source_point, vd_edge->next() == ending_voronoi_edge);
|
||||||
}
|
}
|
||||||
|
|
||||||
transferEdge(Geometry::VoronoiUtils::to_point(ending_voronoi_edge->vertex0()).cast<coord_t>(), end_source_point, *ending_voronoi_edge, prev_edge, start_source_point, end_source_point, segments);
|
transferEdge(Geometry::VoronoiUtils::to_point(ending_voronoi_edge->vertex0()).cast<coord_t>(), end_source_point, *ending_voronoi_edge, prev_edge, start_source_point, end_source_point, segments, apply_hole_compensation);
|
||||||
prev_edge->to->data.distance_to_boundary = 0;
|
prev_edge->to->data.distance_to_boundary = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1775,6 +1789,8 @@ void SkeletalTrapezoidation::generateJunctions(ptr_vector_t<BeadingPropagation>&
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool apply_hole_compensation = edge->data.getHoleCompensationFlag();
|
||||||
|
|
||||||
Beading* beading = &getOrCreateBeading(edge->to, node_beadings)->beading;
|
Beading* beading = &getOrCreateBeading(edge->to, node_beadings)->beading;
|
||||||
edge_junctions.emplace_back(std::make_shared<LineJunctions>());
|
edge_junctions.emplace_back(std::make_shared<LineJunctions>());
|
||||||
edge_.data.setExtrusionJunctions(edge_junctions.back()); // initialization
|
edge_.data.setExtrusionJunctions(edge_junctions.back()); // initialization
|
||||||
|
@ -1828,7 +1844,7 @@ void SkeletalTrapezoidation::generateJunctions(ptr_vector_t<BeadingPropagation>&
|
||||||
{ // Snap to start node if it is really close, in order to be able to see 3-way intersection later on more robustly
|
{ // Snap to start node if it is really close, in order to be able to see 3-way intersection later on more robustly
|
||||||
junction = a;
|
junction = a;
|
||||||
}
|
}
|
||||||
ret.emplace_back(junction, beading->bead_widths[junction_idx], junction_idx);
|
ret.emplace_back(ExtrusionJunction(junction, beading->bead_widths[junction_idx], junction_idx, apply_hole_compensation));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -2113,7 +2129,7 @@ void SkeletalTrapezoidation::generateLocalMaximaSingleBeads()
|
||||||
constexpr coord_t n_segments = 6;
|
constexpr coord_t n_segments = 6;
|
||||||
for (coord_t segment = 0; segment < n_segments; segment++) {
|
for (coord_t segment = 0; segment < n_segments; segment++) {
|
||||||
float a = 2.0 * M_PI / n_segments * segment;
|
float a = 2.0 * M_PI / n_segments * segment;
|
||||||
line.junctions.emplace_back(node.p + Point(r * cos(a), r * sin(a)), width, inset_index);
|
line.junctions.emplace_back(ExtrusionJunction(node.p + Point(r * cos(a), r * sin(a)), width, inset_index, false));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -60,6 +60,8 @@ class SkeletalTrapezoidation
|
||||||
template<typename T>
|
template<typename T>
|
||||||
using ptr_vector_t = std::vector<std::shared_ptr<T>>;
|
using ptr_vector_t = std::vector<std::shared_ptr<T>>;
|
||||||
|
|
||||||
|
bool enable_hole_compensation;
|
||||||
|
std::vector<int> hole_indices;
|
||||||
double transitioning_angle; //!< How pointy a region should be before we apply the method. Equals 180* - limit_bisector_angle
|
double transitioning_angle; //!< How pointy a region should be before we apply the method. Equals 180* - limit_bisector_angle
|
||||||
coord_t discretization_step_size; //!< approximate size of segments when parabolic VD edges get discretized (and vertex-vertex edges)
|
coord_t discretization_step_size; //!< approximate size of segments when parabolic VD edges get discretized (and vertex-vertex edges)
|
||||||
coord_t transition_filter_dist; //!< Filter transition mids (i.e. anchors) closer together than this
|
coord_t transition_filter_dist; //!< Filter transition mids (i.e. anchors) closer together than this
|
||||||
|
@ -108,7 +110,9 @@ public:
|
||||||
, coord_t discretization_step_size
|
, coord_t discretization_step_size
|
||||||
, coord_t transition_filter_dist
|
, coord_t transition_filter_dist
|
||||||
, coord_t allowed_filter_deviation
|
, coord_t allowed_filter_deviation
|
||||||
, coord_t beading_propagation_transition_dist);
|
, coord_t beading_propagation_transition_dist
|
||||||
|
, bool enable_hole_compensation
|
||||||
|
, const std::vector<int>& hole_indices);
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* A skeletal graph through the polygons that we need to fill with beads.
|
* A skeletal graph through the polygons that we need to fill with beads.
|
||||||
|
@ -180,7 +184,7 @@ protected:
|
||||||
* Transfer an edge from the VD to the HE and perform discretization of parabolic edges (and vertex-vertex edges)
|
* Transfer an edge from the VD to the HE and perform discretization of parabolic edges (and vertex-vertex edges)
|
||||||
* \p prev_edge serves as input and output. May be null as input.
|
* \p prev_edge serves as input and output. May be null as input.
|
||||||
*/
|
*/
|
||||||
void transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments);
|
void transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments, const bool hole_compensation_flag);
|
||||||
|
|
||||||
/*!
|
/*!
|
||||||
* Discretize a Voronoi edge that represents the medial axis of a vertex-
|
* Discretize a Voronoi edge that represents the medial axis of a vertex-
|
||||||
|
|
|
@ -110,7 +110,18 @@ public:
|
||||||
return extrusion_junctions.lock();
|
return extrusion_junctions.lock();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setHoleCompensationFlag(bool enabled)
|
||||||
|
{
|
||||||
|
apply_hole_compensation = enabled;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool getHoleCompensationFlag() const
|
||||||
|
{
|
||||||
|
return apply_hole_compensation;
|
||||||
|
}
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
bool apply_hole_compensation{ false };
|
||||||
Central is_central; //! whether the edge is significant; whether the source segments have a sharp angle; -1 is unknown
|
Central is_central; //! whether the edge is significant; whether the source segments have a sharp angle; -1 is unknown
|
||||||
|
|
||||||
std::weak_ptr<std::list<TransitionMiddle>> transitions;
|
std::weak_ptr<std::list<TransitionMiddle>> transitions;
|
||||||
|
|
|
@ -327,8 +327,10 @@ void SkeletalTrapezoidationGraph::makeRib(edge_t*& prev_edge, Point start_source
|
||||||
|
|
||||||
edges.emplace_front(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::EXTRA_VD));
|
edges.emplace_front(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::EXTRA_VD));
|
||||||
edge_t* forth_edge = &edges.front();
|
edge_t* forth_edge = &edges.front();
|
||||||
|
forth_edge->data.setHoleCompensationFlag(prev_edge->data.getHoleCompensationFlag());
|
||||||
edges.emplace_front(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::EXTRA_VD));
|
edges.emplace_front(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::EXTRA_VD));
|
||||||
edge_t* back_edge = &edges.front();
|
edge_t* back_edge = &edges.front();
|
||||||
|
back_edge->data.setHoleCompensationFlag(prev_edge->data.getHoleCompensationFlag());
|
||||||
|
|
||||||
prev_edge->next = forth_edge;
|
prev_edge->next = forth_edge;
|
||||||
forth_edge->prev = prev_edge;
|
forth_edge->prev = prev_edge;
|
||||||
|
@ -352,6 +354,8 @@ std::pair<SkeletalTrapezoidationGraph::edge_t*, SkeletalTrapezoidationGraph::edg
|
||||||
|
|
||||||
Point p = mid_node->p;
|
Point p = mid_node->p;
|
||||||
|
|
||||||
|
bool apply_hole_compensation = edge.data.getHoleCompensationFlag();
|
||||||
|
|
||||||
const Line source_segment = getSource(edge);
|
const Line source_segment = getSource(edge);
|
||||||
Point px;
|
Point px;
|
||||||
source_segment.distance_to_squared(p, &px);
|
source_segment.distance_to_squared(p, &px);
|
||||||
|
@ -372,6 +376,11 @@ std::pair<SkeletalTrapezoidationGraph::edge_t*, SkeletalTrapezoidationGraph::edg
|
||||||
edges.emplace_back(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::TRANSITION_END));
|
edges.emplace_back(SkeletalTrapezoidationEdge(SkeletalTrapezoidationEdge::EdgeType::TRANSITION_END));
|
||||||
edge_t* inward_edge = &edges.back();
|
edge_t* inward_edge = &edges.back();
|
||||||
|
|
||||||
|
first->data.setHoleCompensationFlag(apply_hole_compensation);
|
||||||
|
second->data.setHoleCompensationFlag(apply_hole_compensation);
|
||||||
|
outward_edge->data.setHoleCompensationFlag(apply_hole_compensation);
|
||||||
|
inward_edge->data.setHoleCompensationFlag(apply_hole_compensation);
|
||||||
|
|
||||||
if (edge_before)
|
if (edge_before)
|
||||||
{
|
{
|
||||||
edge_before->next = first;
|
edge_before->next = first;
|
||||||
|
|
|
@ -41,6 +41,12 @@ WallToolPaths::WallToolPaths(const Polygons& outline, const coord_t bead_width_0
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void WallToolPaths::EnableHoleCompensation(bool enable_, const std::vector<int>& hole_indices_)
|
||||||
|
{
|
||||||
|
enable_hole_compensation = enable_;
|
||||||
|
hole_indices = hole_indices_;
|
||||||
|
}
|
||||||
|
|
||||||
void simplify(Polygon &thiss, const int64_t smallest_line_segment_squared, const int64_t allowed_error_distance_squared)
|
void simplify(Polygon &thiss, const int64_t smallest_line_segment_squared, const int64_t allowed_error_distance_squared)
|
||||||
{
|
{
|
||||||
if (thiss.size() < 3) {
|
if (thiss.size() < 3) {
|
||||||
|
@ -437,6 +443,13 @@ const std::vector<VariableWidthLines> &WallToolPaths::generate()
|
||||||
if (this->inset_count < 1)
|
if (this->inset_count < 1)
|
||||||
return toolpaths;
|
return toolpaths;
|
||||||
|
|
||||||
|
size_t original_outline_size = outline.size();
|
||||||
|
bool outline_size_change = false;
|
||||||
|
// Lambda for checking size changes
|
||||||
|
auto update_outline_size_change = [original_outline_size, &outline_size_change](const Polygons& polys) {
|
||||||
|
outline_size_change |= (original_outline_size != polys.size());
|
||||||
|
};
|
||||||
|
|
||||||
const coord_t smallest_segment = Slic3r::Arachne::meshfix_maximum_resolution;
|
const coord_t smallest_segment = Slic3r::Arachne::meshfix_maximum_resolution;
|
||||||
const coord_t allowed_distance = Slic3r::Arachne::meshfix_maximum_deviation;
|
const coord_t allowed_distance = Slic3r::Arachne::meshfix_maximum_deviation;
|
||||||
const coord_t epsilon_offset = (allowed_distance / 2) - 1;
|
const coord_t epsilon_offset = (allowed_distance / 2) - 1;
|
||||||
|
@ -446,26 +459,37 @@ const std::vector<VariableWidthLines> &WallToolPaths::generate()
|
||||||
// Simplify outline for boost::voronoi consumption. Absolutely no self intersections or near-self intersections allowed:
|
// Simplify outline for boost::voronoi consumption. Absolutely no self intersections or near-self intersections allowed:
|
||||||
// TODO: Open question: Does this indeed fix all (or all-but-one-in-a-million) cases for manifold but otherwise possibly complex polygons?
|
// TODO: Open question: Does this indeed fix all (or all-but-one-in-a-million) cases for manifold but otherwise possibly complex polygons?
|
||||||
Polygons prepared_outline = offset(offset(offset(outline, -epsilon_offset), epsilon_offset * 2), -epsilon_offset);
|
Polygons prepared_outline = offset(offset(offset(outline, -epsilon_offset), epsilon_offset * 2), -epsilon_offset);
|
||||||
simplify(prepared_outline, smallest_segment, allowed_distance);
|
update_outline_size_change(prepared_outline);
|
||||||
fixSelfIntersections(epsilon_offset, prepared_outline);
|
|
||||||
removeDegenerateVerts(prepared_outline);
|
// Helper function for applying a sequence of operations with size change tracking
|
||||||
removeColinearEdges(prepared_outline, 0.005);
|
auto process_with_size_check = [&](auto&& operation) {
|
||||||
|
operation();
|
||||||
|
update_outline_size_change(prepared_outline);
|
||||||
|
};
|
||||||
|
|
||||||
|
process_with_size_check([&] { simplify(prepared_outline, smallest_segment, allowed_distance);});
|
||||||
|
process_with_size_check([&] { fixSelfIntersections(epsilon_offset, prepared_outline); });
|
||||||
|
process_with_size_check([&] { removeDegenerateVerts(prepared_outline); });
|
||||||
|
process_with_size_check([&] { removeColinearEdges(prepared_outline, 0.005); });
|
||||||
// Removing collinear edges may introduce self intersections, so we need to fix them again
|
// Removing collinear edges may introduce self intersections, so we need to fix them again
|
||||||
fixSelfIntersections(epsilon_offset, prepared_outline);
|
process_with_size_check([&] { fixSelfIntersections(epsilon_offset, prepared_outline); });
|
||||||
removeDegenerateVerts(prepared_outline);
|
process_with_size_check([&] { removeDegenerateVerts(prepared_outline); });
|
||||||
removeSmallAreas(prepared_outline, small_area_length * small_area_length, false);
|
process_with_size_check([&] { removeSmallAreas(prepared_outline, small_area_length * small_area_length, false); });
|
||||||
|
|
||||||
// The functions above could produce intersecting polygons that could cause a crash inside Arachne.
|
// The functions above could produce intersecting polygons that could cause a crash inside Arachne.
|
||||||
// Applying Clipper union should be enough to get rid of this issue.
|
// Applying Clipper union should be enough to get rid of this issue.
|
||||||
// Clipper union also fixed an issue in Arachne that in post-processing Voronoi diagram, some edges
|
// Clipper union also fixed an issue in Arachne that in post-processing Voronoi diagram, some edges
|
||||||
// didn't have twin edges. (a non-planar Voronoi diagram probably caused this).
|
// didn't have twin edges. (a non-planar Voronoi diagram probably caused this).
|
||||||
prepared_outline = union_(prepared_outline);
|
prepared_outline = union_(prepared_outline);
|
||||||
|
update_outline_size_change(prepared_outline);
|
||||||
|
|
||||||
if (area(prepared_outline) <= 0) {
|
if (area(prepared_outline) <= 0) {
|
||||||
assert(toolpaths.empty());
|
assert(toolpaths.empty());
|
||||||
return toolpaths;
|
return toolpaths;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool apply_hole_compensation = this->enable_hole_compensation && !outline_size_change;
|
||||||
|
|
||||||
const float external_perimeter_extrusion_width = Flow::rounded_rectangle_extrusion_width_from_spacing(unscale<float>(bead_width_0), float(this->layer_height));
|
const float external_perimeter_extrusion_width = Flow::rounded_rectangle_extrusion_width_from_spacing(unscale<float>(bead_width_0), float(this->layer_height));
|
||||||
const float perimeter_extrusion_width = Flow::rounded_rectangle_extrusion_width_from_spacing(unscale<float>(bead_width_x), float(this->layer_height));
|
const float perimeter_extrusion_width = Flow::rounded_rectangle_extrusion_width_from_spacing(unscale<float>(bead_width_x), float(this->layer_height));
|
||||||
|
|
||||||
|
@ -501,7 +525,9 @@ const std::vector<VariableWidthLines> &WallToolPaths::generate()
|
||||||
discretization_step_size,
|
discretization_step_size,
|
||||||
transition_filter_dist,
|
transition_filter_dist,
|
||||||
allowed_filter_deviation,
|
allowed_filter_deviation,
|
||||||
wall_transition_length
|
wall_transition_length,
|
||||||
|
apply_hole_compensation,
|
||||||
|
hole_indices
|
||||||
);
|
);
|
||||||
wall_maker.generateToolpaths(toolpaths);
|
wall_maker.generateToolpaths(toolpaths);
|
||||||
|
|
||||||
|
|
|
@ -44,6 +44,7 @@ public:
|
||||||
*/
|
*/
|
||||||
WallToolPaths(const Polygons& outline, coord_t bead_width_0, coord_t bead_width_x, size_t inset_count, coord_t wall_0_inset, coordf_t layer_height, const WallToolPathsParams ¶ms);
|
WallToolPaths(const Polygons& outline, coord_t bead_width_0, coord_t bead_width_x, size_t inset_count, coord_t wall_0_inset, coordf_t layer_height, const WallToolPathsParams ¶ms);
|
||||||
|
|
||||||
|
void EnableHoleCompensation(bool enable, const std::vector<int>& hole_indices_);
|
||||||
/*!
|
/*!
|
||||||
* Generates the Toolpaths
|
* Generates the Toolpaths
|
||||||
* \return A reference to the newly create ToolPaths
|
* \return A reference to the newly create ToolPaths
|
||||||
|
@ -131,6 +132,9 @@ private:
|
||||||
std::vector<VariableWidthLines> toolpaths; //<! The generated toolpaths
|
std::vector<VariableWidthLines> toolpaths; //<! The generated toolpaths
|
||||||
Polygons inner_contour; //<! The inner contour of the generated toolpaths
|
Polygons inner_contour; //<! The inner contour of the generated toolpaths
|
||||||
const WallToolPathsParams m_params;
|
const WallToolPathsParams m_params;
|
||||||
|
private:
|
||||||
|
bool enable_hole_compensation{ false };
|
||||||
|
std::vector<int> hole_indices;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace Slic3r::Arachne
|
} // namespace Slic3r::Arachne
|
||||||
|
|
|
@ -10,9 +10,10 @@ bool ExtrusionJunction::operator ==(const ExtrusionJunction& other) const
|
||||||
{
|
{
|
||||||
return p == other.p
|
return p == other.p
|
||||||
&& w == other.w
|
&& w == other.w
|
||||||
&& perimeter_index == other.perimeter_index;
|
&& perimeter_index == other.perimeter_index
|
||||||
|
&& hole_compensation_flag == other.hole_compensation_flag;
|
||||||
}
|
}
|
||||||
|
|
||||||
ExtrusionJunction::ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index) : p(p), w(w), perimeter_index(perimeter_index) {}
|
ExtrusionJunction::ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index, const bool compensation_flag) : p(p), w(w), perimeter_index(perimeter_index),hole_compensation_flag(compensation_flag) {}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -18,6 +18,10 @@ namespace Slic3r::Arachne
|
||||||
*/
|
*/
|
||||||
struct ExtrusionJunction
|
struct ExtrusionJunction
|
||||||
{
|
{
|
||||||
|
/*!
|
||||||
|
* whether the junction is generated from a hole that needs compensation
|
||||||
|
*/
|
||||||
|
bool hole_compensation_flag;
|
||||||
/*!
|
/*!
|
||||||
* The position of the centreline of the path when it reaches this junction.
|
* The position of the centreline of the path when it reaches this junction.
|
||||||
* This is the position that should end up in the g-code eventually.
|
* This is the position that should end up in the g-code eventually.
|
||||||
|
@ -37,7 +41,7 @@ struct ExtrusionJunction
|
||||||
*/
|
*/
|
||||||
size_t perimeter_index;
|
size_t perimeter_index;
|
||||||
|
|
||||||
ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index);
|
ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index, const bool hole_compensation);
|
||||||
|
|
||||||
bool operator==(const ExtrusionJunction& other) const;
|
bool operator==(const ExtrusionJunction& other) const;
|
||||||
};
|
};
|
||||||
|
|
|
@ -147,7 +147,7 @@ void ExtrusionLine::simplify(const int64_t smallest_line_segment_squared, const
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
// New point seems like a valid one.
|
// New point seems like a valid one.
|
||||||
const ExtrusionJunction new_to_add = ExtrusionJunction(intersection_point, current.w, current.perimeter_index);
|
const ExtrusionJunction new_to_add = ExtrusionJunction(intersection_point, current.w, current.perimeter_index, current.hole_compensation_flag);
|
||||||
// If there was a previous point added, remove it.
|
// If there was a previous point added, remove it.
|
||||||
if(!new_junctions.empty())
|
if(!new_junctions.empty())
|
||||||
{
|
{
|
||||||
|
@ -232,6 +232,20 @@ int64_t ExtrusionLine::calculateExtrusionAreaDeviationError(ExtrusionJunction A,
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool ExtrusionLine::shouldApplyHoleCompensation(const double threshold) const
|
||||||
|
{
|
||||||
|
int64_t total_length = 0;
|
||||||
|
int64_t marked_length = 0;
|
||||||
|
for (size_t idx = 1; idx < junctions.size(); ++idx) {
|
||||||
|
int64_t length = (junctions[idx].p - junctions[idx - 1].p).cast<int64_t>().norm();
|
||||||
|
total_length += length;
|
||||||
|
int marked_rate = (int)(junctions[idx].hole_compensation_flag) + (int)(junctions[idx - 1].hole_compensation_flag);
|
||||||
|
marked_length += length * marked_rate / 2;
|
||||||
|
}
|
||||||
|
double rate = (double)(marked_length) / (double)(total_length);
|
||||||
|
return rate > threshold;
|
||||||
|
}
|
||||||
|
|
||||||
bool ExtrusionLine::is_contour() const
|
bool ExtrusionLine::is_contour() const
|
||||||
{
|
{
|
||||||
if (!this->is_closed)
|
if (!this->is_closed)
|
||||||
|
|
|
@ -190,6 +190,8 @@ struct ExtrusionLine
|
||||||
* */
|
* */
|
||||||
static int64_t calculateExtrusionAreaDeviationError(ExtrusionJunction A, ExtrusionJunction B, ExtrusionJunction C, coord_t& weighted_average_width);
|
static int64_t calculateExtrusionAreaDeviationError(ExtrusionJunction A, ExtrusionJunction B, ExtrusionJunction C, coord_t& weighted_average_width);
|
||||||
|
|
||||||
|
bool shouldApplyHoleCompensation(const double threshold = 0.8) const;
|
||||||
|
|
||||||
bool is_contour() const;
|
bool is_contour() const;
|
||||||
|
|
||||||
double area() const;
|
double area() const;
|
||||||
|
|
|
@ -7,6 +7,7 @@
|
||||||
|
|
||||||
namespace Slic3r::Geometry {
|
namespace Slic3r::Geometry {
|
||||||
|
|
||||||
|
using PolygonsSegmentIndexIt = std::vector<Arachne::PolygonsSegmentIndex>::iterator;
|
||||||
using PolygonsSegmentIndexConstIt = std::vector<Arachne::PolygonsSegmentIndex>::const_iterator;
|
using PolygonsSegmentIndexConstIt = std::vector<Arachne::PolygonsSegmentIndex>::const_iterator;
|
||||||
using LinesIt = Lines::iterator;
|
using LinesIt = Lines::iterator;
|
||||||
using ColoredLinesIt = ColoredLines::iterator;
|
using ColoredLinesIt = ColoredLines::iterator;
|
||||||
|
@ -29,6 +30,7 @@ template SegmentCellRange<Point> VoronoiUtils::compute_segment_cell_range(const
|
||||||
template SegmentCellRange<Point> VoronoiUtils::compute_segment_cell_range(const VoronoiDiagram::cell_type &, PolygonsSegmentIndexConstIt, PolygonsSegmentIndexConstIt);
|
template SegmentCellRange<Point> VoronoiUtils::compute_segment_cell_range(const VoronoiDiagram::cell_type &, PolygonsSegmentIndexConstIt, PolygonsSegmentIndexConstIt);
|
||||||
template Points VoronoiUtils::discretize_parabola(const Point &, const Arachne::PolygonsSegmentIndex &, const Point &, const Point &, coord_t, float);
|
template Points VoronoiUtils::discretize_parabola(const Point &, const Arachne::PolygonsSegmentIndex &, const Point &, const Point &, coord_t, float);
|
||||||
template Arachne::PolygonsPointIndex VoronoiUtils::get_source_point_index(const VoronoiDiagram::cell_type &, PolygonsSegmentIndexConstIt, PolygonsSegmentIndexConstIt);
|
template Arachne::PolygonsPointIndex VoronoiUtils::get_source_point_index(const VoronoiDiagram::cell_type &, PolygonsSegmentIndexConstIt, PolygonsSegmentIndexConstIt);
|
||||||
|
template Arachne::PolygonsPointIndex VoronoiUtils::get_source_point_index(const VoronoiDiagram::cell_type &, PolygonsSegmentIndexIt, PolygonsSegmentIndexIt);
|
||||||
|
|
||||||
template<typename SegmentIterator>
|
template<typename SegmentIterator>
|
||||||
typename boost::polygon::enable_if<
|
typename boost::polygon::enable_if<
|
||||||
|
|
|
@ -103,12 +103,13 @@ static void fuzzy_extrusion_line(Arachne::ExtrusionLine& ext_lines, double fuzzy
|
||||||
const double range_random_point_dist = fuzzy_skin_point_dist / 2.;
|
const double range_random_point_dist = fuzzy_skin_point_dist / 2.;
|
||||||
double dist_left_over = double(rand()) * (min_dist_between_points / 2) / double(RAND_MAX); // the distance to be traversed on the line before making the first new point
|
double dist_left_over = double(rand()) * (min_dist_between_points / 2) / double(RAND_MAX); // the distance to be traversed on the line before making the first new point
|
||||||
|
|
||||||
|
// do not apply hole compensation in fuzzy skin mode
|
||||||
auto* p0 = &ext_lines.front();
|
auto* p0 = &ext_lines.front();
|
||||||
std::vector<Arachne::ExtrusionJunction> out;
|
std::vector<Arachne::ExtrusionJunction> out;
|
||||||
out.reserve(ext_lines.size());
|
out.reserve(ext_lines.size());
|
||||||
for (auto& p1 : ext_lines) {
|
for (auto& p1 : ext_lines) {
|
||||||
if (p0->p == p1.p) { // Connect endpoints.
|
if (p0->p == p1.p) { // Connect endpoints.
|
||||||
out.emplace_back(p1.p, p1.w, p1.perimeter_index);
|
out.emplace_back(p1.p, p1.w, p1.perimeter_index, false);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -119,7 +120,7 @@ static void fuzzy_extrusion_line(Arachne::ExtrusionLine& ext_lines, double fuzzy
|
||||||
double dist_last_point = dist_left_over + p0p1_size * 2.;
|
double dist_last_point = dist_left_over + p0p1_size * 2.;
|
||||||
for (double p0pa_dist = dist_left_over; p0pa_dist < p0p1_size; p0pa_dist += min_dist_between_points + double(rand()) * range_random_point_dist / double(RAND_MAX)) {
|
for (double p0pa_dist = dist_left_over; p0pa_dist < p0p1_size; p0pa_dist += min_dist_between_points + double(rand()) * range_random_point_dist / double(RAND_MAX)) {
|
||||||
double r = double(rand()) * (fuzzy_skin_thickness * 2.) / double(RAND_MAX) - fuzzy_skin_thickness;
|
double r = double(rand()) * (fuzzy_skin_thickness * 2.) / double(RAND_MAX) - fuzzy_skin_thickness;
|
||||||
out.emplace_back(p0->p + (p0p1 * (p0pa_dist / p0p1_size) + perp(p0p1).cast<double>().normalized() * r).cast<coord_t>(), p1.w, p1.perimeter_index);
|
out.emplace_back(p0->p + (p0p1 * (p0pa_dist / p0p1_size) + perp(p0p1).cast<double>().normalized() * r).cast<coord_t>(), p1.w, p1.perimeter_index, false);
|
||||||
dist_last_point = p0pa_dist;
|
dist_last_point = p0pa_dist;
|
||||||
}
|
}
|
||||||
dist_left_over = p0p1_size - dist_last_point;
|
dist_left_over = p0p1_size - dist_last_point;
|
||||||
|
@ -128,7 +129,7 @@ static void fuzzy_extrusion_line(Arachne::ExtrusionLine& ext_lines, double fuzzy
|
||||||
|
|
||||||
while (out.size() < 3) {
|
while (out.size() < 3) {
|
||||||
size_t point_idx = ext_lines.size() - 2;
|
size_t point_idx = ext_lines.size() - 2;
|
||||||
out.emplace_back(ext_lines[point_idx].p, ext_lines[point_idx].w, ext_lines[point_idx].perimeter_index);
|
out.emplace_back(ext_lines[point_idx].p, ext_lines[point_idx].w, ext_lines[point_idx].perimeter_index,false);
|
||||||
if (point_idx == 0)
|
if (point_idx == 0)
|
||||||
break;
|
break;
|
||||||
--point_idx;
|
--point_idx;
|
||||||
|
@ -1070,6 +1071,8 @@ static ExtrusionEntityCollection traverse_extrusions(const PerimeterGenerator& p
|
||||||
extrusion_paths_append(paths, *extrusion, role, is_external ? perimeter_generator.ext_perimeter_flow : perimeter_generator.perimeter_flow);
|
extrusion_paths_append(paths, *extrusion, role, is_external ? perimeter_generator.ext_perimeter_flow : perimeter_generator.perimeter_flow);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool apply_hole_compensation = extrusion->shouldApplyHoleCompensation();
|
||||||
|
|
||||||
// Append paths to collection.
|
// Append paths to collection.
|
||||||
if (!paths.empty()) {
|
if (!paths.empty()) {
|
||||||
if (extrusion->is_closed) {
|
if (extrusion->is_closed) {
|
||||||
|
@ -1086,6 +1089,11 @@ static ExtrusionEntityCollection traverse_extrusions(const PerimeterGenerator& p
|
||||||
}
|
}
|
||||||
assert(extrusion_loop.paths.front().first_point() == extrusion_loop.paths.back().last_point());
|
assert(extrusion_loop.paths.front().first_point() == extrusion_loop.paths.back().last_point());
|
||||||
|
|
||||||
|
if (apply_hole_compensation) {
|
||||||
|
for (auto& path : extrusion_loop.paths)
|
||||||
|
path.set_customize_flag(CustomizeFlag::cfCircleCompensation);
|
||||||
|
extrusion_loop.set_customize_flag(CustomizeFlag::cfCircleCompensation);
|
||||||
|
}
|
||||||
extrusion_coll.append(std::move(extrusion_loop));
|
extrusion_coll.append(std::move(extrusion_loop));
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
|
@ -1108,6 +1116,11 @@ static ExtrusionEntityCollection traverse_extrusions(const PerimeterGenerator& p
|
||||||
multi_path.paths.emplace_back(std::move(*it_path));
|
multi_path.paths.emplace_back(std::move(*it_path));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (apply_hole_compensation) {
|
||||||
|
for (auto& path : multi_path.paths)
|
||||||
|
path.set_customize_flag(CustomizeFlag::cfCircleCompensation);
|
||||||
|
multi_path.set_customize_flag(CustomizeFlag::cfCircleCompensation);
|
||||||
|
}
|
||||||
extrusion_coll.append(ExtrusionMultiPath(std::move(multi_path)));
|
extrusion_coll.append(ExtrusionMultiPath(std::move(multi_path)));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1120,6 +1133,20 @@ static ExtrusionEntityCollection traverse_extrusions(const PerimeterGenerator& p
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static Polygons to_polygons_with_flag(const ExPolygon& src, const bool contour_flag, const std::vector<int>& holes_flag, std::vector<int>& flags_out)
|
||||||
|
{
|
||||||
|
Polygons polygons;
|
||||||
|
polygons.reserve(src.num_contours());
|
||||||
|
polygons.push_back(src.contour);
|
||||||
|
polygons.insert(polygons.end(), src.holes.begin(), src.holes.end());
|
||||||
|
flags_out.reserve(holes_flag.size() + 1);
|
||||||
|
if(contour_flag == true)
|
||||||
|
flags_out.emplace_back(0);
|
||||||
|
for (size_t idx = 0; idx < holes_flag.size(); ++idx)
|
||||||
|
flags_out.emplace_back(holes_flag[idx] + 1);
|
||||||
|
return polygons;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void PerimeterGenerator::process_classic()
|
void PerimeterGenerator::process_classic()
|
||||||
{
|
{
|
||||||
|
@ -1781,8 +1808,19 @@ void PerimeterGenerator::process_arachne()
|
||||||
// detect how many perimeters must be generated for this island
|
// detect how many perimeters must be generated for this island
|
||||||
int loop_number = this->config->wall_loops + surface.extra_perimeters - 1; // 0-indexed loops
|
int loop_number = this->config->wall_loops + surface.extra_perimeters - 1; // 0-indexed loops
|
||||||
|
|
||||||
|
bool apply_circle_compensation = true;
|
||||||
|
|
||||||
ExPolygons last = offset_ex(surface.expolygon.simplify_p(surface_simplify_resolution), -float(ext_perimeter_width / 2. - ext_perimeter_spacing / 2.));
|
ExPolygons last = offset_ex(surface.expolygon.simplify_p(surface_simplify_resolution), -float(ext_perimeter_width / 2. - ext_perimeter_spacing / 2.));
|
||||||
Polygons last_p = to_polygons(last);
|
int new_size = std::accumulate(last.begin(), last.end(), 0, [](int prev, const ExPolygon& expoly) { return prev + expoly.num_contours(); });
|
||||||
|
if (last.size() != 1 || new_size != surface.expolygon.num_contours())
|
||||||
|
apply_circle_compensation = false;
|
||||||
|
|
||||||
|
std::vector<int> circle_poly_indices;
|
||||||
|
Polygons last_p;
|
||||||
|
if (apply_circle_compensation)
|
||||||
|
last_p = to_polygons_with_flag(last.front(), surface.counter_circle_compensation, surface.holes_circle_compensation, circle_poly_indices);
|
||||||
|
else
|
||||||
|
last_p = to_polygons(last);
|
||||||
|
|
||||||
// check whether to activate one wall mode
|
// check whether to activate one wall mode
|
||||||
if (generate_one_wall && !generate_one_wall_by_first_layer)
|
if (generate_one_wall && !generate_one_wall_by_first_layer)
|
||||||
|
@ -1829,6 +1867,10 @@ void PerimeterGenerator::process_arachne()
|
||||||
coord_t real_loop_number = generate_one_wall ? 1 : loop_number + 1;
|
coord_t real_loop_number = generate_one_wall ? 1 : loop_number + 1;
|
||||||
|
|
||||||
Arachne::WallToolPaths wallToolPaths(last_p, ext_perimeter_spacing, perimeter_spacing, real_loop_number, 0, layer_height, input_params);
|
Arachne::WallToolPaths wallToolPaths(last_p, ext_perimeter_spacing, perimeter_spacing, real_loop_number, 0, layer_height, input_params);
|
||||||
|
|
||||||
|
if (apply_circle_compensation)
|
||||||
|
wallToolPaths.EnableHoleCompensation(true, circle_poly_indices);
|
||||||
|
|
||||||
std::vector<Arachne::VariableWidthLines> perimeters = wallToolPaths.getToolPaths();
|
std::vector<Arachne::VariableWidthLines> perimeters = wallToolPaths.getToolPaths();
|
||||||
ExPolygons infill_contour = union_ex(wallToolPaths.getInnerContour());
|
ExPolygons infill_contour = union_ex(wallToolPaths.getInnerContour());
|
||||||
#ifdef ARACHNE_DEBUG
|
#ifdef ARACHNE_DEBUG
|
||||||
|
|
Loading…
Reference in New Issue