Merge branch 'tm_drilling_improve'
This commit is contained in:
commit
3e5e020651
8 changed files with 213 additions and 51 deletions
|
@ -11,6 +11,8 @@
|
|||
#include <type_traits>
|
||||
#include <vector>
|
||||
|
||||
#include <Eigen/Geometry>
|
||||
|
||||
#include "Utils.hpp" // for next_highest_power_of_2()
|
||||
|
||||
extern "C"
|
||||
|
@ -752,6 +754,83 @@ void get_candidate_idxs(const TreeType& tree, const VectorType& v, std::vector<s
|
|||
return;
|
||||
}
|
||||
|
||||
// Predicate: need to be specialized for intersections of different geomteries
|
||||
template<class G> struct Intersecting {};
|
||||
|
||||
// Intersection predicate specialization for box-box intersections
|
||||
template<class CoordType, int NumD>
|
||||
struct Intersecting<Eigen::AlignedBox<CoordType, NumD>> {
|
||||
Eigen::AlignedBox<CoordType, NumD> box;
|
||||
|
||||
Intersecting(const Eigen::AlignedBox<CoordType, NumD> &bb): box{bb} {}
|
||||
|
||||
bool operator() (const typename Tree<NumD, CoordType>::Node &node) const
|
||||
{
|
||||
return box.intersects(node.bbox);
|
||||
}
|
||||
};
|
||||
|
||||
template<class G> auto intersecting(const G &g) { return Intersecting<G>{g}; }
|
||||
|
||||
template<class G> struct Containing {};
|
||||
|
||||
// Intersection predicate specialization for box-box intersections
|
||||
template<class CoordType, int NumD>
|
||||
struct Containing<Eigen::AlignedBox<CoordType, NumD>> {
|
||||
Eigen::AlignedBox<CoordType, NumD> box;
|
||||
|
||||
Containing(const Eigen::AlignedBox<CoordType, NumD> &bb): box{bb} {}
|
||||
|
||||
bool operator() (const typename Tree<NumD, CoordType>::Node &node) const
|
||||
{
|
||||
return box.contains(node.bbox);
|
||||
}
|
||||
};
|
||||
|
||||
template<class G> auto containing(const G &g) { return Containing<G>{g}; }
|
||||
|
||||
namespace detail {
|
||||
|
||||
template<int Dims, typename T, typename Pred, typename Fn>
|
||||
void 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 (tree.node(idx).is_leaf()) {
|
||||
callback(tree.node(idx).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));
|
||||
};
|
||||
|
||||
// Left / right child node index.
|
||||
trv(Tree<Dims, T>::left_child_idx(idx));
|
||||
trv(Tree<Dims, T>::right_child_idx(idx));
|
||||
}
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
|
||||
// Tree traversal with a predicate. Example usage:
|
||||
// traverse(tree, intersecting(QueryBox), [](size_t face_idx) {
|
||||
// /* ... */
|
||||
// });
|
||||
template<int Dims, typename T, typename Predicate, typename Fn>
|
||||
void traverse(const Tree<Dims, T> &tree, Predicate &&pred, Fn &&callback)
|
||||
{
|
||||
if (tree.empty()) return;
|
||||
|
||||
detail::traverse_recurse(tree, size_t(0), std::forward<Predicate>(pred),
|
||||
std::forward<Fn>(callback));
|
||||
}
|
||||
|
||||
} // namespace AABBTreeIndirect
|
||||
} // namespace Slic3r
|
||||
|
|
|
@ -110,33 +110,19 @@ struct CGALMesh { _EpicMesh m; };
|
|||
// Converions from and to CGAL mesh
|
||||
// /////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
template<class _Mesh> void triangle_mesh_to_cgal(const TriangleMesh &M, _Mesh &out)
|
||||
template<class _Mesh>
|
||||
void triangle_mesh_to_cgal(const std::vector<stl_vertex> & V,
|
||||
const std::vector<stl_triangle_vertex_indices> &F,
|
||||
_Mesh &out)
|
||||
{
|
||||
using Index3 = std::array<size_t, 3>;
|
||||
|
||||
if (M.empty()) return;
|
||||
|
||||
std::vector<typename _Mesh::Point> points;
|
||||
std::vector<Index3> indices;
|
||||
points.reserve(M.its.vertices.size());
|
||||
indices.reserve(M.its.indices.size());
|
||||
for (auto &v : M.its.vertices) points.emplace_back(v.x(), v.y(), v.z());
|
||||
for (auto &_f : M.its.indices) {
|
||||
auto f = _f.cast<size_t>();
|
||||
indices.emplace_back(Index3{f(0), f(1), f(2)});
|
||||
}
|
||||
if (F.empty()) return;
|
||||
|
||||
CGALProc::orient_polygon_soup(points, indices);
|
||||
CGALProc::polygon_soup_to_polygon_mesh(points, indices, out);
|
||||
|
||||
// Number the faces because 'orient_to_bound_a_volume' needs a face <--> index map
|
||||
unsigned index = 0;
|
||||
for (auto face : out.faces()) face = CGAL::SM_Face_index(index++);
|
||||
|
||||
if(CGAL::is_closed(out))
|
||||
CGALProc::orient_to_bound_a_volume(out);
|
||||
else
|
||||
throw Slic3r::RuntimeError("Mesh not watertight");
|
||||
for (auto &v : V)
|
||||
out.add_vertex(typename _Mesh::Point{v.x(), v.y(), v.z()});
|
||||
|
||||
using VI = typename _Mesh::Vertex_index;
|
||||
for (auto &f : F)
|
||||
out.add_face(VI(f(0)), VI(f(1)), VI(f(2)));
|
||||
}
|
||||
|
||||
inline Vec3d to_vec3d(const _EpicMesh::Point &v)
|
||||
|
@ -172,14 +158,16 @@ template<class _Mesh> TriangleMesh cgal_to_triangle_mesh(const _Mesh &cgalmesh)
|
|||
}
|
||||
|
||||
TriangleMesh out{points, facets};
|
||||
out.require_shared_vertices();
|
||||
out.repair();
|
||||
return out;
|
||||
}
|
||||
|
||||
std::unique_ptr<CGALMesh, CGALMeshDeleter> triangle_mesh_to_cgal(const TriangleMesh &M)
|
||||
std::unique_ptr<CGALMesh, CGALMeshDeleter>
|
||||
triangle_mesh_to_cgal(const std::vector<stl_vertex> &V,
|
||||
const std::vector<stl_triangle_vertex_indices> &F)
|
||||
{
|
||||
std::unique_ptr<CGALMesh, CGALMeshDeleter> out(new CGALMesh{});
|
||||
triangle_mesh_to_cgal(M, out->m);
|
||||
triangle_mesh_to_cgal(V, F, out->m);
|
||||
return out;
|
||||
}
|
||||
|
||||
|
@ -238,8 +226,8 @@ template<class Op> void _mesh_boolean_do(Op &&op, TriangleMesh &A, const Triangl
|
|||
{
|
||||
CGALMesh meshA;
|
||||
CGALMesh meshB;
|
||||
triangle_mesh_to_cgal(A, meshA.m);
|
||||
triangle_mesh_to_cgal(B, meshB.m);
|
||||
triangle_mesh_to_cgal(A.its.vertices, A.its.indices, meshA.m);
|
||||
triangle_mesh_to_cgal(B.its.vertices, B.its.indices, meshB.m);
|
||||
|
||||
_cgal_do(op, meshA, meshB);
|
||||
|
||||
|
@ -264,7 +252,7 @@ void intersect(TriangleMesh &A, const TriangleMesh &B)
|
|||
bool does_self_intersect(const TriangleMesh &mesh)
|
||||
{
|
||||
CGALMesh cgalm;
|
||||
triangle_mesh_to_cgal(mesh, cgalm.m);
|
||||
triangle_mesh_to_cgal(mesh.its.vertices, mesh.its.indices, cgalm.m);
|
||||
return CGALProc::does_self_intersect(cgalm.m);
|
||||
}
|
||||
|
||||
|
|
|
@ -27,7 +27,19 @@ namespace cgal {
|
|||
struct CGALMesh;
|
||||
struct CGALMeshDeleter { void operator()(CGALMesh *ptr); };
|
||||
|
||||
std::unique_ptr<CGALMesh, CGALMeshDeleter> triangle_mesh_to_cgal(const TriangleMesh &M);
|
||||
std::unique_ptr<CGALMesh, CGALMeshDeleter>
|
||||
triangle_mesh_to_cgal(const std::vector<stl_vertex> &V,
|
||||
const std::vector<stl_triangle_vertex_indices> &F);
|
||||
|
||||
inline std::unique_ptr<CGALMesh, CGALMeshDeleter> triangle_mesh_to_cgal(const indexed_triangle_set &M)
|
||||
{
|
||||
return triangle_mesh_to_cgal(M.vertices, M.indices);
|
||||
}
|
||||
inline std::unique_ptr<CGALMesh, CGALMeshDeleter> triangle_mesh_to_cgal(const TriangleMesh &M)
|
||||
{
|
||||
return triangle_mesh_to_cgal(M.its);
|
||||
}
|
||||
|
||||
TriangleMesh cgal_to_triangle_mesh(const CGALMesh &cgalmesh);
|
||||
|
||||
// Do boolean mesh difference with CGAL bypassing igl.
|
||||
|
|
|
@ -36,17 +36,18 @@ struct DrainHole
|
|||
Vec3f normal;
|
||||
float radius;
|
||||
float height;
|
||||
bool failed = false;
|
||||
|
||||
DrainHole()
|
||||
: pos(Vec3f::Zero()), normal(Vec3f::UnitZ()), radius(5.f), height(10.f)
|
||||
{}
|
||||
|
||||
DrainHole(Vec3f p, Vec3f n, float r, float h)
|
||||
: pos(p), normal(n), radius(r), height(h)
|
||||
DrainHole(Vec3f p, Vec3f n, float r, float h, bool fl = false)
|
||||
: pos(p), normal(n), radius(r), height(h), failed(fl)
|
||||
{}
|
||||
|
||||
DrainHole(const DrainHole& rhs) :
|
||||
DrainHole(rhs.pos, rhs.normal, rhs.radius, rhs.height) {}
|
||||
DrainHole(rhs.pos, rhs.normal, rhs.radius, rhs.height, rhs.failed) {}
|
||||
|
||||
bool operator==(const DrainHole &sp) const;
|
||||
|
||||
|
@ -61,7 +62,7 @@ struct DrainHole
|
|||
|
||||
template<class Archive> inline void serialize(Archive &ar)
|
||||
{
|
||||
ar(pos, normal, radius, height);
|
||||
ar(pos, normal, radius, height, failed);
|
||||
}
|
||||
|
||||
static constexpr size_t steps = 32;
|
||||
|
|
|
@ -12,6 +12,7 @@
|
|||
#include <libslic3r/SLA/SupportPointGenerator.hpp>
|
||||
|
||||
#include <libslic3r/ElephantFootCompensation.hpp>
|
||||
#include <libslic3r/AABBTreeIndirect.hpp>
|
||||
|
||||
#include <libslic3r/ClipperUtils.hpp>
|
||||
|
||||
|
@ -244,6 +245,8 @@ static std::vector<bool> create_exclude_mask(
|
|||
Vec3f face_normal = C.normalized();
|
||||
|
||||
for (const sla::DrainHole &dh : holes) {
|
||||
if (dh.failed) continue;
|
||||
|
||||
Vec3d dhpos = dh.pos.cast<double>();
|
||||
Vec3d dhend = dhpos + dh.normal.cast<double>() * dh.height;
|
||||
|
||||
|
@ -270,6 +273,36 @@ static std::vector<bool> create_exclude_mask(
|
|||
return exclude_mask;
|
||||
}
|
||||
|
||||
static indexed_triangle_set
|
||||
remove_unconnected_vertices(const indexed_triangle_set &its)
|
||||
{
|
||||
if (its.indices.empty()) {};
|
||||
|
||||
indexed_triangle_set M;
|
||||
|
||||
std::vector<int> vtransl(its.vertices.size(), -1);
|
||||
int vcnt = 0;
|
||||
for (auto &f : its.indices) {
|
||||
|
||||
for (int i = 0; i < 3; ++i)
|
||||
if (vtransl[size_t(f(i))] < 0) {
|
||||
|
||||
M.vertices.emplace_back(its.vertices[size_t(f(i))]);
|
||||
vtransl[size_t(f(i))] = vcnt++;
|
||||
}
|
||||
|
||||
std::array<int, 3> new_f = {
|
||||
vtransl[size_t(f(0))],
|
||||
vtransl[size_t(f(1))],
|
||||
vtransl[size_t(f(2))]
|
||||
};
|
||||
|
||||
M.indices.emplace_back(new_f[0], new_f[1], new_f[2]);
|
||||
}
|
||||
|
||||
return M;
|
||||
}
|
||||
|
||||
// Drill holes into the hollowed/original mesh.
|
||||
void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
||||
{
|
||||
|
@ -313,16 +346,52 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
|||
BOOST_LOG_TRIVIAL(info) << "Drilling drainage holes.";
|
||||
sla::DrainHoles drainholes = po.transformed_drainhole_points();
|
||||
|
||||
auto tree = AABBTreeIndirect::build_aabb_tree_over_indexed_triangle_set(
|
||||
hollowed_mesh.its.vertices,
|
||||
hollowed_mesh.its.indices
|
||||
);
|
||||
|
||||
std::uniform_real_distribution<float> dist(0., float(EPSILON));
|
||||
auto holes_mesh_cgal = MeshBoolean::cgal::triangle_mesh_to_cgal({});
|
||||
for (sla::DrainHole holept : drainholes) {
|
||||
auto holes_mesh_cgal = MeshBoolean::cgal::triangle_mesh_to_cgal({}, {});
|
||||
indexed_triangle_set part_to_drill = hollowed_mesh.its;
|
||||
|
||||
bool hole_fail = false;
|
||||
for (size_t i = 0; i < drainholes.size(); ++i) {
|
||||
sla::DrainHole holept = drainholes[i];
|
||||
|
||||
holept.normal += Vec3f{dist(m_rng), dist(m_rng), dist(m_rng)};
|
||||
holept.normal.normalize();
|
||||
holept.pos += Vec3f{dist(m_rng), dist(m_rng), dist(m_rng)};
|
||||
TriangleMesh m = sla::to_triangle_mesh(holept.to_mesh());
|
||||
m.require_shared_vertices();
|
||||
auto cgal_m = MeshBoolean::cgal::triangle_mesh_to_cgal(m);
|
||||
MeshBoolean::cgal::plus(*holes_mesh_cgal, *cgal_m);
|
||||
|
||||
part_to_drill.indices.clear();
|
||||
auto bb = m.bounding_box();
|
||||
Eigen::AlignedBox<float, 3> ebb{bb.min.cast<float>(),
|
||||
bb.max.cast<float>()};
|
||||
|
||||
AABBTreeIndirect::traverse(
|
||||
tree,
|
||||
AABBTreeIndirect::intersecting(ebb),
|
||||
[&part_to_drill, &hollowed_mesh](size_t faceid)
|
||||
{
|
||||
part_to_drill.indices.emplace_back(hollowed_mesh.its.indices[faceid]);
|
||||
});
|
||||
|
||||
auto cgal_meshpart = MeshBoolean::cgal::triangle_mesh_to_cgal(
|
||||
remove_unconnected_vertices(part_to_drill));
|
||||
|
||||
if (MeshBoolean::cgal::does_self_intersect(*cgal_meshpart)) {
|
||||
BOOST_LOG_TRIVIAL(error) << "Failed to drill hole";
|
||||
|
||||
hole_fail = drainholes[i].failed =
|
||||
po.model_object()->sla_drain_holes[i].failed = true;
|
||||
|
||||
continue;
|
||||
}
|
||||
|
||||
auto cgal_hole = MeshBoolean::cgal::triangle_mesh_to_cgal(m);
|
||||
MeshBoolean::cgal::plus(*holes_mesh_cgal, *cgal_hole);
|
||||
}
|
||||
|
||||
if (MeshBoolean::cgal::does_self_intersect(*holes_mesh_cgal))
|
||||
|
@ -332,6 +401,7 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
|||
|
||||
try {
|
||||
MeshBoolean::cgal::minus(*hollowed_mesh_cgal, *holes_mesh_cgal);
|
||||
|
||||
hollowed_mesh = MeshBoolean::cgal::cgal_to_triangle_mesh(*hollowed_mesh_cgal);
|
||||
mesh_view = hollowed_mesh;
|
||||
|
||||
|
@ -348,6 +418,10 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
|
|||
"Drilling holes into the mesh failed. "
|
||||
"This is usually caused by broken model. Try to fix it first."));
|
||||
}
|
||||
|
||||
if (hole_fail)
|
||||
po.active_step_add_warning(PrintStateBase::WarningLevel::NON_CRITICAL,
|
||||
L("Failed to drill some holes into the model"));
|
||||
}
|
||||
|
||||
// The slicing will be performed on an imaginary 1D grid which starts from
|
||||
|
|
|
@ -122,9 +122,10 @@ void GLGizmoHollow::render_points(const Selection& selection, bool picking) cons
|
|||
glsafe(::glTranslated(0.0, 0.0, m_c->selection_info()->get_sla_shift()));
|
||||
glsafe(::glMultMatrixd(instance_matrix.data()));
|
||||
|
||||
float render_color[4];
|
||||
std::array<float, 4> render_color;
|
||||
const sla::DrainHoles& drain_holes = m_c->selection_info()->model_object()->sla_drain_holes;
|
||||
size_t cache_size = drain_holes.size();
|
||||
|
||||
for (size_t i = 0; i < cache_size; ++i)
|
||||
{
|
||||
const sla::DrainHole& drain_hole = drain_holes[i];
|
||||
|
@ -136,26 +137,27 @@ void GLGizmoHollow::render_points(const Selection& selection, bool picking) cons
|
|||
// First decide about the color of the point.
|
||||
if (picking) {
|
||||
std::array<float, 4> color = picking_color_component(i);
|
||||
render_color[0] = color[0];
|
||||
render_color[1] = color[1];
|
||||
render_color[2] = color[2];
|
||||
render_color[3] = color[3];
|
||||
|
||||
render_color = color;
|
||||
}
|
||||
else {
|
||||
render_color[3] = 1.f;
|
||||
if (size_t(m_hover_id) == i) {
|
||||
render_color[0] = 0.f;
|
||||
render_color[1] = 1.0f;
|
||||
render_color[2] = 1.0f;
|
||||
render_color = {0.f, 1.f, 1.f, 1.f};
|
||||
} else if (m_c->hollowed_mesh() &&
|
||||
i < m_c->hollowed_mesh()->get_drainholes().size() &&
|
||||
m_c->hollowed_mesh()->get_drainholes()[i].failed) {
|
||||
render_color = {1.f, 0.f, 0.f, .5f};
|
||||
}
|
||||
else { // neigher hover nor picking
|
||||
|
||||
render_color[0] = point_selected ? 1.0f : 0.7f;
|
||||
render_color[1] = point_selected ? 0.3f : 0.7f;
|
||||
render_color[2] = point_selected ? 0.3f : 0.7f;
|
||||
render_color[3] = 0.5f;
|
||||
}
|
||||
}
|
||||
glsafe(::glColor4fv(render_color));
|
||||
|
||||
glsafe(::glColor4fv(render_color.data()));
|
||||
float render_color_emissive[4] = { 0.5f * render_color[0], 0.5f * render_color[1], 0.5f * render_color[2], 1.f};
|
||||
glsafe(::glMaterialfv(GL_FRONT, GL_EMISSION, render_color_emissive));
|
||||
|
||||
|
|
|
@ -205,6 +205,7 @@ void HollowedMesh::on_update()
|
|||
m_hollowed_mesh_transformed.reset(new TriangleMesh(backend_mesh));
|
||||
Transform3d trafo_inv = canvas->sla_print()->sla_trafo(*mo).inverse();
|
||||
m_hollowed_mesh_transformed->transform(trafo_inv);
|
||||
m_drainholes = print_object->model_object()->sla_drain_holes;
|
||||
m_old_hollowing_timestamp = timestamp;
|
||||
|
||||
const TriangleMesh &interior = print_object->hollowed_interior_mesh();
|
||||
|
@ -215,8 +216,9 @@ void HollowedMesh::on_update()
|
|||
m_hollowed_interior_transformed->transform(trafo_inv);
|
||||
}
|
||||
}
|
||||
else
|
||||
else {
|
||||
m_hollowed_mesh_transformed.reset(nullptr);
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include <map>
|
||||
|
||||
#include "slic3r/GUI/MeshUtils.hpp"
|
||||
#include "libslic3r/SLA/Hollowing.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
|
||||
|
@ -198,6 +199,8 @@ public:
|
|||
CommonGizmosDataID get_dependencies() const override { return CommonGizmosDataID::SelectionInfo; }
|
||||
#endif // NDEBUG
|
||||
|
||||
const sla::DrainHoles &get_drainholes() const { return m_drainholes; }
|
||||
|
||||
const TriangleMesh* get_hollowed_mesh() const;
|
||||
const TriangleMesh* get_hollowed_interior() const;
|
||||
|
||||
|
@ -211,6 +214,7 @@ private:
|
|||
size_t m_old_hollowing_timestamp = 0;
|
||||
int m_print_object_idx = -1;
|
||||
int m_print_objects_count = 0;
|
||||
sla::DrainHoles m_drainholes;
|
||||
};
|
||||
|
||||
|
||||
|
|
Loading…
Reference in a new issue