Merge branch 'master' of https://github.com/Prusa-Development/PrusaSlicerPrivate
This commit is contained in:
commit
4a0b1c77a7
@ -920,29 +920,35 @@ template<class G> auto within(const G &g) { return Within<G>{g}; }
|
||||
|
||||
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>
|
||||
void traverse_recurse(const Tree<Dims, T> &tree,
|
||||
bool traverse_recurse(const Tree<Dims, T> &tree,
|
||||
size_t idx,
|
||||
Pred && pred,
|
||||
Fn && callback)
|
||||
{
|
||||
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()) {
|
||||
callback(tree.node(idx));
|
||||
// Callback returns true to continue traversal, false to stop traversal.
|
||||
return callback(tree.node(idx));
|
||||
} else {
|
||||
|
||||
// call this with left and right node idx:
|
||||
auto trv = [&](size_t idx) {
|
||||
traverse_recurse(tree, idx, std::forward<Pred>(pred),
|
||||
std::forward<Fn>(callback));
|
||||
auto trv = [&](size_t idx) -> bool {
|
||||
return traverse_recurse(tree, idx, std::forward<Pred>(pred),
|
||||
std::forward<Fn>(callback));
|
||||
};
|
||||
|
||||
// Left / right child node index.
|
||||
trv(Tree<Dims, T>::left_child_idx(idx));
|
||||
trv(Tree<Dims, T>::right_child_idx(idx));
|
||||
// Returns true if both children allow the traversal to continue.
|
||||
return trv(Tree<Dims, T>::left_child_idx(idx)) &&
|
||||
trv(Tree<Dims, T>::right_child_idx(idx));
|
||||
}
|
||||
}
|
||||
|
||||
@ -952,6 +958,7 @@ void traverse_recurse(const Tree<Dims, T> &tree,
|
||||
// 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>
|
||||
void traverse(const Tree<Dims, T> &tree, Predicate &&pred, Fn &&callback)
|
||||
{
|
||||
|
@ -130,6 +130,8 @@ set(SLIC3R_SOURCES
|
||||
GCode/PressureEqualizer.hpp
|
||||
GCode/PrintExtents.cpp
|
||||
GCode/PrintExtents.hpp
|
||||
GCode/RetractWhenCrossingPerimeters.cpp
|
||||
GCode/RetractWhenCrossingPerimeters.hpp
|
||||
GCode/SpiralVase.cpp
|
||||
GCode/SpiralVase.hpp
|
||||
GCode/SeamPlacer.cpp
|
||||
|
@ -140,6 +140,21 @@ namespace ClipperUtils {
|
||||
out.reserve(src.size());
|
||||
for (const Polygon &p : src)
|
||||
out.emplace_back(clip_clipper_polygon_with_subject_bbox(p, bbox));
|
||||
out.erase(
|
||||
std::remove_if(out.begin(), out.end(), [](const Polygon &polygon) { return polygon.empty(); }),
|
||||
out.end());
|
||||
return out;
|
||||
}
|
||||
[[nodiscard]] Polygons clip_clipper_polygons_with_subject_bbox(const ExPolygon &src, const BoundingBox &bbox)
|
||||
{
|
||||
Polygons out;
|
||||
out.reserve(src.num_contours());
|
||||
out.emplace_back(clip_clipper_polygon_with_subject_bbox(src.contour, bbox));
|
||||
for (const Polygon &p : src.holes)
|
||||
out.emplace_back(clip_clipper_polygon_with_subject_bbox(p, bbox));
|
||||
out.erase(
|
||||
std::remove_if(out.begin(), out.end(), [](const Polygon &polygon) { return polygon.empty(); }),
|
||||
out.end());
|
||||
return out;
|
||||
}
|
||||
}
|
||||
@ -794,6 +809,8 @@ Polylines _clipper_pl_closed(ClipperLib::ClipType clipType, PathProvider1 &&subj
|
||||
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)
|
||||
{ return _clipper_pl_open(ClipperLib::ctDifference, ClipperUtils::PolylinesProvider(subject), ClipperUtils::PolygonsProvider(clip)); }
|
||||
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip)
|
||||
|
@ -323,6 +323,7 @@ namespace ClipperUtils {
|
||||
void clip_clipper_polygon_with_subject_bbox(const Polygon &src, const BoundingBox &bbox, Polygon &out);
|
||||
[[nodiscard]] Polygon clip_clipper_polygon_with_subject_bbox(const Polygon &src, const BoundingBox &bbox);
|
||||
[[nodiscard]] Polygons clip_clipper_polygons_with_subject_bbox(const Polygons &src, const BoundingBox &bbox);
|
||||
[[nodiscard]] Polygons clip_clipper_polygons_with_subject_bbox(const ExPolygon &src, const BoundingBox &bbox);
|
||||
}
|
||||
|
||||
// offset Polygons
|
||||
@ -427,6 +428,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::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::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::Polyline &subject, const Slic3r::ExPolygon &clip);
|
||||
Slic3r::Polylines diff_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygons &clip);
|
||||
|
@ -3090,7 +3090,7 @@ bool GCode::needs_retraction(const Polyline &travel, ExtrusionRole role)
|
||||
}
|
||||
|
||||
if (m_config.only_retract_when_crossing_perimeters && m_layer != nullptr &&
|
||||
m_config.fill_density.value > 0 && m_layer->any_internal_region_slice_contains(travel))
|
||||
m_config.fill_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*
|
||||
// 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.
|
||||
|
@ -12,6 +12,7 @@
|
||||
#include "GCode/AvoidCrossingPerimeters.hpp"
|
||||
#include "GCode/CoolingBuffer.hpp"
|
||||
#include "GCode/FindReplace.hpp"
|
||||
#include "GCode/RetractWhenCrossingPerimeters.hpp"
|
||||
#include "GCode/SpiralVase.hpp"
|
||||
#include "GCode/ToolOrdering.hpp"
|
||||
#include "GCode/WipeTower.hpp"
|
||||
@ -349,6 +350,7 @@ private:
|
||||
Wipe m_wipe;
|
||||
AvoidCrossingPerimeters m_avoid_crossing_perimeters;
|
||||
JPSPathFinder m_avoid_curled_filaments;
|
||||
RetractWhenCrossingPerimeters m_retract_when_crossing_perimeters;
|
||||
bool m_enable_loop_clipping;
|
||||
// If enabled, the G-code generator will put following comments at the ends
|
||||
// of the G-code lines: _EXTRUDE_SET_SPEED, _WIPE, _BRIDGE_FAN_START, _BRIDGE_FAN_END
|
||||
|
67
src/libslic3r/GCode/RetractWhenCrossingPerimeters.cpp
Normal file
67
src/libslic3r/GCode/RetractWhenCrossingPerimeters.cpp
Normal file
@ -0,0 +1,67 @@
|
||||
#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->slices().surfaces)
|
||||
if (surface.is_internal())
|
||||
m_internal_islands.emplace_back(&surface.expolygon);
|
||||
// Calculate bounding boxes of internal slices.
|
||||
class BBoxWrapper {
|
||||
public:
|
||||
BBoxWrapper(const size_t idx, const BoundingBox &bbox) :
|
||||
m_idx(idx),
|
||||
// Inflate the bounding box a bit to account for numerical issues.
|
||||
m_bbox(bbox.min - Point(SCALED_EPSILON, SCALED_EPSILON), bbox.max + Point(SCALED_EPSILON, SCALED_EPSILON)) {}
|
||||
size_t idx() const { return m_idx; }
|
||||
const AABBTree::BoundingBox& bbox() const { return m_bbox; }
|
||||
Point centroid() const { return ((m_bbox.min().cast<int64_t>() + m_bbox.max().cast<int64_t>()) / 2).cast<int32_t>(); }
|
||||
private:
|
||||
size_t m_idx;
|
||||
AABBTree::BoundingBox m_bbox;
|
||||
};
|
||||
std::vector<BBoxWrapper> bboxes;
|
||||
bboxes.reserve(m_internal_islands.size());
|
||||
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
|
32
src/libslic3r/GCode/RetractWhenCrossingPerimeters.hpp
Normal file
32
src/libslic3r/GCode/RetractWhenCrossingPerimeters.hpp
Normal file
@ -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_
|
@ -108,7 +108,7 @@ Circled circle_taubin_newton(const Vec2ds& input, size_t cycles)
|
||||
return out;
|
||||
}
|
||||
|
||||
Circled circle_ransac(const Vec2ds& input, size_t iterations)
|
||||
Circled circle_ransac(const Vec2ds& input, size_t iterations, double* min_error)
|
||||
{
|
||||
if (input.size() < 3)
|
||||
return Circled::make_invalid();
|
||||
@ -132,6 +132,8 @@ Circled circle_ransac(const Vec2ds& input, size_t iterations)
|
||||
circle_best = c;
|
||||
}
|
||||
}
|
||||
if (min_error)
|
||||
*min_error = err_min;
|
||||
return circle_best;
|
||||
}
|
||||
|
||||
|
@ -102,7 +102,7 @@ inline Vec2d circle_center_taubin_newton(const Vec2ds& input, size_t cycles = 20
|
||||
Circled circle_taubin_newton(const Vec2ds& input, size_t cycles = 20);
|
||||
|
||||
// Find circle using RANSAC randomized algorithm.
|
||||
Circled circle_ransac(const Vec2ds& input, size_t iterations = 20);
|
||||
Circled circle_ransac(const Vec2ds& input, size_t iterations = 20, double* min_error = nullptr);
|
||||
|
||||
// Randomized algorithm by Emo Welzl, working with squared radii for efficiency. The returned circle radius is inflated by epsilon.
|
||||
template<typename Vector, typename Points>
|
||||
|
@ -8,13 +8,15 @@
|
||||
|
||||
#include <numeric>
|
||||
|
||||
#define DEBUG_EXTRACT_ALL_FEATURES_AT_ONCE 0
|
||||
|
||||
namespace Slic3r {
|
||||
namespace Measure {
|
||||
|
||||
|
||||
constexpr double feature_hover_limit = 0.5; // how close to a feature the mouse must be to highlight it
|
||||
|
||||
static std::pair<Vec3d, double> get_center_and_radius(const std::vector<Vec3d>& points, const Transform3d& trafo)
|
||||
static std::tuple<Vec3d, double, double> get_center_and_radius(const std::vector<Vec3d>& points, const Transform3d& trafo, const Transform3d& trafo_inv)
|
||||
{
|
||||
Vec2ds out;
|
||||
double z = 0.;
|
||||
@ -24,18 +26,17 @@ static std::pair<Vec3d, double> get_center_and_radius(const std::vector<Vec3d>&
|
||||
out.emplace_back(pt_transformed.x(), pt_transformed.y());
|
||||
}
|
||||
|
||||
auto circle = Geometry::circle_ransac(out, 20); // FIXME: iterations?
|
||||
const int iter = points.size() < 10 ? 2 :
|
||||
points.size() < 100 ? 4 :
|
||||
6;
|
||||
|
||||
return std::make_pair(trafo.inverse() * Vec3d(circle.center.x(), circle.center.y(), z), circle.radius);
|
||||
double error = std::numeric_limits<double>::max();
|
||||
auto circle = Geometry::circle_ransac(out, iter, &error);
|
||||
|
||||
return std::make_tuple(trafo.inverse() * Vec3d(circle.center.x(), circle.center.y(), z), circle.radius, error);
|
||||
}
|
||||
|
||||
static bool circle_fit_is_ok(const std::vector<Vec3d>& pts, const Vec3d& center, double radius)
|
||||
{
|
||||
for (const Vec3d& pt : pts)
|
||||
if (std::abs((pt - center).norm() - radius) > 0.05)
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
static std::array<Vec3d, 3> orthonormal_basis(const Vec3d& v)
|
||||
{
|
||||
@ -64,17 +65,18 @@ public:
|
||||
std::vector<SurfaceFeature> surface_features;
|
||||
Vec3d normal;
|
||||
float area;
|
||||
bool features_extracted = false;
|
||||
};
|
||||
|
||||
std::vector<SurfaceFeature> get_all_features() const;
|
||||
std::optional<SurfaceFeature> get_feature(size_t face_idx, const Vec3d& point) const;
|
||||
std::vector<std::vector<int>> get_planes_triangle_indices() const;
|
||||
const std::vector<SurfaceFeature>& get_plane_features(unsigned int plane_id) const;
|
||||
std::optional<SurfaceFeature> get_feature(size_t face_idx, const Vec3d& point);
|
||||
int get_num_of_planes() const;
|
||||
const std::vector<int>& get_plane_triangle_indices(int idx) const;
|
||||
const std::vector<SurfaceFeature>& get_plane_features(unsigned int plane_id);
|
||||
const TriangleMesh& get_mesh() const;
|
||||
|
||||
private:
|
||||
void update_planes();
|
||||
void extract_features();
|
||||
void extract_features(int plane_idx);
|
||||
|
||||
std::vector<PlaneData> m_planes;
|
||||
std::vector<size_t> m_face_to_plane;
|
||||
@ -90,7 +92,13 @@ MeasuringImpl::MeasuringImpl(const indexed_triangle_set& its)
|
||||
: m_mesh(its)
|
||||
{
|
||||
update_planes();
|
||||
extract_features();
|
||||
|
||||
// Extracting features will be done as needed.
|
||||
// To extract all planes at once, run the following:
|
||||
#if DEBUG_EXTRACT_ALL_FEATURES_AT_ONCE
|
||||
for (int i=0; i<int(m_planes.size()); ++i)
|
||||
extract_features(i);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@ -252,30 +260,33 @@ void MeasuringImpl::update_planes()
|
||||
|
||||
|
||||
|
||||
void MeasuringImpl::extract_features()
|
||||
void MeasuringImpl::extract_features(int plane_idx)
|
||||
{
|
||||
assert(! m_planes[plane_idx].features_extracted);
|
||||
|
||||
PlaneData& plane = m_planes[plane_idx];
|
||||
plane.surface_features.clear();
|
||||
const Vec3d& normal = plane.normal;
|
||||
|
||||
Eigen::Quaterniond q;
|
||||
q.setFromTwoVectors(plane.normal, Vec3d::UnitZ());
|
||||
Transform3d trafo = Transform3d::Identity();
|
||||
trafo.rotate(q);
|
||||
const Transform3d trafo_inv = trafo.inverse();
|
||||
|
||||
std::vector<double> angles; // placed in outer scope to prevent reallocations
|
||||
std::vector<double> lengths;
|
||||
|
||||
for (const std::vector<Vec3d>& border : plane.borders) {
|
||||
if (border.size() <= 1)
|
||||
continue;
|
||||
|
||||
for (int i=0; i<(int)m_planes.size(); ++i) {
|
||||
PlaneData& plane = m_planes[i];
|
||||
plane.surface_features.clear();
|
||||
const Vec3d& normal = plane.normal;
|
||||
bool done = false;
|
||||
|
||||
Eigen::Quaterniond q;
|
||||
q.setFromTwoVectors(plane.normal, Vec3d::UnitZ());
|
||||
Transform3d trafo = Transform3d::Identity();
|
||||
trafo.rotate(q);
|
||||
if (border.size() > 4) {
|
||||
const auto& [center, radius, err] = get_center_and_radius(border, trafo, trafo_inv);
|
||||
|
||||
for (const std::vector<Vec3d>& border : plane.borders) {
|
||||
if (border.size() <= 1)
|
||||
continue;
|
||||
|
||||
bool done = false;
|
||||
|
||||
if (const auto& [center, radius] = get_center_and_radius(border, trafo);
|
||||
(border.size()>4) && circle_fit_is_ok(border, center, radius)) {
|
||||
if (err < 0.05) {
|
||||
// The whole border is one circle. Just add it into the list of features
|
||||
// and we are done.
|
||||
|
||||
@ -298,200 +309,190 @@ void MeasuringImpl::extract_features()
|
||||
done = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (! done) {
|
||||
// In this case, the border is not a circle and may contain circular
|
||||
// segments. Try to find them and then add all remaining edges as edges.
|
||||
if (! done) {
|
||||
// In this case, the border is not a circle and may contain circular
|
||||
// segments. Try to find them and then add all remaining edges as edges.
|
||||
|
||||
auto are_angles_same = [](double a, double b) { return Slic3r::is_approx(a,b,0.01); };
|
||||
auto are_lengths_same = [](double a, double b) { return Slic3r::is_approx(a,b,0.01); };
|
||||
auto are_angles_same = [](double a, double b) { return Slic3r::is_approx(a,b,0.01); };
|
||||
auto are_lengths_same = [](double a, double b) { return Slic3r::is_approx(a,b,0.01); };
|
||||
|
||||
|
||||
// Given an idx into border, return the index that is idx+offset position,
|
||||
// while taking into account the need for wrap-around and the fact that
|
||||
// the first and last point are the same.
|
||||
auto offset_to_index = [border_size = int(border.size())](int idx, int offset) -> int {
|
||||
assert(std::abs(offset) < border_size);
|
||||
int out = idx+offset;
|
||||
if (out >= border_size)
|
||||
out = out - border_size;
|
||||
else if (out < 0)
|
||||
out = border_size + out;
|
||||
// Given an idx into border, return the index that is idx+offset position,
|
||||
// while taking into account the need for wrap-around and the fact that
|
||||
// the first and last point are the same.
|
||||
auto offset_to_index = [border_size = int(border.size())](int idx, int offset) -> int {
|
||||
assert(std::abs(offset) < border_size);
|
||||
int out = idx+offset;
|
||||
if (out >= border_size)
|
||||
out = out - border_size;
|
||||
else if (out < 0)
|
||||
out = border_size + out;
|
||||
|
||||
return out;
|
||||
};
|
||||
return out;
|
||||
};
|
||||
|
||||
// First calculate angles at all the vertices.
|
||||
angles.clear();
|
||||
lengths.clear();
|
||||
int first_different_angle_idx = 0;
|
||||
for (int i=0; i<int(border.size()); ++i) {
|
||||
const Vec3d& v2 = border[i] - (i == 0 ? border[border.size()-1] : border[i-1]);
|
||||
const Vec3d& v1 = (i == int(border.size()-1) ? border[0] : border[i+1]) - border[i];
|
||||
double angle = atan2(-normal.dot(v1.cross(v2)), -v1.dot(v2)) + M_PI;
|
||||
if (angle > M_PI)
|
||||
angle = 2*M_PI - angle;
|
||||
// First calculate angles at all the vertices.
|
||||
angles.clear();
|
||||
lengths.clear();
|
||||
int first_different_angle_idx = 0;
|
||||
for (int i=0; i<int(border.size()); ++i) {
|
||||
const Vec3d& v2 = border[i] - (i == 0 ? border[border.size()-1] : border[i-1]);
|
||||
const Vec3d& v1 = (i == int(border.size()-1) ? border[0] : border[i+1]) - border[i];
|
||||
double angle = atan2(-normal.dot(v1.cross(v2)), -v1.dot(v2)) + M_PI;
|
||||
if (angle > M_PI)
|
||||
angle = 2*M_PI - angle;
|
||||
|
||||
angles.push_back(angle);
|
||||
lengths.push_back(v2.norm());
|
||||
if (first_different_angle_idx == 0 && angles.size() > 1) {
|
||||
if (! are_angles_same(angles.back(), angles[angles.size()-2]))
|
||||
first_different_angle_idx = angles.size()-1;
|
||||
}
|
||||
angles.push_back(angle);
|
||||
lengths.push_back(v2.norm());
|
||||
if (first_different_angle_idx == 0 && angles.size() > 1) {
|
||||
if (! are_angles_same(angles.back(), angles[angles.size()-2]))
|
||||
first_different_angle_idx = angles.size()-1;
|
||||
}
|
||||
assert(border.size() == angles.size());
|
||||
assert(border.size() == lengths.size());
|
||||
}
|
||||
assert(border.size() == angles.size());
|
||||
assert(border.size() == lengths.size());
|
||||
|
||||
// First go around the border and pick what might be circular segments.
|
||||
// Save pair of indices to where such potential segments start and end.
|
||||
// Also remember the length of these segments.
|
||||
int start_idx = -1;
|
||||
bool circle = false;
|
||||
bool first_iter = true;
|
||||
std::vector<SurfaceFeature> circles;
|
||||
std::vector<SurfaceFeature> edges;
|
||||
std::vector<std::pair<int, int>> circles_idxs;
|
||||
//std::vector<double> circles_lengths;
|
||||
std::vector<Vec3d> single_circle; // could be in loop-scope, but reallocations
|
||||
double single_circle_length = 0.;
|
||||
int first_pt_idx = offset_to_index(first_different_angle_idx, 1);
|
||||
int i = first_pt_idx;
|
||||
while (i != first_pt_idx || first_iter) {
|
||||
if (are_angles_same(angles[i], angles[offset_to_index(i,-1)])
|
||||
&& i != offset_to_index(first_pt_idx, -1) // not the last point
|
||||
&& i != start_idx ) {
|
||||
// circle
|
||||
if (! circle) {
|
||||
circle = true;
|
||||
single_circle.clear();
|
||||
single_circle_length = 0.;
|
||||
start_idx = offset_to_index(i, -2);
|
||||
single_circle = { border[start_idx], border[offset_to_index(start_idx,1)] };
|
||||
single_circle_length += lengths[offset_to_index(i, -1)];
|
||||
}
|
||||
// First go around the border and pick what might be circular segments.
|
||||
// Save pair of indices to where such potential segments start and end.
|
||||
// Also remember the length of these segments.
|
||||
int start_idx = -1;
|
||||
bool circle = false;
|
||||
bool first_iter = true;
|
||||
std::vector<SurfaceFeature> circles;
|
||||
std::vector<SurfaceFeature> edges;
|
||||
std::vector<std::pair<int, int>> circles_idxs;
|
||||
//std::vector<double> circles_lengths;
|
||||
std::vector<Vec3d> single_circle; // could be in loop-scope, but reallocations
|
||||
double single_circle_length = 0.;
|
||||
int first_pt_idx = offset_to_index(first_different_angle_idx, 1);
|
||||
int i = first_pt_idx;
|
||||
while (i != first_pt_idx || first_iter) {
|
||||
if (are_angles_same(angles[i], angles[offset_to_index(i,-1)])
|
||||
&& i != offset_to_index(first_pt_idx, -1) // not the last point
|
||||
&& i != start_idx ) {
|
||||
// circle
|
||||
if (! circle) {
|
||||
circle = true;
|
||||
single_circle.clear();
|
||||
single_circle_length = 0.;
|
||||
start_idx = offset_to_index(i, -2);
|
||||
single_circle = { border[start_idx], border[offset_to_index(start_idx,1)] };
|
||||
single_circle_length += lengths[offset_to_index(i, -1)];
|
||||
}
|
||||
single_circle.emplace_back(border[i]);
|
||||
single_circle_length += lengths[i];
|
||||
} else {
|
||||
if (circle && single_circle.size() >= 5) { // Less than 5 vertices? Not a circle.
|
||||
single_circle.emplace_back(border[i]);
|
||||
single_circle_length += lengths[i];
|
||||
} else {
|
||||
if (circle && single_circle.size() >= 5) { // Less than 5 vertices? Not a circle.
|
||||
single_circle.emplace_back(border[i]);
|
||||
single_circle_length += lengths[i];
|
||||
|
||||
bool accept_circle = true;
|
||||
{
|
||||
// Check that lengths of internal (!!!) edges match.
|
||||
int j = offset_to_index(start_idx, 3);
|
||||
while (j != i) {
|
||||
if (! are_lengths_same(lengths[offset_to_index(j,-1)], lengths[j])) {
|
||||
accept_circle = false;
|
||||
break;
|
||||
}
|
||||
j = offset_to_index(j, 1);
|
||||
bool accept_circle = true;
|
||||
{
|
||||
// Check that lengths of internal (!!!) edges match.
|
||||
int j = offset_to_index(start_idx, 3);
|
||||
while (j != i) {
|
||||
if (! are_lengths_same(lengths[offset_to_index(j,-1)], lengths[j])) {
|
||||
accept_circle = false;
|
||||
break;
|
||||
}
|
||||
j = offset_to_index(j, 1);
|
||||
}
|
||||
}
|
||||
|
||||
if (accept_circle) {
|
||||
const auto& [center, radius, err] = get_center_and_radius(single_circle, trafo, trafo_inv);
|
||||
|
||||
// Check that the fit went well. The tolerance is high, only to
|
||||
// reject complete failures.
|
||||
accept_circle &= err < 0.05;
|
||||
|
||||
// If the segment subtends less than 90 degrees, throw it away.
|
||||
accept_circle &= single_circle_length / radius > 0.9*M_PI/2.;
|
||||
|
||||
if (accept_circle) {
|
||||
const auto& [center, radius] = get_center_and_radius(single_circle, trafo);
|
||||
|
||||
// Check that the fit went well. The tolerance is high, only to
|
||||
// reject complete failures.
|
||||
accept_circle &= circle_fit_is_ok(single_circle, center, radius);
|
||||
|
||||
// If the segment subtends less than 90 degrees, throw it away.
|
||||
accept_circle &= single_circle_length / radius > 0.9*M_PI/2.;
|
||||
|
||||
if (accept_circle) {
|
||||
// Add the circle and remember indices into borders.
|
||||
circles_idxs.emplace_back(start_idx, i);
|
||||
circles.emplace_back(SurfaceFeature(SurfaceFeatureType::Circle, center, plane.normal, std::nullopt, radius));
|
||||
}
|
||||
// Add the circle and remember indices into borders.
|
||||
circles_idxs.emplace_back(start_idx, i);
|
||||
circles.emplace_back(SurfaceFeature(SurfaceFeatureType::Circle, center, plane.normal, std::nullopt, radius));
|
||||
}
|
||||
}
|
||||
circle = false;
|
||||
}
|
||||
// Take care of the wrap around.
|
||||
first_iter = false;
|
||||
circle = false;
|
||||
}
|
||||
// Take care of the wrap around.
|
||||
first_iter = false;
|
||||
i = offset_to_index(i, 1);
|
||||
}
|
||||
|
||||
// We have the circles. Now go around again and pick edges, while jumping over circles.
|
||||
if (circles_idxs.empty()) {
|
||||
// Just add all edges.
|
||||
for (int i=1; i<int(border.size()); ++i)
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[i-1], border[i]));
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[0], border[border.size()-1]));
|
||||
} else if (circles_idxs.size() > 1 || circles_idxs.front().first != circles_idxs.front().second) {
|
||||
// There is at least one circular segment. Start at its end and add edges until the start of the next one.
|
||||
int i = circles_idxs.front().second;
|
||||
int circle_idx = 1;
|
||||
while (true) {
|
||||
i = offset_to_index(i, 1);
|
||||
}
|
||||
|
||||
// We have the circles. Now go around again and pick edges, while jumping over circles.
|
||||
if (circles_idxs.empty()) {
|
||||
// Just add all edges.
|
||||
for (int i=1; i<int(border.size()); ++i)
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[i-1], border[i]));
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[0], border[border.size()-1]));
|
||||
} else if (circles_idxs.size() > 1 || circles_idxs.front().first != circles_idxs.front().second) {
|
||||
// There is at least one circular segment. Start at its end and add edges until the start of the next one.
|
||||
int i = circles_idxs.front().second;
|
||||
int circle_idx = 1;
|
||||
while (true) {
|
||||
i = offset_to_index(i, 1);
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[offset_to_index(i,-1)], border[i]));
|
||||
if (circle_idx < int(circles_idxs.size()) && i == circles_idxs[circle_idx].first) {
|
||||
i = circles_idxs[circle_idx].second;
|
||||
++circle_idx;
|
||||
}
|
||||
if (i == circles_idxs.front().first)
|
||||
break;
|
||||
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge, border[offset_to_index(i,-1)], border[i]));
|
||||
if (circle_idx < int(circles_idxs.size()) && i == circles_idxs[circle_idx].first) {
|
||||
i = circles_idxs[circle_idx].second;
|
||||
++circle_idx;
|
||||
}
|
||||
if (i == circles_idxs.front().first)
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// Merge adjacent edges where needed.
|
||||
assert(std::all_of(edges.begin(), edges.end(),
|
||||
[](const SurfaceFeature& f) { return f.get_type() == SurfaceFeatureType::Edge; }));
|
||||
for (int i=edges.size()-1; i>=0; --i) {
|
||||
const auto& [first_start, first_end] = edges[i==0 ? edges.size()-1 : i-1].get_edge();
|
||||
const auto& [second_start, second_end] = edges[i].get_edge();
|
||||
// Merge adjacent edges where needed.
|
||||
assert(std::all_of(edges.begin(), edges.end(),
|
||||
[](const SurfaceFeature& f) { return f.get_type() == SurfaceFeatureType::Edge; }));
|
||||
for (int i=edges.size()-1; i>=0; --i) {
|
||||
const auto& [first_start, first_end] = edges[i==0 ? edges.size()-1 : i-1].get_edge();
|
||||
const auto& [second_start, second_end] = edges[i].get_edge();
|
||||
|
||||
if (Slic3r::is_approx(first_end, second_start)
|
||||
&& Slic3r::is_approx((first_end-first_start).normalized().dot((second_end-second_start).normalized()), 1.)) {
|
||||
// The edges have the same direction and share a point. Merge them.
|
||||
edges[i==0 ? edges.size()-1 : i-1] = SurfaceFeature(SurfaceFeatureType::Edge, first_start, second_end);
|
||||
edges.erase(edges.begin() + i);
|
||||
}
|
||||
if (Slic3r::is_approx(first_end, second_start)
|
||||
&& Slic3r::is_approx((first_end-first_start).normalized().dot((second_end-second_start).normalized()), 1.)) {
|
||||
// The edges have the same direction and share a point. Merge them.
|
||||
edges[i==0 ? edges.size()-1 : i-1] = SurfaceFeature(SurfaceFeatureType::Edge, first_start, second_end);
|
||||
edges.erase(edges.begin() + i);
|
||||
}
|
||||
|
||||
// Now move the circles and edges into the feature list for the plane.
|
||||
assert(std::all_of(circles.begin(), circles.end(), [](const SurfaceFeature& f) {
|
||||
return f.get_type() == SurfaceFeatureType::Circle;
|
||||
}));
|
||||
assert(std::all_of(edges.begin(), edges.end(), [](const SurfaceFeature& f) {
|
||||
return f.get_type() == SurfaceFeatureType::Edge;
|
||||
}));
|
||||
plane.surface_features.insert(plane.surface_features.end(), std::make_move_iterator(circles.begin()),
|
||||
std::make_move_iterator(circles.end()));
|
||||
plane.surface_features.insert(plane.surface_features.end(), std::make_move_iterator(edges.begin()),
|
||||
std::make_move_iterator(edges.end()));
|
||||
}
|
||||
}
|
||||
|
||||
// The last surface feature is the plane itself.
|
||||
Vec3d cog = Vec3d::Zero();
|
||||
size_t counter = 0;
|
||||
for (const std::vector<Vec3d>& b : plane.borders) {
|
||||
for (size_t i = 1; i < b.size(); ++i) {
|
||||
cog += b[i];
|
||||
++counter;
|
||||
}
|
||||
// Now move the circles and edges into the feature list for the plane.
|
||||
assert(std::all_of(circles.begin(), circles.end(), [](const SurfaceFeature& f) {
|
||||
return f.get_type() == SurfaceFeatureType::Circle;
|
||||
}));
|
||||
assert(std::all_of(edges.begin(), edges.end(), [](const SurfaceFeature& f) {
|
||||
return f.get_type() == SurfaceFeatureType::Edge;
|
||||
}));
|
||||
plane.surface_features.insert(plane.surface_features.end(), std::make_move_iterator(circles.begin()),
|
||||
std::make_move_iterator(circles.end()));
|
||||
plane.surface_features.insert(plane.surface_features.end(), std::make_move_iterator(edges.begin()),
|
||||
std::make_move_iterator(edges.end()));
|
||||
}
|
||||
cog /= double(counter);
|
||||
plane.surface_features.emplace_back(SurfaceFeature(SurfaceFeatureType::Plane,
|
||||
plane.normal, cog, std::optional<Vec3d>(), i + 0.0001));
|
||||
|
||||
plane.borders.clear();
|
||||
plane.borders.shrink_to_fit();
|
||||
}
|
||||
}
|
||||
|
||||
// The last surface feature is the plane itself.
|
||||
Vec3d cog = Vec3d::Zero();
|
||||
size_t counter = 0;
|
||||
for (const std::vector<Vec3d>& b : plane.borders) {
|
||||
for (size_t i = 1; i < b.size(); ++i) {
|
||||
cog += b[i];
|
||||
++counter;
|
||||
}
|
||||
}
|
||||
cog /= double(counter);
|
||||
plane.surface_features.emplace_back(SurfaceFeature(SurfaceFeatureType::Plane,
|
||||
plane.normal, cog, std::optional<Vec3d>(), plane_idx + 0.0001));
|
||||
|
||||
plane.borders.clear();
|
||||
plane.borders.shrink_to_fit();
|
||||
|
||||
std::vector<SurfaceFeature> MeasuringImpl::get_all_features() const
|
||||
{
|
||||
std::vector<SurfaceFeature> features;
|
||||
//PlaneData& plane = m_planes[0];
|
||||
for (const PlaneData& plane : m_planes)
|
||||
for (const SurfaceFeature& feature : plane.surface_features)
|
||||
features.emplace_back(feature);
|
||||
return features;
|
||||
plane.features_extracted = true;
|
||||
}
|
||||
|
||||
|
||||
@ -499,12 +500,17 @@ std::vector<SurfaceFeature> MeasuringImpl::get_all_features() const
|
||||
|
||||
|
||||
|
||||
std::optional<SurfaceFeature> MeasuringImpl::get_feature(size_t face_idx, const Vec3d& point) const
|
||||
|
||||
|
||||
std::optional<SurfaceFeature> MeasuringImpl::get_feature(size_t face_idx, const Vec3d& point)
|
||||
{
|
||||
if (face_idx >= m_face_to_plane.size())
|
||||
return std::optional<SurfaceFeature>();
|
||||
|
||||
const PlaneData& plane = m_planes[m_face_to_plane[face_idx]];
|
||||
|
||||
if (! plane.features_extracted)
|
||||
extract_features(m_face_to_plane[face_idx]);
|
||||
|
||||
size_t closest_feature_idx = size_t(-1);
|
||||
double min_dist = std::numeric_limits<double>::max();
|
||||
@ -554,17 +560,24 @@ std::optional<SurfaceFeature> MeasuringImpl::get_feature(size_t face_idx, const
|
||||
|
||||
|
||||
|
||||
std::vector<std::vector<int>> MeasuringImpl::get_planes_triangle_indices() const
|
||||
int MeasuringImpl::get_num_of_planes() const
|
||||
{
|
||||
std::vector<std::vector<int>> out;
|
||||
for (const PlaneData& plane : m_planes)
|
||||
out.emplace_back(plane.facets);
|
||||
return out;
|
||||
return (m_planes.size());
|
||||
}
|
||||
|
||||
const std::vector<SurfaceFeature>& MeasuringImpl::get_plane_features(unsigned int plane_id) const
|
||||
|
||||
|
||||
const std::vector<int>& MeasuringImpl::get_plane_triangle_indices(int idx) const
|
||||
{
|
||||
assert(idx >= 0 && idx < int(m_planes.size()));
|
||||
return m_planes[idx].facets;
|
||||
}
|
||||
|
||||
const std::vector<SurfaceFeature>& MeasuringImpl::get_plane_features(unsigned int plane_id)
|
||||
{
|
||||
assert(plane_id < m_planes.size());
|
||||
if (! m_planes[plane_id].features_extracted)
|
||||
extract_features(plane_id);
|
||||
return m_planes[plane_id].surface_features;
|
||||
}
|
||||
|
||||
@ -590,11 +603,6 @@ Measuring::Measuring(const indexed_triangle_set& its)
|
||||
Measuring::~Measuring() {}
|
||||
|
||||
|
||||
std::vector<SurfaceFeature> Measuring::get_all_features() const
|
||||
{
|
||||
return priv->get_all_features();
|
||||
}
|
||||
|
||||
|
||||
std::optional<SurfaceFeature> Measuring::get_feature(size_t face_idx, const Vec3d& point) const
|
||||
{
|
||||
@ -602,10 +610,15 @@ std::optional<SurfaceFeature> Measuring::get_feature(size_t face_idx, const Vec3
|
||||
}
|
||||
|
||||
|
||||
|
||||
std::vector<std::vector<int>> Measuring::get_planes_triangle_indices() const
|
||||
int Measuring::get_num_of_planes() const
|
||||
{
|
||||
return priv->get_planes_triangle_indices();
|
||||
return priv->get_num_of_planes();
|
||||
}
|
||||
|
||||
|
||||
const std::vector<int>& Measuring::get_plane_triangle_indices(int idx) const
|
||||
{
|
||||
return priv->get_plane_triangle_indices(idx);
|
||||
}
|
||||
|
||||
const std::vector<SurfaceFeature>& Measuring::get_plane_features(unsigned int plane_id) const
|
||||
|
@ -93,20 +93,18 @@ public:
|
||||
// Construct the measurement object on a given its.
|
||||
explicit Measuring(const indexed_triangle_set& its);
|
||||
~Measuring();
|
||||
|
||||
// Return a reference to a list of all features identified on the its.
|
||||
// Use only for debugging. Expensive, do not call often.
|
||||
std::vector<SurfaceFeature> get_all_features() const;
|
||||
|
||||
|
||||
// Given a face_idx where the mouse cursor points, return a feature that
|
||||
// should be highlighted (if any).
|
||||
std::optional<SurfaceFeature> get_feature(size_t face_idx, const Vec3d& point) const;
|
||||
|
||||
// Returns a list of triangle indices for each identified plane. Each
|
||||
// Plane object contains an index into this vector. Expensive, do not
|
||||
// call too often.
|
||||
std::vector<std::vector<int>> get_planes_triangle_indices() const;
|
||||
|
||||
// Return total number of planes.
|
||||
int get_num_of_planes() const;
|
||||
|
||||
// Returns a list of triangle indices for given plane.
|
||||
const std::vector<int>& get_plane_triangle_indices(int idx) const;
|
||||
|
||||
// Returns the surface features of the plane with the given index
|
||||
const std::vector<SurfaceFeature>& get_plane_features(unsigned int plane_id) const;
|
||||
|
||||
|
@ -11,11 +11,6 @@
|
||||
|
||||
namespace Slic3r { namespace sla {
|
||||
|
||||
const RasterBase::TMirroring RasterBase::NoMirror = {false, false};
|
||||
const RasterBase::TMirroring RasterBase::MirrorX = {true, false};
|
||||
const RasterBase::TMirroring RasterBase::MirrorY = {false, true};
|
||||
const RasterBase::TMirroring RasterBase::MirrorXY = {true, true};
|
||||
|
||||
EncodedRaster PNGRasterEncoder::operator()(const void *ptr, size_t w, size_t h,
|
||||
size_t num_components)
|
||||
{
|
||||
|
@ -60,10 +60,10 @@ public:
|
||||
enum Orientation { roLandscape, roPortrait };
|
||||
|
||||
using TMirroring = std::array<bool, 2>;
|
||||
static const TMirroring NoMirror;
|
||||
static const TMirroring MirrorX;
|
||||
static const TMirroring MirrorY;
|
||||
static const TMirroring MirrorXY;
|
||||
static const constexpr TMirroring NoMirror = {false, false};
|
||||
static const constexpr TMirroring MirrorX = {true, false};
|
||||
static const constexpr TMirroring MirrorY = {false, true};
|
||||
static const constexpr TMirroring MirrorXY = {true, true};
|
||||
|
||||
struct Trafo {
|
||||
bool mirror_x = false, mirror_y = false, flipXY = false;
|
||||
|
@ -413,6 +413,8 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
||||
[&part_to_drill, &hollowed_mesh](const auto& node)
|
||||
{
|
||||
part_to_drill.indices.emplace_back(hollowed_mesh.its.indices[node.idx]);
|
||||
// continue traversal
|
||||
return true;
|
||||
});
|
||||
|
||||
auto cgal_meshpart = MeshBoolean::cgal::triangle_mesh_to_cgal(
|
||||
|
@ -738,6 +738,13 @@ void its_flip_triangles(indexed_triangle_set &its)
|
||||
std::swap(face(1), face(2));
|
||||
}
|
||||
|
||||
int its_num_degenerate_faces(const indexed_triangle_set &its)
|
||||
{
|
||||
return std::count_if(its.indices.begin(), its.indices.end(), [](auto &face) {
|
||||
return face(0) == face(1) || face(0) == face(2) || face(1) == face(2);
|
||||
});
|
||||
}
|
||||
|
||||
int its_remove_degenerate_faces(indexed_triangle_set &its, bool shrink_to_fit)
|
||||
{
|
||||
auto it = std::remove_if(its.indices.begin(), its.indices.end(), [](auto &face) {
|
||||
|
@ -204,6 +204,8 @@ void its_flip_triangles(indexed_triangle_set &its);
|
||||
// or more than two faces share the same edge position!
|
||||
int its_merge_vertices(indexed_triangle_set &its, bool shrink_to_fit = true);
|
||||
|
||||
// Calculate number of degenerate faces. There should be no degenerate faces in a nice mesh.
|
||||
int its_num_degenerate_faces(const indexed_triangle_set &its);
|
||||
// Remove degenerate faces, return number of faces removed.
|
||||
int its_remove_degenerate_faces(indexed_triangle_set &its, bool shrink_to_fit = true);
|
||||
|
||||
|
@ -242,7 +242,12 @@ static FacetSliceType slice_facet(
|
||||
std::swap(a, b);
|
||||
}
|
||||
IntersectionPoint &point = points[num_points];
|
||||
double t = (double(slice_z) - double(b->z())) / (double(a->z()) - double(b->z()));
|
||||
double t = (double(slice_z) - double(a->z())) / (double(b->z()) - double(a->z()));
|
||||
#if 0
|
||||
// If the intersection point falls into one of the end points, mark it with the end point identifier.
|
||||
// While this sounds like a good idea, it likely breaks the chaining by logical addresses of the intersection points
|
||||
// and the branch for 0 < t < 1 does not guarantee uniqness of the interection point anyways.
|
||||
// Thus this branch is only kept for reference and it is not used in production code.
|
||||
if (t <= 0.) {
|
||||
if (point_on_layer == size_t(-1) || points[point_on_layer].point_id != a_id) {
|
||||
point.x() = a->x();
|
||||
@ -258,11 +263,26 @@ static FacetSliceType slice_facet(
|
||||
point.point_id = b_id;
|
||||
}
|
||||
} else {
|
||||
point.x() = coord_t(floor(double(b->x()) + (double(a->x()) - double(b->x())) * t + 0.5));
|
||||
point.y() = coord_t(floor(double(b->y()) + (double(a->y()) - double(b->y())) * t + 0.5));
|
||||
point.x() = coord_t(floor(double(a->x()) + (double(b->x()) - double(a->x())) * t + 0.5));
|
||||
point.y() = coord_t(floor(double(a->y()) + (double(b->y()) - double(a->y())) * t + 0.5));
|
||||
point.edge_id = edge_id;
|
||||
++ num_points;
|
||||
}
|
||||
#else
|
||||
// Just clamp the intersection point to source triangle edge.
|
||||
if (t <= 0.) {
|
||||
point.x() = a->x();
|
||||
point.y() = a->y();
|
||||
} else if (t >= 1.) {
|
||||
point.x() = b->x();
|
||||
point.y() = b->y();
|
||||
} else {
|
||||
point.x() = coord_t(floor(double(a->x()) + (double(b->x()) - double(a->x())) * t + 0.5));
|
||||
point.y() = coord_t(floor(double(a->y()) + (double(b->y()) - double(a->y())) * t + 0.5));
|
||||
}
|
||||
point.edge_id = edge_id;
|
||||
++ num_points;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
@ -284,6 +304,11 @@ static FacetSliceType slice_facet(
|
||||
assert(line_out.edge_a_id != -1 || line_out.edge_b_id != -1);
|
||||
// General slicing position, use the segment for both slicing and object cutting.
|
||||
#if 0
|
||||
// See the discussion on calculating the intersection point on a triangle edge.
|
||||
// Even if the intersection point is clamped to one of the end points of the triangle edge,
|
||||
// the intersection point is still marked as "on edge", not "on vertex". Such implementation
|
||||
// may produce degenerate triangles, but is topologically correct.
|
||||
// Therefore this block for solving snapping of an intersection edge to triangle vertices is not used.
|
||||
if (line_out.a_id != -1 && line_out.b_id != -1) {
|
||||
// Solving a degenerate case, where both the intersections snapped to an edge.
|
||||
// Correctly classify the face as below or above based on the position of the 3rd point.
|
||||
@ -2009,6 +2034,7 @@ static void triangulate_slice(
|
||||
(l.first.y() == r.first.y() && l.second < r.second))); });
|
||||
|
||||
// 2) Discover duplicate points on the slice. Remap duplicate vertices to a vertex with a lowest index.
|
||||
// Remove denegerate triangles, if they happen to be created by merging duplicate vertices.
|
||||
{
|
||||
std::vector<int> map_duplicate_vertex(int(its.vertices.size()) - num_original_vertices, -1);
|
||||
int i = 0;
|
||||
@ -2031,10 +2057,20 @@ static void triangulate_slice(
|
||||
i = j;
|
||||
}
|
||||
map_vertex_to_index.erase(map_vertex_to_index.begin() + k, map_vertex_to_index.end());
|
||||
for (stl_triangle_vertex_indices &f : its.indices)
|
||||
for (i = 0; i < 3; ++ i)
|
||||
if (f(i) >= num_original_vertices)
|
||||
f(i) = map_duplicate_vertex[f(i) - num_original_vertices];
|
||||
for (i = 0; i < int(its.indices.size());) {
|
||||
stl_triangle_vertex_indices &f = its.indices[i];
|
||||
// Remap the newly added face vertices.
|
||||
for (k = 0; k < 3; ++ k)
|
||||
if (f(k) >= num_original_vertices)
|
||||
f(k) = map_duplicate_vertex[f(k) - num_original_vertices];
|
||||
if (f(0) == f(1) || f(0) == f(2) || f(1) == f(2)) {
|
||||
// Remove degenerate face.
|
||||
f = its.indices.back();
|
||||
its.indices.pop_back();
|
||||
} else
|
||||
// Keep the face.
|
||||
++ i;
|
||||
}
|
||||
}
|
||||
|
||||
if (triangulate) {
|
||||
@ -2108,6 +2144,10 @@ void cut_mesh(const indexed_triangle_set &mesh, float z, indexed_triangle_set *u
|
||||
if (upper == nullptr && lower == nullptr)
|
||||
return;
|
||||
|
||||
#ifndef NDEBUG
|
||||
const size_t had_degenerate_faces = its_num_degenerate_faces(mesh);
|
||||
#endif // NDEBUG
|
||||
|
||||
BOOST_LOG_TRIVIAL(trace) << "cut_mesh - slicing object";
|
||||
|
||||
if (upper) {
|
||||
@ -2251,8 +2291,27 @@ void cut_mesh(const indexed_triangle_set &mesh, float z, indexed_triangle_set *u
|
||||
new_face(lower, iv0, iv0v1_lower, iv2v0_lower);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
char buf[2048];
|
||||
static int irun = 0;
|
||||
++irun;
|
||||
temp.indices.emplace_back(int(temp.vertices.size()), int(temp.vertices.size() + 1), int(temp.vertices.size() + 2));
|
||||
temp.vertices.emplace_back(vertices[0]);
|
||||
temp.vertices.emplace_back(vertices[1]);
|
||||
temp.vertices.emplace_back(vertices[2]);
|
||||
sprintf(buf, "D:\\temp\\test\\temp-%d.obj", irun);
|
||||
its_write_obj(temp, buf);
|
||||
sprintf(buf, "D:\\temp\\test\\upper-%d.obj", irun);
|
||||
its_write_obj(*upper, buf);
|
||||
sprintf(buf, "D:\\temp\\test\\lower-%d.obj", irun);
|
||||
its_write_obj(*lower, buf);
|
||||
*/
|
||||
}
|
||||
|
||||
|
||||
assert(had_degenerate_faces || ! upper || its_num_degenerate_faces(*upper) == 0);
|
||||
assert(had_degenerate_faces || ! lower || its_num_degenerate_faces(*lower) == 0);
|
||||
|
||||
if (upper != nullptr) {
|
||||
triangulate_slice(*upper, upper_lines, upper_slice_vertices, int(mesh.vertices.size()), z, triangulate_caps, NORMALS_DOWN);
|
||||
#ifndef NDEBUG
|
||||
@ -2272,6 +2331,9 @@ void cut_mesh(const indexed_triangle_set &mesh, float z, indexed_triangle_set *u
|
||||
}
|
||||
#endif // NDEBUG
|
||||
}
|
||||
|
||||
assert(had_degenerate_faces || ! upper || its_num_degenerate_faces(*upper) == 0);
|
||||
assert(had_degenerate_faces || ! lower || its_num_degenerate_faces(*lower) == 0);
|
||||
}
|
||||
|
||||
} // namespace Slic3r
|
||||
|
@ -130,6 +130,6 @@ void cut_mesh(
|
||||
indexed_triangle_set *lower,
|
||||
bool triangulate_caps = true);
|
||||
|
||||
}
|
||||
} // namespace Slic3r
|
||||
|
||||
#endif // slic3r_TriangleMeshSlicer_hpp_
|
||||
|
@ -93,11 +93,8 @@ static std::string center_on_feature_type_as_string(Measure::SurfaceFeatureType
|
||||
return ret;
|
||||
}
|
||||
|
||||
static GLModel::Geometry init_plane_data(const indexed_triangle_set& its, const std::vector<std::vector<int>>& planes_triangles, int idx)
|
||||
static GLModel::Geometry init_plane_data(const indexed_triangle_set& its, const std::vector<int>& triangle_indices)
|
||||
{
|
||||
assert(0 <= idx && idx < (int)planes_triangles.size());
|
||||
const std::vector<int>& triangle_indices = planes_triangles[idx];
|
||||
|
||||
GLModel::Geometry init_data;
|
||||
init_data.format = { GUI::GLModel::Geometry::EPrimitiveType::Triangles, GLModel::Geometry::EVertexLayout::P3N3 };
|
||||
unsigned int i = 0;
|
||||
@ -653,11 +650,10 @@ void GLGizmoMeasure::on_render()
|
||||
if (m_last_plane_idx != idx) {
|
||||
m_last_plane_idx = idx;
|
||||
const indexed_triangle_set& its = m_measuring->get_mesh().its;
|
||||
const std::vector<std::vector<int>> planes_triangles = m_measuring->get_planes_triangle_indices();
|
||||
GLModel::Geometry init_data = init_plane_data(its, planes_triangles, idx);
|
||||
const std::vector<int>& plane_triangles = m_measuring->get_plane_triangle_indices(idx);
|
||||
GLModel::Geometry init_data = init_plane_data(its, plane_triangles);
|
||||
m_plane.reset();
|
||||
m_plane.mesh_raycaster = std::make_unique<MeshRaycaster>(std::make_shared<const TriangleMesh>(init_data.get_as_indexed_triangle_set()));
|
||||
m_plane.model.init_from(std::move(init_data));
|
||||
}
|
||||
|
||||
m_raycasters.insert({ PLANE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, PLANE_ID, *m_plane.mesh_raycaster) });
|
||||
@ -1041,10 +1037,9 @@ void GLGizmoMeasure::update_if_needed()
|
||||
{
|
||||
auto update_plane_models_cache = [this](const indexed_triangle_set& its) {
|
||||
m_plane_models_cache.clear();
|
||||
const std::vector<std::vector<int>> planes_triangles = m_measuring->get_planes_triangle_indices();
|
||||
for (int idx = 0; idx < (int)planes_triangles.size(); ++idx) {
|
||||
for (int idx = 0; idx < m_measuring->get_num_of_planes(); ++idx) {
|
||||
m_plane_models_cache.emplace_back(GLModel());
|
||||
GLModel::Geometry init_data = init_plane_data(its, planes_triangles, idx);
|
||||
GLModel::Geometry init_data = init_plane_data(its, m_measuring->get_plane_triangle_indices(idx));
|
||||
m_plane_models_cache.back().init_from(std::move(init_data));
|
||||
}
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user