ENH: speed gcode export up again
thanks prusa Signed-off-by: salt.wei <salt.wei@bambulab.com> Change-Id: Ifbe5e2ea55b16a7fe281b54ca16c37695c15f5b1
This commit is contained in:
parent
c945c47383
commit
4c4b274408
|
@ -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.
|
||||||
|
@ -83,6 +84,13 @@ public:
|
||||||
// to split around.
|
// to split around.
|
||||||
template<typename SourceNode>
|
template<typename SourceNode>
|
||||||
void build(std::vector<SourceNode> &&input)
|
void build(std::vector<SourceNode> &&input)
|
||||||
|
{
|
||||||
|
this->build_modify_input(input);
|
||||||
|
input.clear();
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename SourceNode>
|
||||||
|
void build_modify_input(std::vector<SourceNode> &input)
|
||||||
{
|
{
|
||||||
if (input.empty())
|
if (input.empty())
|
||||||
clear();
|
clear();
|
||||||
|
@ -91,7 +99,6 @@ public:
|
||||||
m_nodes.assign(next_highest_power_of_2(input.size()) * 2 - 1, Node());
|
m_nodes.assign(next_highest_power_of_2(input.size()) * 2 - 1, Node());
|
||||||
build_recursive(input, 0, 0, input.size() - 1);
|
build_recursive(input, 0, 0, input.size() - 1);
|
||||||
}
|
}
|
||||||
input.clear();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
const std::vector<Node>& nodes() const { return m_nodes; }
|
const std::vector<Node>& nodes() const { return m_nodes; }
|
||||||
|
@ -211,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 {
|
||||||
|
@ -513,7 +537,7 @@ namespace detail {
|
||||||
const VectorType origin;
|
const VectorType origin;
|
||||||
|
|
||||||
inline VectorType closest_point_to_origin(size_t primitive_index,
|
inline VectorType closest_point_to_origin(size_t primitive_index,
|
||||||
ScalarType& squared_distance){
|
ScalarType& squared_distance) const {
|
||||||
const auto &triangle = this->faces[primitive_index];
|
const auto &triangle = this->faces[primitive_index];
|
||||||
VectorType closest_point = closest_point_to_triangle<VectorType>(origin,
|
VectorType closest_point = closest_point_to_triangle<VectorType>(origin,
|
||||||
this->vertices[triangle(0)].template cast<ScalarType>(),
|
this->vertices[triangle(0)].template cast<ScalarType>(),
|
||||||
|
@ -607,6 +631,37 @@ namespace detail {
|
||||||
return up_sqr_d;
|
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
|
} // namespace detail
|
||||||
|
|
||||||
// Build a balanced AABB Tree over an indexed triangles set, balancing the tree
|
// Build a balanced AABB Tree over an indexed triangles set, balancing the tree
|
||||||
|
@ -793,6 +848,33 @@ inline bool is_any_triangle_in_radius(
|
||||||
return hit_point.allFinite();
|
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
|
// 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.
|
// contains a given point. Returns size_t(-1) when the point is outside.
|
||||||
|
@ -837,48 +919,54 @@ struct Intersecting<Eigen::AlignedBox<CoordType, NumD>> {
|
||||||
|
|
||||||
template<class G> auto intersecting(const G &g) { return Intersecting<G>{g}; }
|
template<class G> auto intersecting(const G &g) { return Intersecting<G>{g}; }
|
||||||
|
|
||||||
template<class G> struct Containing {};
|
template<class G> struct Within {};
|
||||||
|
|
||||||
// Intersection predicate specialization for box-box intersections
|
// Intersection predicate specialization for box-box intersections
|
||||||
template<class CoordType, int NumD>
|
template<class CoordType, int NumD>
|
||||||
struct Containing<Eigen::AlignedBox<CoordType, NumD>> {
|
struct Within<Eigen::AlignedBox<CoordType, NumD>> {
|
||||||
Eigen::AlignedBox<CoordType, NumD> box;
|
Eigen::AlignedBox<CoordType, NumD> box;
|
||||||
|
|
||||||
Containing(const Eigen::AlignedBox<CoordType, NumD> &bb): box{bb} {}
|
Within(const Eigen::AlignedBox<CoordType, NumD> &bb): box{bb} {}
|
||||||
|
|
||||||
bool operator() (const typename Tree<NumD, CoordType>::Node &node) const
|
bool operator() (const typename Tree<NumD, CoordType>::Node &node) const
|
||||||
{
|
{
|
||||||
return box.contains(node.bbox);
|
return node.is_leaf() ? box.contains(node.bbox) : box.intersects(node.bbox);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
template<class G> auto containing(const G &g) { return Containing<G>{g}; }
|
template<class G> auto within(const G &g) { return Within<G>{g}; }
|
||||||
|
|
||||||
namespace detail {
|
namespace detail {
|
||||||
|
|
||||||
|
// Returns true in case traversal should continue,
|
||||||
|
// returns false if traversal should stop (for example if the first hit was found).
|
||||||
template<int Dims, typename T, typename Pred, typename Fn>
|
template<int Dims, typename T, typename Pred, typename Fn>
|
||||||
void traverse_recurse(const Tree<Dims, T> &tree,
|
bool traverse_recurse(const Tree<Dims, T> &tree,
|
||||||
size_t idx,
|
size_t idx,
|
||||||
Pred && pred,
|
Pred && pred,
|
||||||
Fn && callback)
|
Fn && callback)
|
||||||
{
|
{
|
||||||
assert(tree.node(idx).is_valid());
|
assert(tree.node(idx).is_valid());
|
||||||
|
|
||||||
if (!pred(tree.node(idx))) return;
|
if (!pred(tree.node(idx)))
|
||||||
|
// Continue traversal.
|
||||||
|
return true;
|
||||||
|
|
||||||
if (tree.node(idx).is_leaf()) {
|
if (tree.node(idx).is_leaf()) {
|
||||||
callback(tree.node(idx).idx);
|
// Callback returns true to continue traversal, false to stop traversal.
|
||||||
|
return callback(tree.node(idx));
|
||||||
} else {
|
} else {
|
||||||
|
|
||||||
// call this with left and right node idx:
|
// call this with left and right node idx:
|
||||||
auto trv = [&](size_t idx) {
|
auto trv = [&](size_t idx) -> bool {
|
||||||
traverse_recurse(tree, idx, std::forward<Pred>(pred),
|
return traverse_recurse(tree, idx, std::forward<Pred>(pred),
|
||||||
std::forward<Fn>(callback));
|
std::forward<Fn>(callback));
|
||||||
};
|
};
|
||||||
|
|
||||||
// Left / right child node index.
|
// Left / right child node index.
|
||||||
trv(Tree<Dims, T>::left_child_idx(idx));
|
// Returns true if both children allow the traversal to continue.
|
||||||
trv(Tree<Dims, T>::right_child_idx(idx));
|
return trv(Tree<Dims, T>::left_child_idx(idx)) &&
|
||||||
|
trv(Tree<Dims, T>::right_child_idx(idx));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -888,6 +976,7 @@ void traverse_recurse(const Tree<Dims, T> &tree,
|
||||||
// traverse(tree, intersecting(QueryBox), [](size_t face_idx) {
|
// traverse(tree, intersecting(QueryBox), [](size_t face_idx) {
|
||||||
// /* ... */
|
// /* ... */
|
||||||
// });
|
// });
|
||||||
|
// Callback shall return true to continue traversal, false if it wants to stop traversal, for example if it found the answer.
|
||||||
template<int Dims, typename T, typename Predicate, typename Fn>
|
template<int Dims, typename T, typename Predicate, typename Fn>
|
||||||
void traverse(const Tree<Dims, T> &tree, Predicate &&pred, Fn &&callback)
|
void traverse(const Tree<Dims, T> &tree, Predicate &&pred, Fn &&callback)
|
||||||
{
|
{
|
||||||
|
|
|
@ -1,83 +1,197 @@
|
||||||
#ifndef SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
#ifndef SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
||||||
#define SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
#define SRC_LIBSLIC3R_AABBTREELINES_HPP_
|
||||||
|
|
||||||
#include "libslic3r/Point.hpp"
|
#include "Point.hpp"
|
||||||
#include "libslic3r/EdgeGrid.hpp"
|
#include "Utils.hpp"
|
||||||
|
#include "libslic3r.h"
|
||||||
#include "libslic3r/AABBTreeIndirect.hpp"
|
#include "libslic3r/AABBTreeIndirect.hpp"
|
||||||
#include "libslic3r/Line.hpp"
|
#include "libslic3r/Line.hpp"
|
||||||
|
#include <algorithm>
|
||||||
|
#include <cmath>
|
||||||
|
#include <type_traits>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r { namespace AABBTreeLines {
|
||||||
|
|
||||||
namespace AABBTreeLines {
|
|
||||||
|
|
||||||
namespace detail {
|
namespace detail {
|
||||||
|
|
||||||
template<typename ALineType, typename ATreeType, typename AVectorType>
|
template<typename ALineType, typename ATreeType, typename AVectorType> struct IndexedLinesDistancer
|
||||||
struct IndexedLinesDistancer {
|
{
|
||||||
using LineType = ALineType;
|
using LineType = ALineType;
|
||||||
using TreeType = ATreeType;
|
using TreeType = ATreeType;
|
||||||
using VectorType = AVectorType;
|
using VectorType = AVectorType;
|
||||||
using ScalarType = typename VectorType::Scalar;
|
using ScalarType = typename VectorType::Scalar;
|
||||||
|
|
||||||
const std::vector<LineType> &lines;
|
const std::vector<LineType> &lines;
|
||||||
const TreeType &tree;
|
const TreeType &tree;
|
||||||
|
|
||||||
const VectorType origin;
|
const VectorType origin;
|
||||||
|
|
||||||
inline VectorType closest_point_to_origin(size_t primitive_index,
|
inline VectorType closest_point_to_origin(size_t primitive_index, ScalarType &squared_distance) const
|
||||||
ScalarType &squared_distance) {
|
{
|
||||||
VectorType nearest_point;
|
Vec<LineType::Dim, typename LineType::Scalar> nearest_point;
|
||||||
const LineType &line = lines[primitive_index];
|
const LineType &line = lines[primitive_index];
|
||||||
squared_distance = line_alg::distance_to_squared(line, origin, &nearest_point);
|
squared_distance = line_alg::distance_to_squared(line, origin.template cast<typename LineType::Scalar>(), &nearest_point);
|
||||||
return nearest_point;
|
return nearest_point.template cast<ScalarType>();
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
// returns number of intersections of ray starting in ray_origin and following the specified coordinate line with lines in tree
|
||||||
|
// first number is hits in positive direction of ray, second number hits in negative direction. returns neagtive numbers when ray_origin is
|
||||||
|
// on some line exactly.
|
||||||
|
template<typename LineType, typename TreeType, typename VectorType, int coordinate>
|
||||||
|
inline std::tuple<int, int> coordinate_aligned_ray_hit_count(size_t node_idx,
|
||||||
|
const TreeType &tree,
|
||||||
|
const std::vector<LineType> &lines,
|
||||||
|
const VectorType &ray_origin)
|
||||||
|
{
|
||||||
|
static constexpr int other_coordinate = (coordinate + 1) % 2;
|
||||||
|
using Scalar = typename LineType::Scalar;
|
||||||
|
using Floating = typename std::conditional<std::is_floating_point<Scalar>::value, Scalar, double>::type;
|
||||||
|
const auto &node = tree.node(node_idx);
|
||||||
|
assert(node.is_valid());
|
||||||
|
if (node.is_leaf()) {
|
||||||
|
const LineType &line = lines[node.idx];
|
||||||
|
if (ray_origin[other_coordinate] < std::min(line.a[other_coordinate], line.b[other_coordinate]) ||
|
||||||
|
ray_origin[other_coordinate] >= std::max(line.a[other_coordinate], line.b[other_coordinate])) {
|
||||||
|
// the second inequality is nonsharp for a reason
|
||||||
|
// without it, we may count contour border twice when the lines meet exactly at the spot of intersection. this prevents is
|
||||||
|
return {0, 0};
|
||||||
|
}
|
||||||
|
|
||||||
|
Scalar line_max = std::max(line.a[coordinate], line.b[coordinate]);
|
||||||
|
Scalar line_min = std::min(line.a[coordinate], line.b[coordinate]);
|
||||||
|
if (ray_origin[coordinate] > line_max) {
|
||||||
|
return {1, 0};
|
||||||
|
} else if (ray_origin[coordinate] < line_min) {
|
||||||
|
return {0, 1};
|
||||||
|
} else {
|
||||||
|
// find intersection of ray with line
|
||||||
|
// that is when ( line.a + t * (line.b - line.a) )[other_coordinate] == ray_origin[other_coordinate]
|
||||||
|
// t = ray_origin[oc] - line.a[oc] / (line.b[oc] - line.a[oc]);
|
||||||
|
// then we want to get value of intersection[ coordinate]
|
||||||
|
// val_c = line.a[c] + t * (line.b[c] - line.a[c]);
|
||||||
|
// Note that ray and line may overlap, when (line.b[oc] - line.a[oc]) is zero
|
||||||
|
// In that case, we return negative number
|
||||||
|
Floating distance_oc = line.b[other_coordinate] - line.a[other_coordinate];
|
||||||
|
Floating t = (ray_origin[other_coordinate] - line.a[other_coordinate]) / distance_oc;
|
||||||
|
Floating val_c = line.a[coordinate] + t * (line.b[coordinate] - line.a[coordinate]);
|
||||||
|
if (ray_origin[coordinate] > val_c) {
|
||||||
|
return {1, 0};
|
||||||
|
} else if (ray_origin[coordinate] < val_c) {
|
||||||
|
return {0, 1};
|
||||||
|
} else { // ray origin is on boundary
|
||||||
|
return {-1, -1};
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
int intersections_above = 0;
|
||||||
|
int intersections_below = 0;
|
||||||
|
size_t left_node_idx = node_idx * 2 + 1;
|
||||||
|
size_t right_node_idx = left_node_idx + 1;
|
||||||
|
const auto &node_left = tree.node(left_node_idx);
|
||||||
|
const auto &node_right = tree.node(right_node_idx);
|
||||||
|
assert(node_left.is_valid());
|
||||||
|
assert(node_right.is_valid());
|
||||||
|
|
||||||
|
if (node_left.bbox.min()[other_coordinate] <= ray_origin[other_coordinate] &&
|
||||||
|
node_left.bbox.max()[other_coordinate] >=
|
||||||
|
ray_origin[other_coordinate]) {
|
||||||
|
auto [above, below] = coordinate_aligned_ray_hit_count<LineType, TreeType, VectorType, coordinate>(left_node_idx, tree, lines,
|
||||||
|
ray_origin);
|
||||||
|
if (above < 0 || below < 0) return {-1, -1};
|
||||||
|
intersections_above += above;
|
||||||
|
intersections_below += below;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (node_right.bbox.min()[other_coordinate] <= ray_origin[other_coordinate] &&
|
||||||
|
node_right.bbox.max()[other_coordinate] >= ray_origin[other_coordinate]) {
|
||||||
|
auto [above, below] = coordinate_aligned_ray_hit_count<LineType, TreeType, VectorType, coordinate>(right_node_idx, tree, lines,
|
||||||
|
ray_origin);
|
||||||
|
if (above < 0 || below < 0) return {-1, -1};
|
||||||
|
intersections_above += above;
|
||||||
|
intersections_below += below;
|
||||||
|
}
|
||||||
|
return {intersections_above, intersections_below};
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Build a balanced AABB Tree over a vector of float lines, balancing the tree
|
template<typename LineType, typename TreeType, typename VectorType>
|
||||||
|
inline std::vector<std::pair<VectorType, size_t>> get_intersections_with_line(size_t node_idx,
|
||||||
|
const TreeType &tree,
|
||||||
|
const std::vector<LineType> &lines,
|
||||||
|
const LineType &line,
|
||||||
|
const typename TreeType::BoundingBox &line_bb)
|
||||||
|
{
|
||||||
|
const auto &node = tree.node(node_idx);
|
||||||
|
assert(node.is_valid());
|
||||||
|
if (node.is_leaf()) {
|
||||||
|
VectorType intersection_pt;
|
||||||
|
if (line_alg::intersection(line, lines[node.idx], &intersection_pt)) {
|
||||||
|
return {std::pair<VectorType, size_t>(intersection_pt, node.idx)};
|
||||||
|
} else {
|
||||||
|
return {};
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
size_t left_node_idx = node_idx * 2 + 1;
|
||||||
|
size_t right_node_idx = left_node_idx + 1;
|
||||||
|
const auto &node_left = tree.node(left_node_idx);
|
||||||
|
const auto &node_right = tree.node(right_node_idx);
|
||||||
|
assert(node_left.is_valid());
|
||||||
|
assert(node_right.is_valid());
|
||||||
|
|
||||||
|
std::vector<std::pair<VectorType, size_t>> result;
|
||||||
|
|
||||||
|
if (node_left.bbox.intersects(line_bb)) {
|
||||||
|
std::vector<std::pair<VectorType, size_t>> intersections =
|
||||||
|
get_intersections_with_line<LineType, TreeType, VectorType>(left_node_idx, tree, lines, line, line_bb);
|
||||||
|
result.insert(result.end(), intersections.begin(), intersections.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
if (node_right.bbox.intersects(line_bb)) {
|
||||||
|
std::vector<std::pair<VectorType, size_t>> intersections =
|
||||||
|
get_intersections_with_line<LineType, TreeType, VectorType>(right_node_idx, tree, lines, line, line_bb);
|
||||||
|
result.insert(result.end(), intersections.begin(), intersections.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace detail
|
||||||
|
|
||||||
|
// Build a balanced AABB Tree over a vector of lines, balancing the tree
|
||||||
// on centroids of the lines.
|
// on centroids of the lines.
|
||||||
// Epsilon is applied to the bounding boxes of the AABB Tree to cope with numeric inaccuracies
|
// Epsilon is applied to the bounding boxes of the AABB Tree to cope with numeric inaccuracies
|
||||||
// during tree traversal.
|
// during tree traversal.
|
||||||
template<typename LineType>
|
template<typename LineType>
|
||||||
inline AABBTreeIndirect::Tree<2, typename LineType::Scalar> build_aabb_tree_over_indexed_lines(
|
inline AABBTreeIndirect::Tree<2, typename LineType::Scalar> build_aabb_tree_over_indexed_lines(const std::vector<LineType> &lines)
|
||||||
const std::vector<LineType> &lines,
|
{
|
||||||
//FIXME do we want to apply an epsilon?
|
|
||||||
const float eps = 0)
|
|
||||||
{
|
|
||||||
using TreeType = AABBTreeIndirect::Tree<2, typename LineType::Scalar>;
|
using TreeType = AABBTreeIndirect::Tree<2, typename LineType::Scalar>;
|
||||||
// using CoordType = typename TreeType::CoordType;
|
// using CoordType = typename TreeType::CoordType;
|
||||||
using VectorType = typename TreeType::VectorType;
|
using VectorType = typename TreeType::VectorType;
|
||||||
using BoundingBox = typename TreeType::BoundingBox;
|
using BoundingBox = typename TreeType::BoundingBox;
|
||||||
|
|
||||||
struct InputType {
|
struct InputType
|
||||||
size_t idx() const {
|
{
|
||||||
return m_idx;
|
size_t idx() const { return m_idx; }
|
||||||
}
|
const BoundingBox &bbox() const { return m_bbox; }
|
||||||
const BoundingBox& bbox() const {
|
const VectorType ¢roid() const { return m_centroid; }
|
||||||
return m_bbox;
|
|
||||||
}
|
|
||||||
const VectorType& centroid() const {
|
|
||||||
return m_centroid;
|
|
||||||
}
|
|
||||||
|
|
||||||
size_t m_idx;
|
size_t m_idx;
|
||||||
BoundingBox m_bbox;
|
BoundingBox m_bbox;
|
||||||
VectorType m_centroid;
|
VectorType m_centroid;
|
||||||
};
|
};
|
||||||
|
|
||||||
std::vector<InputType> input;
|
std::vector<InputType> input;
|
||||||
input.reserve(lines.size());
|
input.reserve(lines.size());
|
||||||
const VectorType veps(eps, eps);
|
|
||||||
for (size_t i = 0; i < lines.size(); ++i) {
|
for (size_t i = 0; i < lines.size(); ++i) {
|
||||||
const LineType &line = lines[i];
|
const LineType &line = lines[i];
|
||||||
InputType n;
|
InputType n;
|
||||||
n.m_idx = i;
|
n.m_idx = i;
|
||||||
n.m_centroid = (line.a + line.b) * 0.5;
|
n.m_centroid = (line.a + line.b) * 0.5;
|
||||||
n.m_bbox = BoundingBox(line.a, line.a);
|
n.m_bbox = BoundingBox(line.a, line.a);
|
||||||
n.m_bbox.extend(line.b);
|
n.m_bbox.extend(line.b);
|
||||||
n.m_bbox.min() -= veps;
|
|
||||||
n.m_bbox.max() += veps;
|
|
||||||
input.emplace_back(n);
|
input.emplace_back(n);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -88,25 +202,164 @@ 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
|
// 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>
|
template<typename LineType, typename TreeType, typename VectorType>
|
||||||
inline typename VectorType::Scalar squared_distance_to_indexed_lines(
|
inline typename VectorType::Scalar squared_distance_to_indexed_lines(
|
||||||
const std::vector<LineType> &lines,
|
const std::vector<LineType> &lines,
|
||||||
const TreeType &tree,
|
const TreeType &tree,
|
||||||
const VectorType &point,
|
const VectorType &point,
|
||||||
size_t &hit_idx_out,
|
size_t &hit_idx_out,
|
||||||
Eigen::PlainObjectBase<VectorType> &hit_point_out)
|
Eigen::PlainObjectBase<VectorType> &hit_point_out,
|
||||||
{
|
typename VectorType::Scalar max_sqr_dist = std::numeric_limits<typename VectorType::Scalar>::infinity())
|
||||||
|
{
|
||||||
using Scalar = typename VectorType::Scalar;
|
using Scalar = typename VectorType::Scalar;
|
||||||
auto distancer = detail::IndexedLinesDistancer<LineType, TreeType, VectorType>
|
if (tree.empty()) return Scalar(-1);
|
||||||
{ lines, tree, point };
|
auto distancer = detail::IndexedLinesDistancer<LineType, TreeType, VectorType>{lines, tree, point};
|
||||||
return tree.empty() ?
|
return AABBTreeIndirect::detail::squared_distance_to_indexed_primitives_recursive(distancer, size_t(0), Scalar(0), max_sqr_dist,
|
||||||
Scalar(-1) :
|
hit_idx_out, hit_point_out);
|
||||||
AABBTreeIndirect::detail::squared_distance_to_indexed_primitives_recursive(distancer, size_t(0), Scalar(0),
|
|
||||||
std::numeric_limits<Scalar>::infinity(), hit_idx_out, hit_point_out);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return 1 if true, -1 if false, 0 for point on contour (or if cannot be determined)
|
||||||
|
template<typename LineType, typename TreeType, typename VectorType>
|
||||||
|
inline int point_outside_closed_contours(const std::vector<LineType> &lines, const TreeType &tree, const VectorType &point)
|
||||||
|
{
|
||||||
|
if (tree.empty()) { return 1; }
|
||||||
|
|
||||||
|
auto [hits_above, hits_below] = detail::coordinate_aligned_ray_hit_count<LineType, TreeType, VectorType, 0>(0, tree, lines, point);
|
||||||
|
if (hits_above < 0 || hits_below < 0) {
|
||||||
|
return 0;
|
||||||
|
} else if (hits_above % 2 == 1 && hits_below % 2 == 1) {
|
||||||
|
return -1;
|
||||||
|
} else if (hits_above % 2 == 0 && hits_below % 2 == 0) {
|
||||||
|
return 1;
|
||||||
|
} else { // this should not happen with closed contours. lets check it in Y direction
|
||||||
|
auto [hits_above, hits_below] = detail::coordinate_aligned_ray_hit_count<LineType, TreeType, VectorType, 1>(0, tree, lines, point);
|
||||||
|
if (hits_above < 0 || hits_below < 0) {
|
||||||
|
return 0;
|
||||||
|
} else if (hits_above % 2 == 1 && hits_below % 2 == 1) {
|
||||||
|
return -1;
|
||||||
|
} else if (hits_above % 2 == 0 && hits_below % 2 == 0) {
|
||||||
|
return 1;
|
||||||
|
} else { // both results were unclear
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
template<bool sorted, typename VectorType, typename LineType, typename TreeType>
|
||||||
|
inline std::vector<std::pair<VectorType, size_t>> get_intersections_with_line(const std::vector<LineType> &lines,
|
||||||
|
const TreeType &tree,
|
||||||
|
const LineType &line)
|
||||||
|
{
|
||||||
|
if (tree.empty()) {
|
||||||
|
return {};
|
||||||
|
}
|
||||||
|
auto line_bb = typename TreeType::BoundingBox(line.a, line.a);
|
||||||
|
line_bb.extend(line.b);
|
||||||
|
|
||||||
|
auto intersections = detail::get_intersections_with_line<LineType, TreeType, VectorType>(0, tree, lines, line, line_bb);
|
||||||
|
if (sorted) {
|
||||||
|
using Floating =
|
||||||
|
typename std::conditional<std::is_floating_point<typename LineType::Scalar>::value, typename LineType::Scalar, double>::type;
|
||||||
|
|
||||||
|
std::vector<std::pair<Floating, std::pair<VectorType, size_t>>> points_with_sq_distance{};
|
||||||
|
for (const auto &p : intersections) {
|
||||||
|
points_with_sq_distance.emplace_back((p.first - line.a).template cast<Floating>().squaredNorm(), p);
|
||||||
|
}
|
||||||
|
std::sort(points_with_sq_distance.begin(), points_with_sq_distance.end(),
|
||||||
|
[](const std::pair<Floating, std::pair<VectorType, size_t>> &left,
|
||||||
|
std::pair<Floating, std::pair<VectorType, size_t>> &right) { return left.first < right.first; });
|
||||||
|
for (size_t i = 0; i < points_with_sq_distance.size(); i++) {
|
||||||
|
intersections[i] = points_with_sq_distance[i].second;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return intersections;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename LineType> class LinesDistancer
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
using Scalar = typename LineType::Scalar;
|
||||||
|
using Floating = typename std::conditional<std::is_floating_point<Scalar>::value, Scalar, double>::type;
|
||||||
|
private:
|
||||||
|
std::vector<LineType> lines;
|
||||||
|
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);
|
||||||
|
}
|
||||||
|
|
||||||
|
explicit LinesDistancer(std::vector<LineType> &&lines) : lines(lines)
|
||||||
|
{
|
||||||
|
tree = AABBTreeLines::build_aabb_tree_over_indexed_lines(this->lines);
|
||||||
|
}
|
||||||
|
|
||||||
|
LinesDistancer() = default;
|
||||||
|
|
||||||
|
// 1 true, -1 false, 0 cannot determine
|
||||||
|
int outside(const Vec<2, Scalar> &point) const { return point_outside_closed_contours(lines, tree, point); }
|
||||||
|
|
||||||
|
// negative sign means inside
|
||||||
|
template<bool SIGNED_DISTANCE>
|
||||||
|
std::tuple<Floating, size_t, Vec<2, Floating>> 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);
|
||||||
|
|
||||||
|
if (SIGNED_DISTANCE) {
|
||||||
|
distance *= outside(point);
|
||||||
|
}
|
||||||
|
|
||||||
|
return {distance, nearest_line_index_out, nearest_point_out};
|
||||||
|
}
|
||||||
|
|
||||||
|
template<bool SIGNED_DISTANCE> Floating distance_from_lines(const Vec<2, typename LineType::Scalar> &point) const
|
||||||
|
{
|
||||||
|
auto [dist, idx, np] = distance_from_lines_extra<SIGNED_DISTANCE>(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);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<bool sorted> std::vector<std::pair<Vec<2, Scalar>, size_t>> intersections_with_line(const LineType &line) const
|
||||||
|
{
|
||||||
|
return get_intersections_with_line<sorted, Vec<2, Scalar>>(lines, tree, line);
|
||||||
|
}
|
||||||
|
|
||||||
|
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_ */
|
#endif /* SRC_LIBSLIC3R_AABBTREELINES_HPP_ */
|
||||||
|
|
|
@ -22,6 +22,8 @@ set(lisbslic3r_sources
|
||||||
ArcFitter.hpp
|
ArcFitter.hpp
|
||||||
pchheader.cpp
|
pchheader.cpp
|
||||||
pchheader.hpp
|
pchheader.hpp
|
||||||
|
AABBTreeIndirect.hpp
|
||||||
|
AABBTreeLines.hpp
|
||||||
BoundingBox.cpp
|
BoundingBox.cpp
|
||||||
BoundingBox.hpp
|
BoundingBox.hpp
|
||||||
BridgeDetector.cpp
|
BridgeDetector.cpp
|
||||||
|
@ -125,6 +127,8 @@ set(lisbslic3r_sources
|
||||||
# GCode/PressureEqualizer.hpp
|
# GCode/PressureEqualizer.hpp
|
||||||
GCode/PrintExtents.cpp
|
GCode/PrintExtents.cpp
|
||||||
GCode/PrintExtents.hpp
|
GCode/PrintExtents.hpp
|
||||||
|
GCode/RetractWhenCrossingPerimeters.cpp
|
||||||
|
GCode/RetractWhenCrossingPerimeters.hpp
|
||||||
GCode/SpiralVase.cpp
|
GCode/SpiralVase.cpp
|
||||||
GCode/SpiralVase.hpp
|
GCode/SpiralVase.hpp
|
||||||
GCode/SeamPlacer.cpp
|
GCode/SeamPlacer.cpp
|
||||||
|
|
|
@ -833,6 +833,8 @@ Polylines _clipper_pl_closed(ClipperLib::ClipType clipType, PathProvider1 &&subj
|
||||||
return retval;
|
return retval;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Slic3r::Polylines diff_pl(const Slic3r::Polyline& subject, const Slic3r::Polygons& clip)
|
||||||
|
{ return _clipper_pl_open(ClipperLib::ctDifference, ClipperUtils::SinglePathProvider(subject.points), ClipperUtils::PolygonsProvider(clip)); }
|
||||||
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::Polygons &clip)
|
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::Polygons &clip)
|
||||||
{ return _clipper_pl_open(ClipperLib::ctDifference, ClipperUtils::PolylinesProvider(subject), ClipperUtils::PolygonsProvider(clip)); }
|
{ return _clipper_pl_open(ClipperLib::ctDifference, ClipperUtils::PolylinesProvider(subject), ClipperUtils::PolygonsProvider(clip)); }
|
||||||
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip)
|
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip)
|
||||||
|
|
|
@ -430,6 +430,7 @@ Slic3r::ExPolygons diff_ex(const Slic3r::Surfaces &subject, const Slic3r::ExPoly
|
||||||
Slic3r::ExPolygons diff_ex(const Slic3r::ExPolygons &subject, const Slic3r::Surfaces &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
Slic3r::ExPolygons diff_ex(const Slic3r::ExPolygons &subject, const Slic3r::Surfaces &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
||||||
Slic3r::ExPolygons diff_ex(const Slic3r::Surfaces &subject, const Slic3r::Surfaces &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
Slic3r::ExPolygons diff_ex(const Slic3r::Surfaces &subject, const Slic3r::Surfaces &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
||||||
Slic3r::ExPolygons diff_ex(const Slic3r::SurfacesPtr &subject, const Slic3r::Polygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
Slic3r::ExPolygons diff_ex(const Slic3r::SurfacesPtr &subject, const Slic3r::Polygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
|
||||||
|
Slic3r::Polylines diff_pl(const Slic3r::Polyline& subject, const Slic3r::Polygons& clip);
|
||||||
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::Polygons &clip);
|
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::Polygons &clip);
|
||||||
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip);
|
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip);
|
||||||
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::ExPolygon &clip);
|
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::ExPolygon &clip);
|
||||||
|
|
|
@ -4064,7 +4064,7 @@ bool GCode::needs_retraction(const Polyline &travel, ExtrusionRole role, LiftTyp
|
||||||
}
|
}
|
||||||
//BBS: need retract when long moving to print perimeter to avoid dropping of material
|
//BBS: need retract when long moving to print perimeter to avoid dropping of material
|
||||||
if (!is_perimeter(role) && m_config.reduce_infill_retraction && m_layer != nullptr &&
|
if (!is_perimeter(role) && m_config.reduce_infill_retraction && m_layer != nullptr &&
|
||||||
m_config.sparse_infill_density.value > 0 && m_layer->any_internal_region_slmplify_slice_contains(travel))
|
m_config.sparse_infill_density.value > 0 && m_retract_when_crossing_perimeters.travel_inside_internal_regions(*m_layer, travel))
|
||||||
// Skip retraction if travel is contained in an internal slice *and*
|
// Skip retraction if travel is contained in an internal slice *and*
|
||||||
// internal infill is enabled (so that stringing is entirely not visible).
|
// internal infill is enabled (so that stringing is entirely not visible).
|
||||||
//FIXME any_internal_region_slice_contains() is potentionally very slow, it shall test for the bounding boxes first.
|
//FIXME any_internal_region_slice_contains() is potentionally very slow, it shall test for the bounding boxes first.
|
||||||
|
|
|
@ -10,6 +10,7 @@
|
||||||
#include "PrintConfig.hpp"
|
#include "PrintConfig.hpp"
|
||||||
#include "GCode/AvoidCrossingPerimeters.hpp"
|
#include "GCode/AvoidCrossingPerimeters.hpp"
|
||||||
#include "GCode/CoolingBuffer.hpp"
|
#include "GCode/CoolingBuffer.hpp"
|
||||||
|
#include "GCode/RetractWhenCrossingPerimeters.hpp"
|
||||||
#include "GCode/SpiralVase.hpp"
|
#include "GCode/SpiralVase.hpp"
|
||||||
#include "GCode/ToolOrdering.hpp"
|
#include "GCode/ToolOrdering.hpp"
|
||||||
#include "GCode/WipeTower.hpp"
|
#include "GCode/WipeTower.hpp"
|
||||||
|
@ -423,6 +424,7 @@ private:
|
||||||
OozePrevention m_ooze_prevention;
|
OozePrevention m_ooze_prevention;
|
||||||
Wipe m_wipe;
|
Wipe m_wipe;
|
||||||
AvoidCrossingPerimeters m_avoid_crossing_perimeters;
|
AvoidCrossingPerimeters m_avoid_crossing_perimeters;
|
||||||
|
RetractWhenCrossingPerimeters m_retract_when_crossing_perimeters;
|
||||||
bool m_enable_loop_clipping;
|
bool m_enable_loop_clipping;
|
||||||
// If enabled, the G-code generator will put following comments at the ends
|
// If enabled, the G-code generator will put following comments at the ends
|
||||||
// of the G-code lines: _EXTRUDE_SET_SPEED, _WIPE, _OVERHANG_FAN_START, _OVERHANG_FAN_END
|
// of the G-code lines: _EXTRUDE_SET_SPEED, _WIPE, _OVERHANG_FAN_START, _OVERHANG_FAN_END
|
||||||
|
|
|
@ -0,0 +1,54 @@
|
||||||
|
#include "../ClipperUtils.hpp"
|
||||||
|
#include "../Layer.hpp"
|
||||||
|
#include "../Polyline.hpp"
|
||||||
|
|
||||||
|
#include "RetractWhenCrossingPerimeters.hpp"
|
||||||
|
|
||||||
|
namespace Slic3r {
|
||||||
|
|
||||||
|
bool RetractWhenCrossingPerimeters::travel_inside_internal_regions(const Layer &layer, const Polyline &travel)
|
||||||
|
{
|
||||||
|
if (m_layer != &layer) {
|
||||||
|
// Update cache.
|
||||||
|
m_layer = &layer;
|
||||||
|
m_internal_islands.clear();
|
||||||
|
m_aabbtree_internal_islands.clear();
|
||||||
|
// Collect expolygons of internal slices.
|
||||||
|
for (const LayerRegion *layerm : layer.regions())
|
||||||
|
for (const Surface &surface : layerm->get_slices_simplified().surfaces)
|
||||||
|
if (surface.is_internal())
|
||||||
|
m_internal_islands.emplace_back(&surface.expolygon);
|
||||||
|
// Calculate bounding boxes of internal slices.
|
||||||
|
std::vector<AABBTreeIndirect::BoundingBoxWrapper> bboxes;
|
||||||
|
bboxes.reserve(m_internal_islands.size());
|
||||||
|
for (size_t i = 0; i < m_internal_islands.size(); ++ i)
|
||||||
|
bboxes.emplace_back(i, get_extents(*m_internal_islands[i]));
|
||||||
|
// Build AABB tree over bounding boxes of internal slices.
|
||||||
|
m_aabbtree_internal_islands.build_modify_input(bboxes);
|
||||||
|
}
|
||||||
|
|
||||||
|
BoundingBox bbox_travel = get_extents(travel);
|
||||||
|
AABBTree::BoundingBox bbox_travel_eigen{ bbox_travel.min, bbox_travel.max };
|
||||||
|
int result = -1;
|
||||||
|
bbox_travel.offset(SCALED_EPSILON);
|
||||||
|
AABBTreeIndirect::traverse(m_aabbtree_internal_islands,
|
||||||
|
[&bbox_travel_eigen](const AABBTree::Node &node) {
|
||||||
|
return bbox_travel_eigen.intersects(node.bbox);
|
||||||
|
},
|
||||||
|
[&travel, &bbox_travel, &result, &islands = m_internal_islands](const AABBTree::Node &node) {
|
||||||
|
assert(node.is_leaf());
|
||||||
|
assert(node.is_valid());
|
||||||
|
Polygons clipped = ClipperUtils::clip_clipper_polygons_with_subject_bbox(*islands[node.idx], bbox_travel);
|
||||||
|
if (diff_pl(travel, clipped).empty()) {
|
||||||
|
// Travel path is completely inside an "internal" island. Don't retract.
|
||||||
|
result = int(node.idx);
|
||||||
|
// Stop traversal.
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
// Continue traversal.
|
||||||
|
return true;
|
||||||
|
});
|
||||||
|
return result != -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace Slic3r
|
|
@ -0,0 +1,32 @@
|
||||||
|
#ifndef slic3r_RetractWhenCrossingPerimeters_hpp_
|
||||||
|
#define slic3r_RetractWhenCrossingPerimeters_hpp_
|
||||||
|
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#include "../AABBTreeIndirect.hpp"
|
||||||
|
|
||||||
|
namespace Slic3r {
|
||||||
|
|
||||||
|
// Forward declarations.
|
||||||
|
class ExPolygon;
|
||||||
|
class Layer;
|
||||||
|
class Polyline;
|
||||||
|
|
||||||
|
class RetractWhenCrossingPerimeters
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
bool travel_inside_internal_regions(const Layer &layer, const Polyline &travel);
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Last object layer visited, for which a cache of internal islands was created.
|
||||||
|
const Layer *m_layer;
|
||||||
|
// Internal islands only, referencing data owned by m_layer->regions()->surfaces().
|
||||||
|
std::vector<const ExPolygon*> m_internal_islands;
|
||||||
|
// Search structure over internal islands.
|
||||||
|
using AABBTree = AABBTreeIndirect::Tree<2, coord_t>;
|
||||||
|
AABBTree m_aabbtree_internal_islands;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace Slic3r
|
||||||
|
|
||||||
|
#endif // slic3r_RetractWhenCrossingPerimeters_hpp_
|
|
@ -30,6 +30,9 @@ public:
|
||||||
const Layer* layer() const { return m_layer; }
|
const Layer* layer() const { return m_layer; }
|
||||||
const PrintRegion& region() const { return *m_region; }
|
const PrintRegion& region() const { return *m_region; }
|
||||||
|
|
||||||
|
const SurfaceCollection& get_slices() const { return slices; }
|
||||||
|
const SurfaceCollection& get_slices_simplified() const { return slices_simplified; }
|
||||||
|
|
||||||
// collection of surfaces generated by slicing the original geometry
|
// collection of surfaces generated by slicing the original geometry
|
||||||
// divided by type top/bottom/internal
|
// divided by type top/bottom/internal
|
||||||
SurfaceCollection slices;
|
SurfaceCollection slices;
|
||||||
|
@ -170,11 +173,6 @@ public:
|
||||||
for (const LayerRegion *layerm : m_regions) if (layerm->slices.any_internal_contains(item)) return true;
|
for (const LayerRegion *layerm : m_regions) if (layerm->slices.any_internal_contains(item)) return true;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
//BBS: only be used in gcode export when reduce_infill_retraction is enabled
|
|
||||||
template <class T> bool any_internal_region_slmplify_slice_contains(const T& item) const {
|
|
||||||
for (const LayerRegion* layerm : m_regions) if (layerm->slices_simplified.any_internal_contains(item)) return true;
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
template <class T> bool any_bottom_region_slice_contains(const T &item) const {
|
template <class T> bool any_bottom_region_slice_contains(const T &item) const {
|
||||||
for (const LayerRegion *layerm : m_regions) if (layerm->slices.any_bottom_contains(item)) return true;
|
for (const LayerRegion *layerm : m_regions) if (layerm->slices.any_bottom_contains(item)) return true;
|
||||||
return false;
|
return false;
|
||||||
|
|
|
@ -335,6 +335,7 @@ remove_unconnected_vertices(const indexed_triangle_set &its)
|
||||||
// Drill holes into the hollowed/original mesh.
|
// Drill holes into the hollowed/original mesh.
|
||||||
void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
||||||
{
|
{
|
||||||
|
/*
|
||||||
bool needs_drilling = ! po.m_model_object->sla_drain_holes.empty();
|
bool needs_drilling = ! po.m_model_object->sla_drain_holes.empty();
|
||||||
bool is_hollowed =
|
bool is_hollowed =
|
||||||
(po.m_hollowing_data && po.m_hollowing_data->interior &&
|
(po.m_hollowing_data && po.m_hollowing_data->interior &&
|
||||||
|
@ -465,6 +466,7 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
||||||
if (hole_fail)
|
if (hole_fail)
|
||||||
po.active_step_add_warning(PrintStateBase::WarningLevel::NON_CRITICAL,
|
po.active_step_add_warning(PrintStateBase::WarningLevel::NON_CRITICAL,
|
||||||
L("Failed to drill some holes into the model"));
|
L("Failed to drill some holes into the model"));
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
// The slicing will be performed on an imaginary 1D grid which starts from
|
// The slicing will be performed on an imaginary 1D grid which starts from
|
||||||
|
|
Loading…
Reference in New Issue