Merge branch 'master' into fs_emboss
# Conflicts: # src/libslic3r/AABBTreeLines.hpp # src/libslic3r/ExPolygon.hpp # tests/libslic3r/test_aabbindirect.cpp
This commit is contained in:
commit
e340fa6abe
15 changed files with 1046 additions and 842 deletions
|
@ -519,7 +519,7 @@ namespace detail {
|
|||
const VectorType origin;
|
||||
|
||||
inline VectorType closest_point_to_origin(size_t primitive_index,
|
||||
ScalarType& squared_distance){
|
||||
ScalarType& squared_distance) const {
|
||||
const auto &triangle = this->faces[primitive_index];
|
||||
VectorType closest_point = closest_point_to_triangle<VectorType>(origin,
|
||||
this->vertices[triangle(0)].template cast<ScalarType>(),
|
||||
|
@ -613,6 +613,37 @@ namespace detail {
|
|||
return up_sqr_d;
|
||||
}
|
||||
|
||||
template<typename IndexedPrimitivesDistancerType, typename Scalar>
|
||||
static inline void indexed_primitives_within_distance_squared_recurisve(const IndexedPrimitivesDistancerType &distancer,
|
||||
size_t node_idx,
|
||||
Scalar squared_distance_limit,
|
||||
std::vector<size_t> &found_primitives_indices)
|
||||
{
|
||||
const auto &node = distancer.tree.node(node_idx);
|
||||
assert(node.is_valid());
|
||||
if (node.is_leaf()) {
|
||||
Scalar sqr_dist;
|
||||
distancer.closest_point_to_origin(node.idx, sqr_dist);
|
||||
if (sqr_dist < squared_distance_limit) { found_primitives_indices.push_back(node.idx); }
|
||||
} else {
|
||||
size_t left_node_idx = node_idx * 2 + 1;
|
||||
size_t right_node_idx = left_node_idx + 1;
|
||||
const auto &node_left = distancer.tree.node(left_node_idx);
|
||||
const auto &node_right = distancer.tree.node(right_node_idx);
|
||||
assert(node_left.is_valid());
|
||||
assert(node_right.is_valid());
|
||||
|
||||
if (node_left.bbox.squaredExteriorDistance(distancer.origin) < squared_distance_limit) {
|
||||
indexed_primitives_within_distance_squared_recurisve(distancer, left_node_idx, squared_distance_limit,
|
||||
found_primitives_indices);
|
||||
}
|
||||
if (node_right.bbox.squaredExteriorDistance(distancer.origin) < squared_distance_limit) {
|
||||
indexed_primitives_within_distance_squared_recurisve(distancer, right_node_idx, squared_distance_limit,
|
||||
found_primitives_indices);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
|
||||
// Build a balanced AABB Tree over an indexed triangles set, balancing the tree
|
||||
|
@ -799,6 +830,33 @@ inline bool is_any_triangle_in_radius(
|
|||
return hit_point.allFinite();
|
||||
}
|
||||
|
||||
// Returns all triangles within the given radius limit
|
||||
template<typename VertexType, typename IndexedFaceType, typename TreeType, typename VectorType>
|
||||
inline std::vector<size_t> all_triangles_in_radius(
|
||||
// Indexed triangle set - 3D vertices.
|
||||
const std::vector<VertexType> &vertices,
|
||||
// Indexed triangle set - triangular faces, references to vertices.
|
||||
const std::vector<IndexedFaceType> &faces,
|
||||
// AABBTreeIndirect::Tree over vertices & faces, bounding boxes built with the accuracy of vertices.
|
||||
const TreeType &tree,
|
||||
// Point to which the distances on the indexed triangle set is searched for.
|
||||
const VectorType &point,
|
||||
//Square of maximum distance in which triangles are searched for
|
||||
typename VectorType::Scalar max_distance_squared)
|
||||
{
|
||||
auto distancer = detail::IndexedTriangleSetDistancer<VertexType, IndexedFaceType, TreeType, VectorType>
|
||||
{ vertices, faces, tree, point };
|
||||
|
||||
if(tree.empty())
|
||||
{
|
||||
return {};
|
||||
}
|
||||
|
||||
std::vector<size_t> found_triangles{};
|
||||
detail::indexed_primitives_within_distance_squared_recurisve(distancer, size_t(0), max_distance_squared, found_triangles);
|
||||
return found_triangles;
|
||||
}
|
||||
|
||||
|
||||
// Traverse the tree and return the index of an entity whose bounding box
|
||||
// contains a given point. Returns size_t(-1) when the point is outside.
|
||||
|
|
|
@ -1,8 +1,12 @@
|
|||
#ifndef SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
||||
#define SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
||||
|
||||
#include "Utils.hpp"
|
||||
#include "libslic3r.h"
|
||||
#include "libslic3r/AABBTreeIndirect.hpp"
|
||||
#include "libslic3r/Line.hpp"
|
||||
#include <type_traits>
|
||||
#include <vector>
|
||||
|
||||
namespace Slic3r {
|
||||
|
||||
|
@ -23,17 +27,17 @@ struct IndexedLinesDistancer {
|
|||
const VectorType origin;
|
||||
|
||||
inline VectorType closest_point_to_origin(size_t primitive_index,
|
||||
ScalarType &squared_distance) {
|
||||
VectorType nearest_point;
|
||||
ScalarType &squared_distance) const {
|
||||
Vec<LineType::Dim, typename LineType::Scalar> nearest_point;
|
||||
const LineType &line = lines[primitive_index];
|
||||
squared_distance = line_alg::distance_to_squared(line, origin, &nearest_point);
|
||||
return nearest_point;
|
||||
squared_distance = line_alg::distance_to_squared(line, origin.template cast<typename LineType::Scalar>(), &nearest_point);
|
||||
return nearest_point.template cast<ScalarType>();
|
||||
}
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
// Build a balanced AABB Tree over a vector of float lines, balancing the tree
|
||||
// Build a balanced AABB Tree over a vector of lines, balancing the tree
|
||||
// on centroids of the lines.
|
||||
// Epsilon is applied to the bounding boxes of the AABB Tree to cope with numeric inaccuracies
|
||||
// during tree traversal.
|
||||
|
@ -41,7 +45,7 @@ template<typename LineType>
|
|||
inline AABBTreeIndirect::Tree<2, typename LineType::Scalar> build_aabb_tree_over_indexed_lines(
|
||||
const std::vector<LineType> &lines,
|
||||
//FIXME do we want to apply an epsilon?
|
||||
const float eps = 0)
|
||||
const double eps = 0)
|
||||
{
|
||||
using TreeType = AABBTreeIndirect::Tree<2, typename LineType::Scalar>;
|
||||
// using CoordType = typename TreeType::CoordType;
|
||||
|
@ -85,29 +89,100 @@ inline AABBTreeIndirect::Tree<2, typename LineType::Scalar> build_aabb_tree_over
|
|||
}
|
||||
|
||||
// Finding a closest line, its closest point and squared distance to the closest point
|
||||
// Returns squared distance to the closest point or -1 if the input is empty
|
||||
// Returns squared distance to the closest point or -1 if the input is empty.
|
||||
// or no closer point than max_sq_dist
|
||||
template<typename LineType, typename TreeType, typename VectorType,
|
||||
typename Scalar = typename VectorType::Scalar>
|
||||
inline typename VectorType::Scalar squared_distance_to_indexed_lines(
|
||||
const std::vector<LineType> &lines,
|
||||
const TreeType &tree,
|
||||
const VectorType &point,
|
||||
size_t &hit_idx_out,
|
||||
Eigen::PlainObjectBase<VectorType> &hit_point_out,
|
||||
Scalar max_sqr_dist = std::numeric_limits<Scalar>::infinity())
|
||||
template<typename LineType, typename TreeType, typename VectorType, typename Scalar = typename VectorType::Scalar>
|
||||
inline typename Scalar squared_distance_to_indexed_lines(const std::vector<LineType> &lines,
|
||||
const TreeType &tree,
|
||||
const VectorType &point,
|
||||
size_t &hit_idx_out,
|
||||
Eigen::PlainObjectBase<VectorType> &hit_point_out,
|
||||
Scalar max_sqr_dist = std::numeric_limits<Scalar>::infinity())
|
||||
{
|
||||
if (tree.empty()) return Scalar(-1);
|
||||
auto distancer = detail::IndexedLinesDistancer<LineType, TreeType, VectorType>
|
||||
{ lines, tree, point };
|
||||
hit_idx_out = std::numeric_limits<size_t>::max();
|
||||
Scalar distance = AABBTreeIndirect::detail::squared_distance_to_indexed_primitives_recursive(
|
||||
auto distancer = detail::IndexedLinesDistancer<LineType, TreeType, VectorType>{lines, tree, point};
|
||||
return AABBTreeIndirect::detail::squared_distance_to_indexed_primitives_recursive(
|
||||
distancer, size_t(0), Scalar(0), max_sqr_dist, hit_idx_out, hit_point_out);
|
||||
if (hit_idx_out == std::numeric_limits<size_t>::max()) return Scalar(-1);
|
||||
return distance;
|
||||
}
|
||||
|
||||
// Returns all lines within the given radius limit
|
||||
template<typename LineType, typename TreeType, typename VectorType>
|
||||
inline std::vector<size_t> all_lines_in_radius(const std::vector<LineType> &lines,
|
||||
const TreeType &tree,
|
||||
const VectorType &point,
|
||||
typename VectorType::Scalar max_distance_squared)
|
||||
{
|
||||
auto distancer = detail::IndexedLinesDistancer<LineType, TreeType, VectorType>{lines, tree, point};
|
||||
|
||||
if (tree.empty()) { return {}; }
|
||||
|
||||
std::vector<size_t> found_lines{};
|
||||
AABBTreeIndirect::detail::indexed_primitives_within_distance_squared_recurisve(distancer, size_t(0), max_distance_squared, found_lines);
|
||||
return found_lines;
|
||||
}
|
||||
}
|
||||
|
||||
template<typename LineType> class LinesDistancer
|
||||
{
|
||||
private:
|
||||
std::vector<LineType> lines;
|
||||
using Scalar = typename LineType::Scalar;
|
||||
using Floating = typename std::conditional<std::is_floating_point<Scalar>::value, Scalar, double>::type;
|
||||
AABBTreeIndirect::Tree<2, Scalar> tree;
|
||||
|
||||
public:
|
||||
explicit LinesDistancer(const std::vector<LineType> &lines) : lines(lines)
|
||||
{
|
||||
tree = AABBTreeLines::build_aabb_tree_over_indexed_lines(this->lines);
|
||||
}
|
||||
|
||||
// negative sign means inside
|
||||
std::tuple<Floating, size_t, Vec<2, Floating>> signed_distance_from_lines_extra(const Vec<2, Scalar> &point) const
|
||||
{
|
||||
size_t nearest_line_index_out = size_t(-1);
|
||||
Vec<2, Floating> nearest_point_out = Vec<2, Floating>::Zero();
|
||||
Vec<2, Floating> p = point.template cast<Floating>();
|
||||
auto distance = AABBTreeLines::squared_distance_to_indexed_lines(lines, tree, p, nearest_line_index_out, nearest_point_out);
|
||||
|
||||
if (distance < 0) { return {std::numeric_limits<Floating>::infinity(), nearest_line_index_out, nearest_point_out}; }
|
||||
distance = sqrt(distance);
|
||||
const LineType &line = lines[nearest_line_index_out];
|
||||
Vec<2, Floating> v1 = (line.b - line.a).template cast<Floating>();
|
||||
Vec<2, Floating> v2 = (point - line.a).template cast<Floating>();
|
||||
auto d1 = (v1.x() * v2.y()) - (v1.y() * v2.x());
|
||||
|
||||
LineType second_line = line;
|
||||
if ((line.a.template cast<Floating>() - nearest_point_out).squaredNorm() < SCALED_EPSILON) {
|
||||
second_line = lines[prev_idx_modulo(nearest_line_index_out, lines.size())];
|
||||
} else {
|
||||
second_line = lines[next_idx_modulo(nearest_line_index_out, lines.size())];
|
||||
}
|
||||
v1 = (second_line.b - second_line.a).template cast<Floating>();
|
||||
v2 = (point - second_line.a).template cast<Floating>();
|
||||
auto d2 = (v1.x() * v2.y()) - (v1.y() * v2.x());
|
||||
|
||||
auto d = abs(d1) > abs(d2) ? d1 : d2;
|
||||
|
||||
if (d > 0.0) { distance *= -1.0; }
|
||||
|
||||
return {distance, nearest_line_index_out, nearest_point_out};
|
||||
}
|
||||
|
||||
Floating signed_distance_from_lines(const Vec<2, typename LineType::Scalar> &point) const
|
||||
{
|
||||
auto [dist, idx, np] = signed_distance_from_lines_extra(point);
|
||||
return dist;
|
||||
}
|
||||
|
||||
std::vector<size_t> all_lines_in_radius(const Vec<2, typename LineType::Scalar> &point, Floating radius)
|
||||
{
|
||||
return all_lines_in_radius(this->lines, this->tree, point, radius * radius);
|
||||
}
|
||||
|
||||
const LineType &get_line(size_t line_idx) const { return lines[line_idx]; }
|
||||
|
||||
const std::vector<LineType> &get_lines() const { return lines; }
|
||||
};
|
||||
|
||||
}} // namespace Slic3r::AABBTreeLines
|
||||
|
||||
#endif /* SRC_LIBSLIC3R_AABBTREELINES_HPP_ */
|
||||
|
|
|
@ -19,6 +19,7 @@ set(SLIC3R_SOURCES
|
|||
pchheader.hpp
|
||||
AStar.hpp
|
||||
AABBTreeIndirect.hpp
|
||||
AABBTreeLines.hpp
|
||||
AABBMesh.hpp
|
||||
AABBMesh.cpp
|
||||
BoundingBox.cpp
|
||||
|
@ -274,7 +275,6 @@ set(SLIC3R_SOURCES
|
|||
TriangleMeshSlicer.hpp
|
||||
MeshSplitImpl.hpp
|
||||
TriangulateWall.hpp
|
||||
TriangulateWall.cpp
|
||||
utils.cpp
|
||||
Utils.hpp
|
||||
Time.cpp
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#ifndef slic3r_ExPolygon_hpp_
|
||||
#define slic3r_ExPolygon_hpp_
|
||||
|
||||
#include "Point.hpp"
|
||||
#include "libslic3r.h"
|
||||
#include "Polygon.hpp"
|
||||
#include "Polyline.hpp"
|
||||
|
@ -134,6 +135,28 @@ inline Lines to_lines(const ExPolygons &src)
|
|||
return lines;
|
||||
}
|
||||
|
||||
inline std::vector<Linef> to_linesf(const ExPolygons &src)
|
||||
{
|
||||
size_t n_lines = 0;
|
||||
for (ExPolygons::const_iterator it_expoly = src.begin(); it_expoly != src.end(); ++ it_expoly) {
|
||||
n_lines += it_expoly->contour.points.size();
|
||||
for (size_t i = 0; i < it_expoly->holes.size(); ++ i)
|
||||
n_lines += it_expoly->holes[i].points.size();
|
||||
}
|
||||
std::vector<Linef> lines;
|
||||
lines.reserve(n_lines);
|
||||
for (ExPolygons::const_iterator it_expoly = src.begin(); it_expoly != src.end(); ++ it_expoly) {
|
||||
for (size_t i = 0; i <= it_expoly->holes.size(); ++ i) {
|
||||
const Points &points = ((i == 0) ? it_expoly->contour : it_expoly->holes[i - 1]).points;
|
||||
for (Points::const_iterator it = points.begin(); it != points.end()-1; ++it)
|
||||
lines.push_back(Linef(unscaled(*it), unscaled(*(it + 1))));
|
||||
lines.push_back(Linef(unscaled(points.back()), unscaled(points.front())));
|
||||
}
|
||||
}
|
||||
return lines;
|
||||
}
|
||||
|
||||
|
||||
inline Points to_points(const ExPolygons &src)
|
||||
{
|
||||
Points points;
|
||||
|
|
|
@ -1,6 +1,7 @@
|
|||
#include "SeamPlacer.hpp"
|
||||
|
||||
#include "Color.hpp"
|
||||
#include "Polygon.hpp"
|
||||
#include "PrintConfig.hpp"
|
||||
#include "tbb/parallel_for.h"
|
||||
#include "tbb/blocked_range.h"
|
||||
|
@ -995,49 +996,6 @@ void pick_random_seam_point(const std::vector<SeamCandidate> &perimeter_points,
|
|||
perimeter.finalized = true;
|
||||
}
|
||||
|
||||
class PerimeterDistancer {
|
||||
std::vector<Linef> lines;
|
||||
AABBTreeIndirect::Tree<2, double> tree;
|
||||
|
||||
public:
|
||||
PerimeterDistancer(const Layer *layer) {
|
||||
ExPolygons layer_outline = layer->lslices;
|
||||
for (const ExPolygon &island : layer_outline) {
|
||||
assert(island.contour.is_counter_clockwise());
|
||||
for (const auto &line : island.contour.lines()) {
|
||||
lines.emplace_back(unscale(line.a), unscale(line.b));
|
||||
}
|
||||
for (const Polygon &hole : island.holes) {
|
||||
assert(hole.is_clockwise());
|
||||
for (const auto &line : hole.lines()) {
|
||||
lines.emplace_back(unscale(line.a), unscale(line.b));
|
||||
}
|
||||
}
|
||||
}
|
||||
tree = AABBTreeLines::build_aabb_tree_over_indexed_lines(lines);
|
||||
}
|
||||
|
||||
float distance_from_perimeter(const Vec2f &point) const {
|
||||
Vec2d p = point.cast<double>();
|
||||
size_t hit_idx_out { };
|
||||
Vec2d hit_point_out = Vec2d::Zero();
|
||||
auto distance = AABBTreeLines::squared_distance_to_indexed_lines(lines, tree, p, hit_idx_out, hit_point_out);
|
||||
if (distance < 0) {
|
||||
return std::numeric_limits<float>::max();
|
||||
}
|
||||
|
||||
distance = sqrt(distance);
|
||||
const Linef &line = lines[hit_idx_out];
|
||||
Vec2d v1 = line.b - line.a;
|
||||
Vec2d v2 = p - line.a;
|
||||
if ((v1.x() * v2.y()) - (v1.y() * v2.x()) > 0.0) {
|
||||
distance *= -1;
|
||||
}
|
||||
return distance;
|
||||
}
|
||||
}
|
||||
;
|
||||
|
||||
} // namespace SeamPlacerImpl
|
||||
|
||||
// Parallel process and extract each perimeter polygon of the given print object.
|
||||
|
@ -1089,13 +1047,14 @@ void SeamPlacer::calculate_candidates_visibility(const PrintObject *po,
|
|||
|
||||
void SeamPlacer::calculate_overhangs_and_layer_embedding(const PrintObject *po) {
|
||||
using namespace SeamPlacerImpl;
|
||||
using PerimeterDistancer = AABBTreeLines::LinesDistancer<Linef>;
|
||||
|
||||
std::vector<PrintObjectSeamData::LayerSeams> &layers = m_seam_per_object[po].layers;
|
||||
tbb::parallel_for(tbb::blocked_range<size_t>(0, layers.size()),
|
||||
[po, &layers](tbb::blocked_range<size_t> r) {
|
||||
std::unique_ptr<PerimeterDistancer> prev_layer_distancer;
|
||||
if (r.begin() > 0) { // previous layer exists
|
||||
prev_layer_distancer = std::make_unique<PerimeterDistancer>(po->layers()[r.begin() - 1]);
|
||||
prev_layer_distancer = std::make_unique<PerimeterDistancer>(to_linesf(po->layers()[r.begin() - 1]->lslices));
|
||||
}
|
||||
|
||||
for (size_t layer_idx = r.begin(); layer_idx < r.end(); ++layer_idx) {
|
||||
|
@ -1106,12 +1065,12 @@ void SeamPlacer::calculate_overhangs_and_layer_embedding(const PrintObject *po)
|
|||
}
|
||||
};
|
||||
bool should_compute_layer_embedding = regions_with_perimeter > 1;
|
||||
std::unique_ptr<PerimeterDistancer> current_layer_distancer = std::make_unique<PerimeterDistancer>(po->layers()[layer_idx]);
|
||||
std::unique_ptr<PerimeterDistancer> current_layer_distancer = std::make_unique<PerimeterDistancer>(to_linesf(po->layers()[layer_idx]->lslices));
|
||||
|
||||
for (SeamCandidate &perimeter_point : layers[layer_idx].points) {
|
||||
Vec2f point = Vec2f { perimeter_point.position.head<2>() };
|
||||
if (prev_layer_distancer.get() != nullptr) {
|
||||
perimeter_point.overhang = prev_layer_distancer->distance_from_perimeter(point)
|
||||
perimeter_point.overhang = prev_layer_distancer->signed_distance_from_lines(point.cast<double>())
|
||||
+ 0.6f * perimeter_point.perimeter.flow_width
|
||||
- tan(SeamPlacer::overhang_angle_threshold)
|
||||
* po->layers()[layer_idx]->height;
|
||||
|
@ -1120,7 +1079,7 @@ void SeamPlacer::calculate_overhangs_and_layer_embedding(const PrintObject *po)
|
|||
}
|
||||
|
||||
if (should_compute_layer_embedding) { // search for embedded perimeter points (points hidden inside the print ,e.g. multimaterial join, best position for seam)
|
||||
perimeter_point.embedded_distance = current_layer_distancer->distance_from_perimeter(point)
|
||||
perimeter_point.embedded_distance = current_layer_distancer->signed_distance_from_lines(point.cast<double>())
|
||||
+ 0.6f * perimeter_point.perimeter.flow_width;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -1,6 +1,9 @@
|
|||
#include "SupportSpotsGenerator.hpp"
|
||||
|
||||
#include "ExPolygon.hpp"
|
||||
#include "ExtrusionEntity.hpp"
|
||||
#include "Line.hpp"
|
||||
#include "Polygon.hpp"
|
||||
#include "tbb/parallel_for.h"
|
||||
#include "tbb/blocked_range.h"
|
||||
#include "tbb/blocked_range2d.h"
|
||||
|
@ -70,46 +73,10 @@ SupportPoint::SupportPoint(const Vec3f &position, float force, float spot_radius
|
|||
position(position), force(force), spot_radius(spot_radius), direction(direction) {
|
||||
}
|
||||
|
||||
class LinesDistancer {
|
||||
private:
|
||||
std::vector<ExtrusionLine> lines;
|
||||
AABBTreeIndirect::Tree<2, float> tree;
|
||||
|
||||
public:
|
||||
explicit LinesDistancer(const std::vector<ExtrusionLine> &lines) :
|
||||
lines(lines) {
|
||||
tree = AABBTreeLines::build_aabb_tree_over_indexed_lines(this->lines);
|
||||
}
|
||||
|
||||
// negative sign means inside
|
||||
float signed_distance_from_lines(const Vec2f &point, size_t &nearest_line_index_out,
|
||||
Vec2f &nearest_point_out) const {
|
||||
auto distance = AABBTreeLines::squared_distance_to_indexed_lines(lines, tree, point, nearest_line_index_out,
|
||||
nearest_point_out);
|
||||
if (distance < 0)
|
||||
return std::numeric_limits<float>::infinity();
|
||||
|
||||
distance = sqrt(distance);
|
||||
const ExtrusionLine &line = lines[nearest_line_index_out];
|
||||
Vec2f v1 = line.b - line.a;
|
||||
Vec2f v2 = point - line.a;
|
||||
if ((v1.x() * v2.y()) - (v1.y() * v2.x()) > 0.0) {
|
||||
distance *= -1;
|
||||
}
|
||||
return distance;
|
||||
}
|
||||
|
||||
const ExtrusionLine& get_line(size_t line_idx) const {
|
||||
return lines[line_idx];
|
||||
}
|
||||
|
||||
const std::vector<ExtrusionLine>& get_lines() const {
|
||||
return lines;
|
||||
}
|
||||
};
|
||||
|
||||
static const size_t NULL_ISLAND = std::numeric_limits<size_t>::max();
|
||||
|
||||
using LD = AABBTreeLines::LinesDistancer<ExtrusionLine>;
|
||||
|
||||
class PixelGrid {
|
||||
Vec2f pixel_size;
|
||||
Vec2f origin;
|
||||
|
@ -387,7 +354,7 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
|
|||
std::vector<ExtrusionLine> &checked_lines_out,
|
||||
float layer_z,
|
||||
const LayerRegion *layer_region,
|
||||
const LinesDistancer &prev_layer_lines,
|
||||
const LD &prev_layer_lines,
|
||||
Issues &issues,
|
||||
const Params ¶ms) {
|
||||
|
||||
|
@ -429,11 +396,7 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
|
|||
// malformation in concave angles does not happen
|
||||
malformation_acc.add_angle(std::max(0.0f, curr_angle));
|
||||
|
||||
size_t nearest_line_idx;
|
||||
Vec2f nearest_point;
|
||||
float dist_from_prev_layer = prev_layer_lines.signed_distance_from_lines(current_line.b, nearest_line_idx,
|
||||
nearest_point);
|
||||
|
||||
auto [dist_from_prev_layer, nearest_line_idx, nearest_point] = prev_layer_lines.signed_distance_from_lines_extra(current_line.b);
|
||||
if (fabs(dist_from_prev_layer) < overhang_dist) {
|
||||
bridging_acc.reset();
|
||||
} else {
|
||||
|
@ -491,53 +454,18 @@ std::tuple<LayerIslands, PixelGrid> reckon_islands(
|
|||
}
|
||||
}
|
||||
|
||||
std::vector<LinesDistancer> islands; // these search trees will be used to determine to which island does the extrusion belong.
|
||||
std::vector<std::vector<size_t>> island_extrusions; //final assigment of each extrusion to an island.
|
||||
// initliaze the search from external perimeters - at the beginning, there is island candidate for each external perimeter.
|
||||
// some of them will disappear (e.g. holes)
|
||||
for (size_t e = 0; e < extrusions.size(); ++e) {
|
||||
if (layer_lines[extrusions[e].first].origin_entity->is_loop() &&
|
||||
layer_lines[extrusions[e].first].is_external_perimeter()) {
|
||||
std::vector<ExtrusionLine> copy(extrusions[e].second - extrusions[e].first);
|
||||
for (size_t ex_line_idx = extrusions[e].first; ex_line_idx < extrusions[e].second; ++ex_line_idx) {
|
||||
copy[ex_line_idx - extrusions[e].first] = layer_lines[ex_line_idx];
|
||||
}
|
||||
islands.emplace_back(copy);
|
||||
island_extrusions.push_back( { e });
|
||||
}
|
||||
std::vector<AABBTreeLines::LinesDistancer<Line>> islands; // these search trees will be used to determine to which island does the extrusion belong.
|
||||
for (const ExPolygon& island : layer->lslices) {
|
||||
islands.emplace_back(to_lines(island));
|
||||
}
|
||||
|
||||
// backup code if islands not found
|
||||
// If that happens, just make the first extrusion into island - it may be wrong, but it won't crash.
|
||||
if (islands.empty() && !extrusions.empty()) {
|
||||
std::vector<ExtrusionLine> copy(extrusions[0].second - extrusions[0].first);
|
||||
for (size_t ex_line_idx = extrusions[0].first; ex_line_idx < extrusions[0].second; ++ex_line_idx) {
|
||||
copy[ex_line_idx - extrusions[0].first] = layer_lines[ex_line_idx];
|
||||
}
|
||||
islands.emplace_back(copy);
|
||||
island_extrusions.push_back( { 0 });
|
||||
}
|
||||
|
||||
// assign non external extrusions to islands
|
||||
for (size_t e = 0; e < extrusions.size(); ++e) {
|
||||
if (!layer_lines[extrusions[e].first].origin_entity->is_loop() ||
|
||||
!layer_lines[extrusions[e].first].is_external_perimeter()) {
|
||||
bool island_assigned = false;
|
||||
for (size_t i = 0; i < islands.size(); ++i) {
|
||||
if (island_extrusions[i].empty()) {
|
||||
continue;
|
||||
}
|
||||
size_t idx = 0;
|
||||
Vec2f pt = Vec2f::Zero();
|
||||
if (islands[i].signed_distance_from_lines(layer_lines[extrusions[e].first].a, idx, pt) < 0) {
|
||||
island_extrusions[i].push_back(e);
|
||||
island_assigned = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (!island_assigned) { // If extrusion is not assigned for some reason, push it into the first island. As with the previous backup code,
|
||||
// it may be wrong, but it won't crash
|
||||
island_extrusions[0].push_back(e);
|
||||
std::vector<std::vector<size_t>> island_extrusions(islands.size(),
|
||||
std::vector<size_t>{}); // final assigment of each extrusion to an island.
|
||||
for (size_t extrusion_idx = 0; extrusion_idx < extrusions.size(); extrusion_idx++) {
|
||||
Point second_point = Point::new_scale(layer_lines[extrusions[extrusion_idx].first].b);
|
||||
for (size_t island_idx = 0; island_idx < islands.size(); island_idx++) {
|
||||
if (islands[island_idx].signed_distance_from_lines(second_point) <= 0.0) {
|
||||
island_extrusions[island_idx].push_back(extrusion_idx);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -553,10 +481,14 @@ std::tuple<LayerIslands, PixelGrid> reckon_islands(
|
|||
}
|
||||
|
||||
Island island { };
|
||||
island.external_lines.insert(island.external_lines.end(),
|
||||
layer_lines.begin() + extrusions[island_ex[0]].first,
|
||||
layer_lines.begin() + extrusions[island_ex[0]].second);
|
||||
for (size_t extrusion_idx : island_ex) {
|
||||
|
||||
if (layer_lines[extrusions[extrusion_idx].first].is_external_perimeter()) {
|
||||
island.external_lines.insert(island.external_lines.end(),
|
||||
layer_lines.begin() + extrusions[extrusion_idx].first,
|
||||
layer_lines.begin() + extrusions[extrusion_idx].second);
|
||||
}
|
||||
|
||||
for (size_t lidx = extrusions[extrusion_idx].first; lidx < extrusions[extrusion_idx].second; ++lidx) {
|
||||
line_to_island_mapping[lidx] = result.islands.size();
|
||||
const ExtrusionLine &line = layer_lines[lidx];
|
||||
|
@ -1050,7 +982,7 @@ Issues check_global_stability(SupportGridFilter supports_presence_grid,
|
|||
#ifdef DETAILED_DEBUG_LOGS
|
||||
weakest_conn.print_info("weakest connection info: ");
|
||||
#endif
|
||||
LinesDistancer island_lines_dist(island.external_lines);
|
||||
LD island_lines_dist(island.external_lines);
|
||||
float unchecked_dist = params.min_distance_between_support_points + 1.0f;
|
||||
|
||||
for (const ExtrusionLine &line : island.external_lines) {
|
||||
|
@ -1059,12 +991,9 @@ Issues check_global_stability(SupportGridFilter supports_presence_grid,
|
|||
unchecked_dist += line.len;
|
||||
} else {
|
||||
unchecked_dist = line.len;
|
||||
Vec2f target_point;
|
||||
size_t idx;
|
||||
Vec3f pivot_site_search_point = to_3d(Vec2f(line.b + (line.b - line.a).normalized() * 300.0f),
|
||||
layer_z);
|
||||
island_lines_dist.signed_distance_from_lines(pivot_site_search_point.head<2>(), idx,
|
||||
target_point);
|
||||
auto [dist, nidx, target_point] = island_lines_dist.signed_distance_from_lines_extra(pivot_site_search_point.head<2>());
|
||||
Vec3f support_point = to_3d(target_point, layer_z);
|
||||
auto force = part.is_stable_while_extruding(weakest_conn, line, support_point, layer_z, params);
|
||||
if (force > 0) {
|
||||
|
@ -1147,7 +1076,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
|
|||
}
|
||||
}
|
||||
#endif
|
||||
LinesDistancer external_lines(layer_lines);
|
||||
LD external_lines(layer_lines);
|
||||
layer_lines.clear();
|
||||
prev_layer_grid = layer_grid;
|
||||
|
||||
|
@ -1199,7 +1128,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
|
|||
}
|
||||
}
|
||||
#endif
|
||||
external_lines = LinesDistancer(layer_lines);
|
||||
external_lines = LD(layer_lines);
|
||||
layer_lines.clear();
|
||||
prev_layer_grid = layer_grid;
|
||||
}
|
||||
|
|
|
@ -1,159 +0,0 @@
|
|||
#include "TriangulateWall.hpp"
|
||||
#include "MTUtils.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
|
||||
//class Ring {
|
||||
// size_t idx = 0, nextidx = 1, startidx = 0, begin = 0, end = 0;
|
||||
|
||||
//public:
|
||||
// explicit Ring(size_t from, size_t to) : begin(from), end(to) { init(begin); }
|
||||
|
||||
// size_t size() const { return end - begin; }
|
||||
// std::pair<size_t, size_t> pos() const { return {idx, nextidx}; }
|
||||
// bool is_lower() const { return idx < size(); }
|
||||
|
||||
// void inc()
|
||||
// {
|
||||
// if (nextidx != startidx) nextidx++;
|
||||
// if (nextidx == end) nextidx = begin;
|
||||
// idx ++;
|
||||
// if (idx == end) idx = begin;
|
||||
// }
|
||||
|
||||
// void init(size_t pos)
|
||||
// {
|
||||
// startidx = begin + (pos - begin) % size();
|
||||
// idx = startidx;
|
||||
// nextidx = begin + (idx + 1 - begin) % size();
|
||||
// }
|
||||
|
||||
// bool is_finished() const { return nextidx == idx; }
|
||||
//};
|
||||
|
||||
//template<class Sc>
|
||||
//static Sc sq_dst(const Vec<3, Sc> &v1, const Vec<3, Sc>& v2)
|
||||
//{
|
||||
// Vec<3, Sc> v = v1 - v2;
|
||||
// return v.x() * v.x() + v.y() * v.y() /*+ v.z() * v.z()*/;
|
||||
//}
|
||||
|
||||
//template<class Sc>
|
||||
//static Sc trscore(const Ring & onring,
|
||||
// const Ring & offring,
|
||||
// const std::vector<Vec<3, Sc>> &pts)
|
||||
//{
|
||||
// Sc a = sq_dst(pts[onring.pos().first], pts[offring.pos().first]);
|
||||
// Sc b = sq_dst(pts[onring.pos().second], pts[offring.pos().first]);
|
||||
// return (std::abs(a) + std::abs(b)) / 2.;
|
||||
//}
|
||||
|
||||
//template<class Sc>
|
||||
//class Triangulator {
|
||||
// const std::vector<Vec<3, Sc>> *pts;
|
||||
// Ring *onring, *offring;
|
||||
|
||||
// double calc_score() const
|
||||
// {
|
||||
// return trscore(*onring, *offring, *pts);
|
||||
// }
|
||||
|
||||
// void synchronize_rings()
|
||||
// {
|
||||
// Ring lring = *offring;
|
||||
// auto minsc = trscore(*onring, lring, *pts);
|
||||
// size_t imin = lring.pos().first;
|
||||
|
||||
// lring.inc();
|
||||
|
||||
// while(!lring.is_finished()) {
|
||||
// double score = trscore(*onring, lring, *pts);
|
||||
// if (score < minsc) { minsc = score; imin = lring.pos().first; }
|
||||
// lring.inc();
|
||||
// }
|
||||
|
||||
// offring->init(imin);
|
||||
// }
|
||||
|
||||
// void emplace_indices(std::vector<Vec3i> &indices)
|
||||
// {
|
||||
// Vec3i tr{int(onring->pos().first), int(onring->pos().second),
|
||||
// int(offring->pos().first)};
|
||||
// if (onring->is_lower()) std::swap(tr(0), tr(1));
|
||||
// indices.emplace_back(tr);
|
||||
// }
|
||||
|
||||
//public:
|
||||
// void run(std::vector<Vec3i> &indices)
|
||||
// {
|
||||
// synchronize_rings();
|
||||
|
||||
// double score = 0, prev_score = 0;
|
||||
// while (!onring->is_finished() || !offring->is_finished()) {
|
||||
// prev_score = score;
|
||||
// if (onring->is_finished() || (score = calc_score()) > prev_score) {
|
||||
// std::swap(onring, offring);
|
||||
// } else {
|
||||
// emplace_indices(indices);
|
||||
// onring->inc();
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
|
||||
// explicit Triangulator(const std::vector<Vec<3, Sc>> *points,
|
||||
// Ring & lower,
|
||||
// Ring & upper)
|
||||
// : pts{points}, onring{&upper}, offring{&lower}
|
||||
// {}
|
||||
//};
|
||||
|
||||
//template<class Sc, class I>
|
||||
//void triangulate_wall(std::vector<Vec<3, Sc>> &pts,
|
||||
// std::vector<Vec<3, I>> & ind,
|
||||
// const Polygon & lower,
|
||||
// const Polygon & upper,
|
||||
// double lower_z_mm,
|
||||
// double upper_z_mm)
|
||||
//{
|
||||
// if (upper.points.size() < 3 || lower.points.size() < 3) return;
|
||||
|
||||
// pts.reserve(lower.points.size() + upper.points.size());
|
||||
// for (auto &p : lower.points)
|
||||
// pts.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
|
||||
// for (auto &p : upper.points)
|
||||
// pts.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
|
||||
|
||||
// ind.reserve(2 * (lower.size() + upper.size()));
|
||||
|
||||
// Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
|
||||
// Triangulator t{&pts, lring, uring};
|
||||
// t.run(ind);
|
||||
//}
|
||||
|
||||
//Wall triangulate_wall(const Polygon &lower,
|
||||
// const Polygon &upper,
|
||||
// double lower_z_mm,
|
||||
// double upper_z_mm)
|
||||
//{
|
||||
// if (upper.points.size() < 3 || lower.points.size() < 3) return {};
|
||||
|
||||
// Wall wall;
|
||||
// auto &pts = wall.first;
|
||||
// auto &ind = wall.second;
|
||||
|
||||
// pts.reserve(lower.points.size() + upper.points.size());
|
||||
// for (auto &p : lower.points)
|
||||
// wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
|
||||
// for (auto &p : upper.points)
|
||||
// wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
|
||||
|
||||
// ind.reserve(2 * (lower.size() + upper.size()));
|
||||
|
||||
// Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
|
||||
// Triangulator t{&pts, lring, uring};
|
||||
// t.run(ind);
|
||||
|
||||
// return wall;
|
||||
//}
|
||||
|
||||
} // namespace Slic3r
|
Loading…
Add table
Add a link
Reference in a new issue