mirror of
				https://github.com/SoftFever/OrcaSlicer.git
				synced 2025-11-02 20:51:23 -07:00 
			
		
		
		
	SLA backend refactored, except Hollowing
This commit is contained in:
		
							parent
							
								
									1c35dfe591
								
							
						
					
					
						commit
						1009f78862
					
				
					 22 changed files with 687 additions and 404 deletions
				
			
		| 
						 | 
				
			
			@ -149,9 +149,11 @@ struct indexed_triangle_set
 | 
			
		|||
	}
 | 
			
		||||
 | 
			
		||||
	std::vector<stl_triangle_vertex_indices> 	indices;
 | 
			
		||||
	std::vector<stl_vertex>       				    vertices;
 | 
			
		||||
    std::vector<stl_vertex>       				    vertices;
 | 
			
		||||
	//FIXME add normals once we get rid of the stl_file from TriangleMesh completely.
 | 
			
		||||
	//std::vector<stl_normal> 					      normals
 | 
			
		||||
 | 
			
		||||
    bool empty() const { return indices.empty() || vertices.empty(); }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
extern bool stl_open(stl_file *stl, const char *file);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -154,14 +154,14 @@ InteriorPtr generate_interior(const TriangleMesh &   mesh,
 | 
			
		|||
    return interior;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D DrainHole::to_mesh() const
 | 
			
		||||
indexed_triangle_set DrainHole::to_mesh() const
 | 
			
		||||
{
 | 
			
		||||
    auto r = double(radius);
 | 
			
		||||
    auto h = double(height);
 | 
			
		||||
    sla::Contour3D hole = sla::cylinder(r, h, steps);
 | 
			
		||||
    Eigen::Quaterniond q;
 | 
			
		||||
    q.setFromTwoVectors(Vec3d{0., 0., 1.}, normal.cast<double>());
 | 
			
		||||
    for(auto& p : hole.points) p = q * p + pos.cast<double>();
 | 
			
		||||
    indexed_triangle_set hole = sla::cylinder(r, h, steps);
 | 
			
		||||
    Eigen::Quaternionf q;
 | 
			
		||||
    q.setFromTwoVectors(Vec3f{0.f, 0.f, 1.f}, normal);
 | 
			
		||||
    for(auto& p : hole.vertices) p = q * p + pos;
 | 
			
		||||
    
 | 
			
		||||
    return hole;
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			@ -292,7 +292,7 @@ void cut_drainholes(std::vector<ExPolygons> & obj_slices,
 | 
			
		|||
{
 | 
			
		||||
    TriangleMesh mesh;
 | 
			
		||||
    for (const sla::DrainHole &holept : holes)
 | 
			
		||||
        mesh.merge(sla::to_triangle_mesh(holept.to_mesh()));
 | 
			
		||||
        mesh.merge(TriangleMesh{holept.to_mesh()});
 | 
			
		||||
    
 | 
			
		||||
    if (mesh.empty()) return;
 | 
			
		||||
    
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -58,7 +58,7 @@ struct DrainHole
 | 
			
		|||
    bool get_intersections(const Vec3f& s, const Vec3f& dir,
 | 
			
		||||
                           std::array<std::pair<float, Vec3d>, 2>& out) const;
 | 
			
		||||
    
 | 
			
		||||
    Contour3D to_mesh() const;
 | 
			
		||||
    indexed_triangle_set to_mesh() const;
 | 
			
		||||
    
 | 
			
		||||
    template<class Archive> inline void serialize(Archive &ar)
 | 
			
		||||
    {
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -10,59 +10,75 @@
 | 
			
		|||
#include <libslic3r/SLA/Hollowing.hpp>
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
namespace Slic3r { namespace sla {
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
 | 
			
		||||
namespace sla {
 | 
			
		||||
 | 
			
		||||
class IndexedMesh::AABBImpl {
 | 
			
		||||
private:
 | 
			
		||||
    AABBTreeIndirect::Tree3f m_tree;
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
    void init(const TriangleMesh& tm)
 | 
			
		||||
    void init(const indexed_triangle_set &its)
 | 
			
		||||
    {
 | 
			
		||||
        m_tree = AABBTreeIndirect::build_aabb_tree_over_indexed_triangle_set(
 | 
			
		||||
            tm.its.vertices, tm.its.indices);
 | 
			
		||||
            its.vertices, its.indices);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    void intersect_ray(const TriangleMesh& tm,
 | 
			
		||||
                       const Vec3d& s, const Vec3d& dir, igl::Hit& hit)
 | 
			
		||||
    void intersect_ray(const indexed_triangle_set &its,
 | 
			
		||||
                       const Vec3d &               s,
 | 
			
		||||
                       const Vec3d &               dir,
 | 
			
		||||
                       igl::Hit &                  hit)
 | 
			
		||||
    {
 | 
			
		||||
        AABBTreeIndirect::intersect_ray_first_hit(tm.its.vertices,
 | 
			
		||||
                                                  tm.its.indices,
 | 
			
		||||
                                                  m_tree,
 | 
			
		||||
                                                  s, dir, hit);
 | 
			
		||||
        AABBTreeIndirect::intersect_ray_first_hit(its.vertices, its.indices,
 | 
			
		||||
                                                  m_tree, s, dir, hit);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    void intersect_ray(const TriangleMesh& tm,
 | 
			
		||||
                       const Vec3d& s, const Vec3d& dir, std::vector<igl::Hit>& hits)
 | 
			
		||||
    void intersect_ray(const indexed_triangle_set &its,
 | 
			
		||||
                       const Vec3d &               s,
 | 
			
		||||
                       const Vec3d &               dir,
 | 
			
		||||
                       std::vector<igl::Hit> &     hits)
 | 
			
		||||
    {
 | 
			
		||||
        AABBTreeIndirect::intersect_ray_all_hits(tm.its.vertices,
 | 
			
		||||
                                                 tm.its.indices,
 | 
			
		||||
                                                 m_tree,
 | 
			
		||||
                                                 s, dir, hits);
 | 
			
		||||
        AABBTreeIndirect::intersect_ray_all_hits(its.vertices, its.indices,
 | 
			
		||||
                                                 m_tree, s, dir, hits);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    double squared_distance(const TriangleMesh& tm,
 | 
			
		||||
                            const Vec3d& point, int& i, Eigen::Matrix<double, 1, 3>& closest) {
 | 
			
		||||
    double squared_distance(const indexed_triangle_set & its,
 | 
			
		||||
                            const Vec3d &                point,
 | 
			
		||||
                            int &                        i,
 | 
			
		||||
                            Eigen::Matrix<double, 1, 3> &closest)
 | 
			
		||||
    {
 | 
			
		||||
        size_t idx_unsigned = 0;
 | 
			
		||||
        Vec3d closest_vec3d(closest);
 | 
			
		||||
        double dist = AABBTreeIndirect::squared_distance_to_indexed_triangle_set(
 | 
			
		||||
            tm.its.vertices,
 | 
			
		||||
            tm.its.indices,
 | 
			
		||||
            m_tree, point, idx_unsigned, closest_vec3d);
 | 
			
		||||
        i = int(idx_unsigned);
 | 
			
		||||
        Vec3d  closest_vec3d(closest);
 | 
			
		||||
        double dist =
 | 
			
		||||
            AABBTreeIndirect::squared_distance_to_indexed_triangle_set(
 | 
			
		||||
                its.vertices, its.indices, m_tree, point, idx_unsigned,
 | 
			
		||||
                closest_vec3d);
 | 
			
		||||
        i       = int(idx_unsigned);
 | 
			
		||||
        closest = closest_vec3d;
 | 
			
		||||
        return dist;
 | 
			
		||||
    }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
IndexedMesh::IndexedMesh(const TriangleMesh& tmesh)
 | 
			
		||||
    : m_aabb(new AABBImpl()), m_tm(&tmesh)
 | 
			
		||||
template<class M> void IndexedMesh::init(const M &mesh)
 | 
			
		||||
{
 | 
			
		||||
    auto&& bb = tmesh.bounding_box();
 | 
			
		||||
    BoundingBoxf3 bb = bounding_box(mesh);
 | 
			
		||||
    m_ground_level += bb.min(Z);
 | 
			
		||||
 | 
			
		||||
    // Build the AABB accelaration tree
 | 
			
		||||
    m_aabb->init(tmesh);
 | 
			
		||||
    m_aabb->init(*m_tm);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
IndexedMesh::IndexedMesh(const indexed_triangle_set& tmesh)
 | 
			
		||||
    : m_aabb(new AABBImpl()), m_tm(&tmesh)
 | 
			
		||||
{
 | 
			
		||||
    init(tmesh);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
IndexedMesh::IndexedMesh(const TriangleMesh &mesh)
 | 
			
		||||
    : m_aabb(new AABBImpl()), m_tm(&mesh.its)
 | 
			
		||||
{
 | 
			
		||||
    init(mesh);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
IndexedMesh::~IndexedMesh() {}
 | 
			
		||||
| 
						 | 
				
			
			@ -87,34 +103,34 @@ IndexedMesh::IndexedMesh(IndexedMesh &&other) = default;
 | 
			
		|||
 | 
			
		||||
const std::vector<Vec3f>& IndexedMesh::vertices() const
 | 
			
		||||
{
 | 
			
		||||
    return m_tm->its.vertices;
 | 
			
		||||
    return m_tm->vertices;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
const std::vector<Vec3i>& IndexedMesh::indices()  const
 | 
			
		||||
{
 | 
			
		||||
    return m_tm->its.indices;
 | 
			
		||||
    return m_tm->indices;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
const Vec3f& IndexedMesh::vertices(size_t idx) const
 | 
			
		||||
{
 | 
			
		||||
    return m_tm->its.vertices[idx];
 | 
			
		||||
    return m_tm->vertices[idx];
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
const Vec3i& IndexedMesh::indices(size_t idx) const
 | 
			
		||||
{
 | 
			
		||||
    return m_tm->its.indices[idx];
 | 
			
		||||
    return m_tm->indices[idx];
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
Vec3d IndexedMesh::normal_by_face_id(int face_id) const {
 | 
			
		||||
    return m_tm->stl.facet_start[face_id].normal.cast<double>();
 | 
			
		||||
 | 
			
		||||
    return its_unnormalized_normal(*m_tm, face_id).cast<double>().normalized();
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -15,6 +15,8 @@
 | 
			
		|||
  #include "libslic3r/SLA/Hollowing.hpp"
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
struct indexed_triangle_set;
 | 
			
		||||
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
 | 
			
		||||
class TriangleMesh;
 | 
			
		||||
| 
						 | 
				
			
			@ -29,7 +31,7 @@ using PointSet = Eigen::MatrixXd;
 | 
			
		|||
class IndexedMesh {
 | 
			
		||||
    class AABBImpl;
 | 
			
		||||
    
 | 
			
		||||
    const TriangleMesh* m_tm;
 | 
			
		||||
    const indexed_triangle_set* m_tm;
 | 
			
		||||
    double m_ground_level = 0, m_gnd_offset = 0;
 | 
			
		||||
    
 | 
			
		||||
    std::unique_ptr<AABBImpl> m_aabb;
 | 
			
		||||
| 
						 | 
				
			
			@ -40,9 +42,12 @@ class IndexedMesh {
 | 
			
		|||
    std::vector<DrainHole> m_holes;
 | 
			
		||||
#endif
 | 
			
		||||
 | 
			
		||||
    template<class M> void init(const M &mesh);
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
    
 | 
			
		||||
    explicit IndexedMesh(const TriangleMesh&);
 | 
			
		||||
    explicit IndexedMesh(const indexed_triangle_set&);
 | 
			
		||||
    explicit IndexedMesh(const TriangleMesh &mesh);
 | 
			
		||||
    
 | 
			
		||||
    IndexedMesh(const IndexedMesh& other);
 | 
			
		||||
    IndexedMesh& operator=(const IndexedMesh&);
 | 
			
		||||
| 
						 | 
				
			
			@ -130,7 +135,7 @@ public:
 | 
			
		|||
 | 
			
		||||
    Vec3d normal_by_face_id(int face_id) const;
 | 
			
		||||
 | 
			
		||||
    const TriangleMesh * get_triangle_mesh() const { return m_tm; }
 | 
			
		||||
    const indexed_triangle_set * get_triangle_mesh() const { return m_tm; }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
// Calculate the normals for the selected points (from 'points' set) on the
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -1,7 +1,7 @@
 | 
			
		|||
#include <libslic3r/SLA/Pad.hpp>
 | 
			
		||||
#include <libslic3r/SLA/SpatIndex.hpp>
 | 
			
		||||
#include <libslic3r/SLA/BoostAdapter.hpp>
 | 
			
		||||
#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
//#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
#include <libslic3r/TriangleMeshSlicer.hpp>
 | 
			
		||||
 | 
			
		||||
#include "ConcaveHull.hpp"
 | 
			
		||||
| 
						 | 
				
			
			@ -29,25 +29,23 @@ namespace Slic3r { namespace sla {
 | 
			
		|||
 | 
			
		||||
namespace {
 | 
			
		||||
 | 
			
		||||
Contour3D walls(
 | 
			
		||||
indexed_triangle_set walls(
 | 
			
		||||
    const Polygon &lower,
 | 
			
		||||
    const Polygon &upper,
 | 
			
		||||
    double         lower_z_mm,
 | 
			
		||||
    double         upper_z_mm)
 | 
			
		||||
{
 | 
			
		||||
    Wall w = triangulate_wall(lower, upper, lower_z_mm, upper_z_mm);
 | 
			
		||||
 | 
			
		||||
    Contour3D ret;
 | 
			
		||||
    ret.points = std::move(w.first);
 | 
			
		||||
    ret.faces3 = std::move(w.second);
 | 
			
		||||
    indexed_triangle_set w;
 | 
			
		||||
    triangulate_wall(w.vertices, w.indices, lower, upper, lower_z_mm,
 | 
			
		||||
                     upper_z_mm);
 | 
			
		||||
    
 | 
			
		||||
    return ret;
 | 
			
		||||
    return w;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
// Same as walls() but with identical higher and lower polygons.
 | 
			
		||||
Contour3D inline straight_walls(const Polygon &plate,
 | 
			
		||||
                                double         lo_z,
 | 
			
		||||
                                double         hi_z)
 | 
			
		||||
inline indexed_triangle_set straight_walls(const Polygon &plate,
 | 
			
		||||
                                           double         lo_z,
 | 
			
		||||
                                           double         hi_z)
 | 
			
		||||
{
 | 
			
		||||
    return walls(plate, plate, lo_z, hi_z);
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			@ -357,8 +355,10 @@ ExPolygon offset_contour_only(const ExPolygon &poly, coord_t delta, Args...args)
 | 
			
		|||
    return std::move(tmp2.front());
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
bool add_cavity(Contour3D &pad, ExPolygon &top_poly, const PadConfig3D &cfg,
 | 
			
		||||
                ThrowOnCancel thr)
 | 
			
		||||
bool add_cavity(indexed_triangle_set &pad,
 | 
			
		||||
                ExPolygon &           top_poly,
 | 
			
		||||
                const PadConfig3D &   cfg,
 | 
			
		||||
                ThrowOnCancel         thr)
 | 
			
		||||
{
 | 
			
		||||
    auto logerr = []{BOOST_LOG_TRIVIAL(error)<<"Could not create pad cavity";};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -377,18 +377,18 @@ bool add_cavity(Contour3D &pad, ExPolygon &top_poly, const PadConfig3D &cfg,
 | 
			
		|||
    top_poly = pdiff.front();
 | 
			
		||||
 | 
			
		||||
    double z_min = -cfg.wing_height, z_max = 0;
 | 
			
		||||
    pad.merge(walls(inner_base.contour, middle_base.contour, z_min, z_max));
 | 
			
		||||
    its_merge(pad, walls(inner_base.contour, middle_base.contour, z_min, z_max));
 | 
			
		||||
    thr();
 | 
			
		||||
    pad.merge(triangulate_expolygon_3d(inner_base, z_min, NORMALS_UP));
 | 
			
		||||
    its_merge(pad, triangulate_expolygon_3d(inner_base, z_min, NORMALS_UP));
 | 
			
		||||
 | 
			
		||||
    return true;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D create_outer_pad_geometry(const ExPolygons & skeleton,
 | 
			
		||||
                                    const PadConfig3D &cfg,
 | 
			
		||||
                                    ThrowOnCancel      thr)
 | 
			
		||||
indexed_triangle_set create_outer_pad_geometry(const ExPolygons & skeleton,
 | 
			
		||||
                                               const PadConfig3D &cfg,
 | 
			
		||||
                                               ThrowOnCancel      thr)
 | 
			
		||||
{
 | 
			
		||||
    Contour3D ret;
 | 
			
		||||
    indexed_triangle_set ret;
 | 
			
		||||
 | 
			
		||||
    for (const ExPolygon &pad_part : skeleton) {
 | 
			
		||||
        ExPolygon top_poly{pad_part};
 | 
			
		||||
| 
						 | 
				
			
			@ -399,45 +399,45 @@ Contour3D create_outer_pad_geometry(const ExPolygons & skeleton,
 | 
			
		|||
        thr();
 | 
			
		||||
        
 | 
			
		||||
        double z_min = -cfg.height, z_max = 0;
 | 
			
		||||
        ret.merge(walls(top_poly.contour, bottom_poly.contour, z_max, z_min));
 | 
			
		||||
        its_merge(ret, walls(top_poly.contour, bottom_poly.contour, z_max, z_min));
 | 
			
		||||
 | 
			
		||||
        if (cfg.wing_height > 0. && add_cavity(ret, top_poly, cfg, thr))
 | 
			
		||||
            z_max = -cfg.wing_height;
 | 
			
		||||
 | 
			
		||||
        for (auto &h : bottom_poly.holes)
 | 
			
		||||
            ret.merge(straight_walls(h, z_max, z_min));
 | 
			
		||||
            its_merge(ret, straight_walls(h, z_max, z_min));
 | 
			
		||||
        
 | 
			
		||||
        ret.merge(triangulate_expolygon_3d(bottom_poly, z_min, NORMALS_DOWN));
 | 
			
		||||
        ret.merge(triangulate_expolygon_3d(top_poly, NORMALS_UP));
 | 
			
		||||
        its_merge(ret, triangulate_expolygon_3d(bottom_poly, z_min, NORMALS_DOWN));
 | 
			
		||||
        its_merge(ret, triangulate_expolygon_3d(top_poly, NORMALS_UP));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    return ret;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D create_inner_pad_geometry(const ExPolygons & skeleton,
 | 
			
		||||
                                    const PadConfig3D &cfg,
 | 
			
		||||
                                    ThrowOnCancel      thr)
 | 
			
		||||
indexed_triangle_set create_inner_pad_geometry(const ExPolygons & skeleton,
 | 
			
		||||
                                               const PadConfig3D &cfg,
 | 
			
		||||
                                               ThrowOnCancel      thr)
 | 
			
		||||
{
 | 
			
		||||
    Contour3D ret;
 | 
			
		||||
    indexed_triangle_set ret;
 | 
			
		||||
 | 
			
		||||
    double z_max = 0., z_min = -cfg.height;
 | 
			
		||||
    for (const ExPolygon &pad_part : skeleton) {
 | 
			
		||||
        thr();
 | 
			
		||||
        ret.merge(straight_walls(pad_part.contour, z_max, z_min));
 | 
			
		||||
        its_merge(ret, straight_walls(pad_part.contour, z_max, z_min));
 | 
			
		||||
 | 
			
		||||
        for (auto &h : pad_part.holes)
 | 
			
		||||
            ret.merge(straight_walls(h, z_max, z_min));
 | 
			
		||||
            its_merge(ret, straight_walls(h, z_max, z_min));
 | 
			
		||||
    
 | 
			
		||||
        ret.merge(triangulate_expolygon_3d(pad_part, z_min, NORMALS_DOWN));
 | 
			
		||||
        ret.merge(triangulate_expolygon_3d(pad_part, z_max, NORMALS_UP));
 | 
			
		||||
        its_merge(ret, triangulate_expolygon_3d(pad_part, z_min, NORMALS_DOWN));
 | 
			
		||||
        its_merge(ret, triangulate_expolygon_3d(pad_part, z_max, NORMALS_UP));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    return ret;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D create_pad_geometry(const PadSkeleton &skelet,
 | 
			
		||||
                              const PadConfig &  cfg,
 | 
			
		||||
                              ThrowOnCancel      thr)
 | 
			
		||||
indexed_triangle_set create_pad_geometry(const PadSkeleton &skelet,
 | 
			
		||||
                                         const PadConfig &  cfg,
 | 
			
		||||
                                         ThrowOnCancel      thr)
 | 
			
		||||
{
 | 
			
		||||
#ifndef NDEBUG
 | 
			
		||||
    SVG svg("pad_skeleton.svg");
 | 
			
		||||
| 
						 | 
				
			
			@ -447,14 +447,16 @@ Contour3D create_pad_geometry(const PadSkeleton &skelet,
 | 
			
		|||
#endif
 | 
			
		||||
 | 
			
		||||
    PadConfig3D cfg3d(cfg);
 | 
			
		||||
    return create_outer_pad_geometry(skelet.outer, cfg3d, thr)
 | 
			
		||||
        .merge(create_inner_pad_geometry(skelet.inner, cfg3d, thr));
 | 
			
		||||
    auto pg = create_outer_pad_geometry(skelet.outer, cfg3d, thr);
 | 
			
		||||
    its_merge(pg, create_inner_pad_geometry(skelet.inner, cfg3d, thr));
 | 
			
		||||
 | 
			
		||||
    return pg;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D create_pad_geometry(const ExPolygons &supp_bp,
 | 
			
		||||
                              const ExPolygons &model_bp,
 | 
			
		||||
                              const PadConfig & cfg,
 | 
			
		||||
                              ThrowOnCancel thr)
 | 
			
		||||
indexed_triangle_set create_pad_geometry(const ExPolygons &supp_bp,
 | 
			
		||||
                                         const ExPolygons &model_bp,
 | 
			
		||||
                                         const PadConfig & cfg,
 | 
			
		||||
                                         ThrowOnCancel     thr)
 | 
			
		||||
{
 | 
			
		||||
    PadSkeleton skelet;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -471,15 +473,15 @@ Contour3D create_pad_geometry(const ExPolygons &supp_bp,
 | 
			
		|||
 | 
			
		||||
} // namespace
 | 
			
		||||
 | 
			
		||||
void pad_blueprint(const TriangleMesh &      mesh,
 | 
			
		||||
                   ExPolygons &              output,
 | 
			
		||||
                   const std::vector<float> &heights,
 | 
			
		||||
                   ThrowOnCancel             thrfn)
 | 
			
		||||
void pad_blueprint(const indexed_triangle_set &mesh,
 | 
			
		||||
                   ExPolygons &                output,
 | 
			
		||||
                   const std::vector<float> &  heights,
 | 
			
		||||
                   ThrowOnCancel               thrfn)
 | 
			
		||||
{
 | 
			
		||||
    if (mesh.empty()) return;
 | 
			
		||||
 | 
			
		||||
    assert(mesh.has_shared_vertices());
 | 
			
		||||
    std::vector<ExPolygons> out = slice_mesh_ex(mesh.its, heights, thrfn);
 | 
			
		||||
    std::vector<ExPolygons> out = slice_mesh_ex(mesh, heights, thrfn);
 | 
			
		||||
 | 
			
		||||
    size_t count = 0;
 | 
			
		||||
    for(auto& o : out) count += o.size();
 | 
			
		||||
| 
						 | 
				
			
			@ -500,26 +502,26 @@ void pad_blueprint(const TriangleMesh &      mesh,
 | 
			
		|||
    }
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void pad_blueprint(const TriangleMesh &mesh,
 | 
			
		||||
                   ExPolygons &        output,
 | 
			
		||||
                   float               h,
 | 
			
		||||
                   float               layerh,
 | 
			
		||||
                   ThrowOnCancel       thrfn)
 | 
			
		||||
void pad_blueprint(const indexed_triangle_set &mesh,
 | 
			
		||||
                   ExPolygons &                output,
 | 
			
		||||
                   float                       h,
 | 
			
		||||
                   float                       layerh,
 | 
			
		||||
                   ThrowOnCancel               thrfn)
 | 
			
		||||
{
 | 
			
		||||
    float gnd = float(mesh.bounding_box().min(Z));
 | 
			
		||||
    float gnd = float(bounding_box(mesh).min(Z));
 | 
			
		||||
 | 
			
		||||
    std::vector<float> slicegrid = grid(gnd, gnd + h, layerh);
 | 
			
		||||
    pad_blueprint(mesh, output, slicegrid, thrfn);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void create_pad(const ExPolygons &sup_blueprint,
 | 
			
		||||
                const ExPolygons &model_blueprint,
 | 
			
		||||
                TriangleMesh &    out,
 | 
			
		||||
                const PadConfig & cfg,
 | 
			
		||||
                ThrowOnCancel thr)
 | 
			
		||||
void create_pad(const ExPolygons &    sup_blueprint,
 | 
			
		||||
                const ExPolygons &    model_blueprint,
 | 
			
		||||
                indexed_triangle_set &out,
 | 
			
		||||
                const PadConfig &     cfg,
 | 
			
		||||
                ThrowOnCancel         thr)
 | 
			
		||||
{
 | 
			
		||||
    Contour3D t = create_pad_geometry(sup_blueprint, model_blueprint, cfg, thr);
 | 
			
		||||
    out.merge(to_triangle_mesh(std::move(t)));
 | 
			
		||||
    auto t = create_pad_geometry(sup_blueprint, model_blueprint, cfg, thr);
 | 
			
		||||
    its_merge(out, t);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
std::string PadConfig::validate() const
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -6,6 +6,8 @@
 | 
			
		|||
#include <cmath>
 | 
			
		||||
#include <string>
 | 
			
		||||
 | 
			
		||||
struct indexed_triangle_set;
 | 
			
		||||
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
 | 
			
		||||
class ExPolygon;
 | 
			
		||||
| 
						 | 
				
			
			@ -13,25 +15,23 @@ class Polygon;
 | 
			
		|||
using ExPolygons = std::vector<ExPolygon>;
 | 
			
		||||
using Polygons = std::vector<Polygon>;
 | 
			
		||||
 | 
			
		||||
class TriangleMesh;
 | 
			
		||||
 | 
			
		||||
namespace sla {
 | 
			
		||||
 | 
			
		||||
using ThrowOnCancel = std::function<void(void)>;
 | 
			
		||||
 | 
			
		||||
/// Calculate the polygon representing the silhouette.
 | 
			
		||||
void pad_blueprint(
 | 
			
		||||
    const TriangleMesh &mesh,       // input mesh
 | 
			
		||||
    const indexed_triangle_set &mesh,       // input mesh
 | 
			
		||||
    ExPolygons &        output,     // Output will be merged with
 | 
			
		||||
    const std::vector<float> &,     // Exact Z levels to sample
 | 
			
		||||
    ThrowOnCancel thrfn = [] {}); // Function that throws if cancel was requested
 | 
			
		||||
 | 
			
		||||
void pad_blueprint(
 | 
			
		||||
    const TriangleMesh &mesh,
 | 
			
		||||
    ExPolygons &        output,
 | 
			
		||||
    float               samplingheight = 0.1f,  // The height range to sample
 | 
			
		||||
    float               layerheight    = 0.05f, // The sampling height
 | 
			
		||||
    ThrowOnCancel       thrfn = [] {});
 | 
			
		||||
    const indexed_triangle_set &mesh,
 | 
			
		||||
    ExPolygons &                output,
 | 
			
		||||
    float         samplingheight = 0.1f,  // The height range to sample
 | 
			
		||||
    float         layerheight    = 0.05f, // The sampling height
 | 
			
		||||
    ThrowOnCancel thrfn          = [] {});
 | 
			
		||||
 | 
			
		||||
struct PadConfig {
 | 
			
		||||
    double wall_thickness_mm = 1.;
 | 
			
		||||
| 
						 | 
				
			
			@ -82,11 +82,12 @@ struct PadConfig {
 | 
			
		|||
    std::string validate() const;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
void create_pad(const ExPolygons &support_contours,
 | 
			
		||||
                const ExPolygons &model_contours,
 | 
			
		||||
                TriangleMesh &    output_mesh,
 | 
			
		||||
                const PadConfig & = PadConfig(),
 | 
			
		||||
                ThrowOnCancel throw_on_cancel = []{});
 | 
			
		||||
void create_pad(
 | 
			
		||||
    const ExPolygons &    support_contours,
 | 
			
		||||
    const ExPolygons &    model_contours,
 | 
			
		||||
    indexed_triangle_set &output_mesh,
 | 
			
		||||
    const PadConfig &             = PadConfig(),
 | 
			
		||||
    ThrowOnCancel throw_on_cancel = [] {});
 | 
			
		||||
 | 
			
		||||
} // namespace sla
 | 
			
		||||
} // namespace Slic3r
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -29,16 +29,16 @@
 | 
			
		|||
namespace Slic3r {
 | 
			
		||||
namespace sla {
 | 
			
		||||
 | 
			
		||||
void SupportTree::retrieve_full_mesh(TriangleMesh &outmesh) const {
 | 
			
		||||
    outmesh.merge(retrieve_mesh(MeshType::Support));
 | 
			
		||||
    outmesh.merge(retrieve_mesh(MeshType::Pad));
 | 
			
		||||
void SupportTree::retrieve_full_mesh(indexed_triangle_set &outmesh) const {
 | 
			
		||||
    its_merge(outmesh, retrieve_mesh(MeshType::Support));
 | 
			
		||||
    its_merge(outmesh, retrieve_mesh(MeshType::Pad));
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
std::vector<ExPolygons> SupportTree::slice(
 | 
			
		||||
    const std::vector<float> &grid, float cr) const
 | 
			
		||||
std::vector<ExPolygons> SupportTree::slice(const std::vector<float> &grid,
 | 
			
		||||
                                           float                     cr) const
 | 
			
		||||
{
 | 
			
		||||
    const TriangleMesh &sup_mesh = retrieve_mesh(MeshType::Support);
 | 
			
		||||
    const TriangleMesh &pad_mesh = retrieve_mesh(MeshType::Pad);
 | 
			
		||||
    const indexed_triangle_set &sup_mesh = retrieve_mesh(MeshType::Support);
 | 
			
		||||
    const indexed_triangle_set &pad_mesh = retrieve_mesh(MeshType::Pad);
 | 
			
		||||
 | 
			
		||||
    using Slices = std::vector<ExPolygons>;
 | 
			
		||||
    auto slices = reserve_vector<Slices>(2);
 | 
			
		||||
| 
						 | 
				
			
			@ -46,13 +46,13 @@ std::vector<ExPolygons> SupportTree::slice(
 | 
			
		|||
    if (!sup_mesh.empty()) {
 | 
			
		||||
        slices.emplace_back();
 | 
			
		||||
        assert(sup_mesh.has_shared_vertices());
 | 
			
		||||
        slices.back() = slice_mesh_ex(sup_mesh.its, grid, cr, ctl().cancelfn);
 | 
			
		||||
        slices.back() = slice_mesh_ex(sup_mesh, grid, cr, ctl().cancelfn);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    if (!pad_mesh.empty()) {
 | 
			
		||||
        slices.emplace_back();
 | 
			
		||||
 | 
			
		||||
        auto bb = pad_mesh.bounding_box();
 | 
			
		||||
        auto bb = bounding_box(pad_mesh);
 | 
			
		||||
        auto maxzit = std::upper_bound(grid.begin(), grid.end(), bb.max.z());
 | 
			
		||||
        
 | 
			
		||||
        auto cap = grid.end() - maxzit;
 | 
			
		||||
| 
						 | 
				
			
			@ -60,7 +60,7 @@ std::vector<ExPolygons> SupportTree::slice(
 | 
			
		|||
        std::copy(grid.begin(), maxzit, std::back_inserter(padgrid));
 | 
			
		||||
 | 
			
		||||
        assert(pad_mesh.has_shared_vertices());
 | 
			
		||||
        slices.back() = slice_mesh_ex(pad_mesh.its, padgrid, cr, ctl().cancelfn);
 | 
			
		||||
        slices.back() = slice_mesh_ex(pad_mesh, padgrid, cr, ctl().cancelfn);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    size_t len = grid.size();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -122,9 +122,9 @@ struct SupportableMesh
 | 
			
		|||
    IndexedMesh  emesh;
 | 
			
		||||
    SupportPoints pts;
 | 
			
		||||
    SupportTreeConfig cfg;
 | 
			
		||||
    PadConfig     pad_cfg;
 | 
			
		||||
//    PadConfig     pad_cfg;
 | 
			
		||||
 | 
			
		||||
    explicit SupportableMesh(const TriangleMesh & trmsh,
 | 
			
		||||
    explicit SupportableMesh(const indexed_triangle_set & trmsh,
 | 
			
		||||
                             const SupportPoints &sp,
 | 
			
		||||
                             const SupportTreeConfig &c)
 | 
			
		||||
        : emesh{trmsh}, pts{sp}, cfg{c}
 | 
			
		||||
| 
						 | 
				
			
			@ -149,22 +149,22 @@ public:
 | 
			
		|||
 | 
			
		||||
    virtual ~SupportTree() = default;
 | 
			
		||||
 | 
			
		||||
    virtual const TriangleMesh &retrieve_mesh(MeshType meshtype) const = 0;
 | 
			
		||||
    virtual const indexed_triangle_set &retrieve_mesh(MeshType meshtype) const = 0;
 | 
			
		||||
 | 
			
		||||
    /// Adding the "pad" under the supports.
 | 
			
		||||
    /// modelbase will be used according to the embed_object flag in PoolConfig.
 | 
			
		||||
    /// If set, the plate will be interpreted as the model's intrinsic pad. 
 | 
			
		||||
    /// Otherwise, the modelbase will be unified with the base plate calculated
 | 
			
		||||
    /// from the supports.
 | 
			
		||||
    virtual const TriangleMesh &add_pad(const ExPolygons &modelbase,
 | 
			
		||||
                                        const PadConfig & pcfg) = 0;
 | 
			
		||||
    
 | 
			
		||||
    virtual const indexed_triangle_set &add_pad(const ExPolygons &modelbase,
 | 
			
		||||
                                                const PadConfig & pcfg) = 0;
 | 
			
		||||
 | 
			
		||||
    virtual void remove_pad() = 0;
 | 
			
		||||
    
 | 
			
		||||
    std::vector<ExPolygons> slice(const std::vector<float> &,
 | 
			
		||||
                                  float closing_radius) const;
 | 
			
		||||
    
 | 
			
		||||
    void retrieve_full_mesh(TriangleMesh &outmesh) const;
 | 
			
		||||
    void retrieve_full_mesh(indexed_triangle_set &outmesh) const;
 | 
			
		||||
    
 | 
			
		||||
    const JobController &ctl() const { return m_ctl; }
 | 
			
		||||
};
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -3,7 +3,7 @@
 | 
			
		|||
#include <libslic3r/SLA/SupportTreeBuilder.hpp>
 | 
			
		||||
#include <libslic3r/SLA/SupportTreeBuildsteps.hpp>
 | 
			
		||||
#include <libslic3r/SLA/SupportTreeMesher.hpp>
 | 
			
		||||
#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
//#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
namespace sla {
 | 
			
		||||
| 
						 | 
				
			
			@ -23,11 +23,11 @@ Head::Head(double       r_big_mm,
 | 
			
		|||
{
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Pad::Pad(const TriangleMesh &support_mesh,
 | 
			
		||||
         const ExPolygons &  model_contours,
 | 
			
		||||
         double              ground_level,
 | 
			
		||||
         const PadConfig &   pcfg,
 | 
			
		||||
         ThrowOnCancel       thr)
 | 
			
		||||
Pad::Pad(const indexed_triangle_set &support_mesh,
 | 
			
		||||
         const ExPolygons &          model_contours,
 | 
			
		||||
         double                      ground_level,
 | 
			
		||||
         const PadConfig &           pcfg,
 | 
			
		||||
         ThrowOnCancel               thr)
 | 
			
		||||
    : cfg(pcfg)
 | 
			
		||||
    , zlevel(ground_level + pcfg.full_height() - pcfg.required_elevation())
 | 
			
		||||
{
 | 
			
		||||
| 
						 | 
				
			
			@ -41,12 +41,14 @@ Pad::Pad(const TriangleMesh &support_mesh,
 | 
			
		|||
    pad_blueprint(support_mesh, sup_contours, grid(zstart, zend, 0.1f), thr);
 | 
			
		||||
    create_pad(sup_contours, model_contours, tmesh, pcfg);
 | 
			
		||||
    
 | 
			
		||||
    tmesh.translate(0, 0, float(zlevel));
 | 
			
		||||
    if (!tmesh.empty()) tmesh.require_shared_vertices();
 | 
			
		||||
    Vec3f offs{.0f, .0f, float(zlevel)};
 | 
			
		||||
    for (auto &p : tmesh.vertices) p += offs;
 | 
			
		||||
 | 
			
		||||
    its_merge_vertices(tmesh);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
const TriangleMesh &SupportTreeBuilder::add_pad(const ExPolygons &modelbase,
 | 
			
		||||
                                                const PadConfig & cfg)
 | 
			
		||||
const indexed_triangle_set &SupportTreeBuilder::add_pad(
 | 
			
		||||
    const ExPolygons &modelbase, const PadConfig &cfg)
 | 
			
		||||
{
 | 
			
		||||
    m_pad = Pad{merged_mesh(), modelbase, ground_level, cfg, ctl().cancelfn};
 | 
			
		||||
    return m_pad.tmesh;
 | 
			
		||||
| 
						 | 
				
			
			@ -120,74 +122,74 @@ void SupportTreeBuilder::add_pillar_base(long pid, double baseheight, double rad
 | 
			
		|||
    m_meshcache_valid = false;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
const TriangleMesh &SupportTreeBuilder::merged_mesh(size_t steps) const
 | 
			
		||||
const indexed_triangle_set &SupportTreeBuilder::merged_mesh(size_t steps) const
 | 
			
		||||
{
 | 
			
		||||
    if (m_meshcache_valid) return m_meshcache;
 | 
			
		||||
    
 | 
			
		||||
    Contour3D merged;
 | 
			
		||||
    indexed_triangle_set merged;
 | 
			
		||||
    
 | 
			
		||||
    for (auto &head : m_heads) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        if (head.is_valid()) merged.merge(get_mesh(head, steps));
 | 
			
		||||
        if (head.is_valid()) its_merge(merged, get_mesh(head, steps));
 | 
			
		||||
    }
 | 
			
		||||
    
 | 
			
		||||
    for (auto &pill : m_pillars) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(pill, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(pill, steps));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    for (auto &pedest : m_pedestals) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(pedest, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(pedest, steps));
 | 
			
		||||
    }
 | 
			
		||||
    
 | 
			
		||||
    for (auto &j : m_junctions) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(j, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(j, steps));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    for (auto &bs : m_bridges) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(bs, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(bs, steps));
 | 
			
		||||
    }
 | 
			
		||||
    
 | 
			
		||||
    for (auto &bs : m_crossbridges) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(bs, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(bs, steps));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    for (auto &bs : m_diffbridges) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(bs, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(bs, steps));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    for (auto &anch : m_anchors) {
 | 
			
		||||
        if (ctl().stopcondition()) break;
 | 
			
		||||
        merged.merge(get_mesh(anch, steps));
 | 
			
		||||
        its_merge(merged, get_mesh(anch, steps));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    if (ctl().stopcondition()) {
 | 
			
		||||
        // In case of failure we have to return an empty mesh
 | 
			
		||||
        m_meshcache = TriangleMesh();
 | 
			
		||||
        m_meshcache = {};
 | 
			
		||||
        return m_meshcache;
 | 
			
		||||
    }
 | 
			
		||||
    
 | 
			
		||||
    m_meshcache = to_triangle_mesh(merged);
 | 
			
		||||
    m_meshcache = merged;
 | 
			
		||||
    
 | 
			
		||||
    // The mesh will be passed by const-pointer to TriangleMeshSlicer,
 | 
			
		||||
    // which will need this.
 | 
			
		||||
    if (!m_meshcache.empty()) m_meshcache.require_shared_vertices();
 | 
			
		||||
    
 | 
			
		||||
    BoundingBoxf3 &&bb = m_meshcache.bounding_box();
 | 
			
		||||
    m_model_height       = bb.max(Z) - bb.min(Z);
 | 
			
		||||
    its_merge_vertices(m_meshcache);
 | 
			
		||||
    
 | 
			
		||||
    BoundingBoxf3 bb = bounding_box(m_meshcache);
 | 
			
		||||
    m_model_height   = bb.max(Z) - bb.min(Z);
 | 
			
		||||
 | 
			
		||||
    m_meshcache_valid = true;
 | 
			
		||||
    return m_meshcache;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
double SupportTreeBuilder::full_height() const
 | 
			
		||||
{
 | 
			
		||||
    if (merged_mesh().empty() && !pad().empty())
 | 
			
		||||
    if (merged_mesh().indices.empty() && !pad().empty())
 | 
			
		||||
        return pad().cfg.full_height();
 | 
			
		||||
    
 | 
			
		||||
    double h = mesh_height();
 | 
			
		||||
| 
						 | 
				
			
			@ -195,7 +197,7 @@ double SupportTreeBuilder::full_height() const
 | 
			
		|||
    return h;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
const TriangleMesh &SupportTreeBuilder::merge_and_cleanup()
 | 
			
		||||
const indexed_triangle_set &SupportTreeBuilder::merge_and_cleanup()
 | 
			
		||||
{
 | 
			
		||||
    // in case the mesh is not generated, it should be...
 | 
			
		||||
    auto &ret = merged_mesh(); 
 | 
			
		||||
| 
						 | 
				
			
			@ -210,7 +212,7 @@ const TriangleMesh &SupportTreeBuilder::merge_and_cleanup()
 | 
			
		|||
    return ret;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
const TriangleMesh &SupportTreeBuilder::retrieve_mesh(MeshType meshtype) const
 | 
			
		||||
const indexed_triangle_set &SupportTreeBuilder::retrieve_mesh(MeshType meshtype) const
 | 
			
		||||
{
 | 
			
		||||
    switch(meshtype) {
 | 
			
		||||
    case MeshType::Support: return merged_mesh();
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -3,7 +3,8 @@
 | 
			
		|||
 | 
			
		||||
#include <libslic3r/SLA/Concurrency.hpp>
 | 
			
		||||
#include <libslic3r/SLA/SupportTree.hpp>
 | 
			
		||||
#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
//#include <libslic3r/SLA/Contour3D.hpp>
 | 
			
		||||
#include <libslic3r/TriangleMesh.hpp>
 | 
			
		||||
#include <libslic3r/SLA/Pad.hpp>
 | 
			
		||||
#include <libslic3r/MTUtils.hpp>
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -187,19 +188,19 @@ struct DiffBridge: public Bridge {
 | 
			
		|||
 | 
			
		||||
// A wrapper struct around the pad
 | 
			
		||||
struct Pad {
 | 
			
		||||
    TriangleMesh tmesh;
 | 
			
		||||
    indexed_triangle_set tmesh;
 | 
			
		||||
    PadConfig cfg;
 | 
			
		||||
    double zlevel = 0;
 | 
			
		||||
    
 | 
			
		||||
    Pad() = default;
 | 
			
		||||
    
 | 
			
		||||
    Pad(const TriangleMesh &support_mesh,
 | 
			
		||||
        const ExPolygons &  model_contours,
 | 
			
		||||
        double              ground_level,
 | 
			
		||||
        const PadConfig &   pcfg,
 | 
			
		||||
        ThrowOnCancel       thr);
 | 
			
		||||
    
 | 
			
		||||
    bool empty() const { return tmesh.facets_count() == 0; }
 | 
			
		||||
 | 
			
		||||
    Pad(const indexed_triangle_set &support_mesh,
 | 
			
		||||
        const ExPolygons &          model_contours,
 | 
			
		||||
        double                      ground_level,
 | 
			
		||||
        const PadConfig &           pcfg,
 | 
			
		||||
        ThrowOnCancel               thr);
 | 
			
		||||
 | 
			
		||||
    bool empty() const { return tmesh.indices.size() == 0; }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
// This class will hold the support tree meshes with some additional
 | 
			
		||||
| 
						 | 
				
			
			@ -232,7 +233,7 @@ class SupportTreeBuilder: public SupportTree {
 | 
			
		|||
    
 | 
			
		||||
    using Mutex = ccr::SpinningMutex;
 | 
			
		||||
    
 | 
			
		||||
    mutable TriangleMesh m_meshcache;
 | 
			
		||||
    mutable indexed_triangle_set m_meshcache;
 | 
			
		||||
    mutable Mutex m_mutex;
 | 
			
		||||
    mutable bool m_meshcache_valid = false;
 | 
			
		||||
    mutable double m_model_height = 0; // the full height of the model
 | 
			
		||||
| 
						 | 
				
			
			@ -418,7 +419,7 @@ public:
 | 
			
		|||
    const Pad& pad() const { return m_pad; }
 | 
			
		||||
    
 | 
			
		||||
    // WITHOUT THE PAD!!!
 | 
			
		||||
    const TriangleMesh &merged_mesh(size_t steps = 45) const;
 | 
			
		||||
    const indexed_triangle_set &merged_mesh(size_t steps = 45) const;
 | 
			
		||||
    
 | 
			
		||||
    // WITH THE PAD
 | 
			
		||||
    double full_height() const;
 | 
			
		||||
| 
						 | 
				
			
			@ -431,16 +432,16 @@ public:
 | 
			
		|||
    }
 | 
			
		||||
    
 | 
			
		||||
    // Intended to be called after the generation is fully complete
 | 
			
		||||
    const TriangleMesh & merge_and_cleanup();
 | 
			
		||||
    const indexed_triangle_set & merge_and_cleanup();
 | 
			
		||||
    
 | 
			
		||||
    // Implement SupportTree interface:
 | 
			
		||||
 | 
			
		||||
    const TriangleMesh &add_pad(const ExPolygons &modelbase,
 | 
			
		||||
                                const PadConfig & pcfg) override;
 | 
			
		||||
    
 | 
			
		||||
    const indexed_triangle_set &add_pad(const ExPolygons &modelbase,
 | 
			
		||||
                                        const PadConfig & pcfg) override;
 | 
			
		||||
 | 
			
		||||
    void remove_pad() override { m_pad = Pad(); }
 | 
			
		||||
    
 | 
			
		||||
    virtual const TriangleMesh &retrieve_mesh(
 | 
			
		||||
 | 
			
		||||
    virtual const indexed_triangle_set &retrieve_mesh(
 | 
			
		||||
        MeshType meshtype = MeshType::Support) const override;
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -2,22 +2,22 @@
 | 
			
		|||
 | 
			
		||||
namespace Slic3r { namespace sla {
 | 
			
		||||
 | 
			
		||||
Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		||||
indexed_triangle_set sphere(double rho, Portion portion, double fa) {
 | 
			
		||||
 | 
			
		||||
    Contour3D ret;
 | 
			
		||||
    indexed_triangle_set ret;
 | 
			
		||||
 | 
			
		||||
    // prohibit close to zero radius
 | 
			
		||||
    if(rho <= 1e-6 && rho >= -1e-6) return ret;
 | 
			
		||||
 | 
			
		||||
    auto& vertices = ret.points;
 | 
			
		||||
    auto& facets = ret.faces3;
 | 
			
		||||
    auto& vertices = ret.vertices;
 | 
			
		||||
    auto& facets = ret.indices;
 | 
			
		||||
 | 
			
		||||
    // Algorithm:
 | 
			
		||||
    // Add points one-by-one to the sphere grid and form facets using relative
 | 
			
		||||
    // coordinates. Sphere is composed effectively of a mesh of stacked circles.
 | 
			
		||||
 | 
			
		||||
    // adjust via rounding to get an even multiple for any provided angle.
 | 
			
		||||
    double angle = (2*PI / floor(2*PI / fa));
 | 
			
		||||
    double angle = (2 * PI / floor(2*PI / fa) );
 | 
			
		||||
 | 
			
		||||
    // Ring to be scaled to generate the steps of the sphere
 | 
			
		||||
    std::vector<double> ring;
 | 
			
		||||
| 
						 | 
				
			
			@ -32,8 +32,9 @@ Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		|||
 | 
			
		||||
    // special case: first ring connects to 0,0,0
 | 
			
		||||
    // insert and form facets.
 | 
			
		||||
    if(sbegin == 0)
 | 
			
		||||
        vertices.emplace_back(Vec3d(0.0, 0.0, -rho + increment*sbegin*2.0*rho));
 | 
			
		||||
    if (sbegin == 0)
 | 
			
		||||
        vertices.emplace_back(
 | 
			
		||||
            Vec3f(0.f, 0.f, float(-rho + increment * sbegin * 2. * rho)));
 | 
			
		||||
 | 
			
		||||
    auto id = coord_t(vertices.size());
 | 
			
		||||
    for (size_t i = 0; i < ring.size(); i++) {
 | 
			
		||||
| 
						 | 
				
			
			@ -42,7 +43,7 @@ Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		|||
        // radius of the circle for this step.
 | 
			
		||||
        const double r = std::sqrt(std::abs(rho*rho - z*z));
 | 
			
		||||
        Vec2d b = Eigen::Rotation2Dd(ring[i]) * Eigen::Vector2d(0, r);
 | 
			
		||||
        vertices.emplace_back(Vec3d(b(0), b(1), z));
 | 
			
		||||
        vertices.emplace_back(Vec3d(b(0), b(1), z).cast<float>());
 | 
			
		||||
 | 
			
		||||
        if (sbegin == 0)
 | 
			
		||||
            (i == 0) ? facets.emplace_back(coord_t(ring.size()), 0, 1) :
 | 
			
		||||
| 
						 | 
				
			
			@ -53,12 +54,12 @@ Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		|||
    // General case: insert and form facets for each step,
 | 
			
		||||
    // joining it to the ring below it.
 | 
			
		||||
    for (size_t s = sbegin + 2; s < send - 1; s++) {
 | 
			
		||||
        const double z = -rho + increment*double(s*2.0*rho);
 | 
			
		||||
        const double z = -rho + increment * double(s * 2. * rho);
 | 
			
		||||
        const double r = std::sqrt(std::abs(rho*rho - z*z));
 | 
			
		||||
 | 
			
		||||
        for (size_t i = 0; i < ring.size(); i++) {
 | 
			
		||||
            Vec2d b = Eigen::Rotation2Dd(ring[i]) * Eigen::Vector2d(0, r);
 | 
			
		||||
            vertices.emplace_back(Vec3d(b(0), b(1), z));
 | 
			
		||||
            vertices.emplace_back(Vec3d(b(0), b(1), z).cast<float>());
 | 
			
		||||
            auto id_ringsize = coord_t(id - int(ring.size()));
 | 
			
		||||
            if (i == 0) {
 | 
			
		||||
                // wrap around
 | 
			
		||||
| 
						 | 
				
			
			@ -75,7 +76,7 @@ Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		|||
    // special case: last ring connects to 0,0,rho*2.0
 | 
			
		||||
    // only form facets.
 | 
			
		||||
    if(send >= size_t(2*PI / angle)) {
 | 
			
		||||
        vertices.emplace_back(Vec3d(0.0, 0.0, -rho + increment*send*2.0*rho));
 | 
			
		||||
        vertices.emplace_back(0.f, 0.f, float(-rho + increment*send*2.0*rho));
 | 
			
		||||
        for (size_t i = 0; i < ring.size(); i++) {
 | 
			
		||||
            auto id_ringsize = coord_t(id - int(ring.size()));
 | 
			
		||||
            if (i == 0) {
 | 
			
		||||
| 
						 | 
				
			
			@ -92,15 +93,15 @@ Contour3D sphere(double rho, Portion portion, double fa) {
 | 
			
		|||
    return ret;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D cylinder(double r, double h, size_t ssteps, const Vec3d &sp)
 | 
			
		||||
indexed_triangle_set cylinder(double r, double h, size_t ssteps, const Vec3d &sp)
 | 
			
		||||
{
 | 
			
		||||
    assert(ssteps > 0);
 | 
			
		||||
 | 
			
		||||
    Contour3D ret;
 | 
			
		||||
    indexed_triangle_set ret;
 | 
			
		||||
 | 
			
		||||
    auto steps = int(ssteps);
 | 
			
		||||
    auto& points = ret.points;
 | 
			
		||||
    auto& indices = ret.faces3;
 | 
			
		||||
    auto& points = ret.vertices;
 | 
			
		||||
    auto& indices = ret.indices;
 | 
			
		||||
    points.reserve(2*ssteps);
 | 
			
		||||
    double a = 2*PI/steps;
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -110,17 +111,17 @@ Contour3D cylinder(double r, double h, size_t ssteps, const Vec3d &sp)
 | 
			
		|||
    // Upper circle points
 | 
			
		||||
    for(int i = 0; i < steps; ++i) {
 | 
			
		||||
        double phi = i*a;
 | 
			
		||||
        double ex = endp(X) + r*std::cos(phi);
 | 
			
		||||
        double ey = endp(Y) + r*std::sin(phi);
 | 
			
		||||
        points.emplace_back(ex, ey, endp(Z));
 | 
			
		||||
        auto ex = float(endp(X) + r*std::cos(phi));
 | 
			
		||||
        auto ey = float(endp(Y) + r*std::sin(phi));
 | 
			
		||||
        points.emplace_back(ex, ey, float(endp(Z)));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    // Lower circle points
 | 
			
		||||
    for(int i = 0; i < steps; ++i) {
 | 
			
		||||
        double phi = i*a;
 | 
			
		||||
        double x = jp(X) + r*std::cos(phi);
 | 
			
		||||
        double y = jp(Y) + r*std::sin(phi);
 | 
			
		||||
        points.emplace_back(x, y, jp(Z));
 | 
			
		||||
        auto x = float(jp(X) + r*std::cos(phi));
 | 
			
		||||
        auto y = float(jp(Y) + r*std::sin(phi));
 | 
			
		||||
        points.emplace_back(x, y, float(jp(Z)));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    // Now create long triangles connecting upper and lower circles
 | 
			
		||||
| 
						 | 
				
			
			@ -139,13 +140,13 @@ Contour3D cylinder(double r, double h, size_t ssteps, const Vec3d &sp)
 | 
			
		|||
    // According to the slicing algorithms, we need to aid them with generating
 | 
			
		||||
    // a watertight body. So we create a triangle fan for the upper and lower
 | 
			
		||||
    // ending of the cylinder to close the geometry.
 | 
			
		||||
    points.emplace_back(jp); int ci = int(points.size() - 1);
 | 
			
		||||
    points.emplace_back(jp.cast<float>()); int ci = int(points.size() - 1);
 | 
			
		||||
    for(int i = 0; i < steps - 1; ++i)
 | 
			
		||||
        indices.emplace_back(i + offs + 1, i + offs, ci);
 | 
			
		||||
 | 
			
		||||
    indices.emplace_back(offs, steps + offs - 1, ci);
 | 
			
		||||
 | 
			
		||||
    points.emplace_back(endp); ci = int(points.size() - 1);
 | 
			
		||||
    points.emplace_back(endp.cast<float>()); ci = int(points.size() - 1);
 | 
			
		||||
    for(int i = 0; i < steps - 1; ++i)
 | 
			
		||||
        indices.emplace_back(ci, i, i + 1);
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -154,14 +155,17 @@ Contour3D cylinder(double r, double h, size_t ssteps, const Vec3d &sp)
 | 
			
		|||
    return ret;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D pinhead(double r_pin, double r_back, double length, size_t steps)
 | 
			
		||||
indexed_triangle_set pinhead(double r_pin,
 | 
			
		||||
                             double r_back,
 | 
			
		||||
                             double length,
 | 
			
		||||
                             size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    assert(steps > 0);
 | 
			
		||||
    assert(length >= 0.);
 | 
			
		||||
    assert(r_back > 0.);
 | 
			
		||||
    assert(r_pin > 0.);
 | 
			
		||||
 | 
			
		||||
    Contour3D mesh;
 | 
			
		||||
    indexed_triangle_set mesh;
 | 
			
		||||
 | 
			
		||||
    // We create two spheres which will be connected with a robe that fits
 | 
			
		||||
    // both circles perfectly.
 | 
			
		||||
| 
						 | 
				
			
			@ -187,66 +191,66 @@ Contour3D pinhead(double r_pin, double r_back, double length, size_t steps)
 | 
			
		|||
    auto &&s1 = sphere(r_back, make_portion(0, PI / 2 + phi), detail);
 | 
			
		||||
    auto &&s2 = sphere(r_pin, make_portion(PI / 2 + phi, PI), detail);
 | 
			
		||||
 | 
			
		||||
    for (auto &p : s2.points) p.z() += h;
 | 
			
		||||
    for (auto &p : s2.vertices) p.z() += h;
 | 
			
		||||
 | 
			
		||||
    mesh.merge(s1);
 | 
			
		||||
    mesh.merge(s2);
 | 
			
		||||
    its_merge(mesh, s1);
 | 
			
		||||
    its_merge(mesh, s2);
 | 
			
		||||
 | 
			
		||||
    for (size_t idx1 = s1.points.size() - steps, idx2 = s1.points.size();
 | 
			
		||||
         idx1 < s1.points.size() - 1; idx1++, idx2++) {
 | 
			
		||||
    for (size_t idx1 = s1.vertices.size() - steps, idx2 = s1.vertices.size();
 | 
			
		||||
         idx1 < s1.vertices.size() - 1; idx1++, idx2++) {
 | 
			
		||||
        coord_t i1s1 = coord_t(idx1), i1s2 = coord_t(idx2);
 | 
			
		||||
        coord_t i2s1 = i1s1 + 1, i2s2 = i1s2 + 1;
 | 
			
		||||
 | 
			
		||||
        mesh.faces3.emplace_back(i1s1, i2s1, i2s2);
 | 
			
		||||
        mesh.faces3.emplace_back(i1s1, i2s2, i1s2);
 | 
			
		||||
        mesh.indices.emplace_back(i1s1, i2s1, i2s2);
 | 
			
		||||
        mesh.indices.emplace_back(i1s1, i2s2, i1s2);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    auto i1s1 = coord_t(s1.points.size()) - coord_t(steps);
 | 
			
		||||
    auto i2s1 = coord_t(s1.points.size()) - 1;
 | 
			
		||||
    auto i1s2 = coord_t(s1.points.size());
 | 
			
		||||
    auto i2s2 = coord_t(s1.points.size()) + coord_t(steps) - 1;
 | 
			
		||||
    auto i1s1 = coord_t(s1.vertices.size()) - coord_t(steps);
 | 
			
		||||
    auto i2s1 = coord_t(s1.vertices.size()) - 1;
 | 
			
		||||
    auto i1s2 = coord_t(s1.vertices.size());
 | 
			
		||||
    auto i2s2 = coord_t(s1.vertices.size()) + coord_t(steps) - 1;
 | 
			
		||||
 | 
			
		||||
    mesh.faces3.emplace_back(i2s2, i2s1, i1s1);
 | 
			
		||||
    mesh.faces3.emplace_back(i1s2, i2s2, i1s1);
 | 
			
		||||
    mesh.indices.emplace_back(i2s2, i2s1, i1s1);
 | 
			
		||||
    mesh.indices.emplace_back(i1s2, i2s2, i1s1);
 | 
			
		||||
 | 
			
		||||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D halfcone(double       baseheight,
 | 
			
		||||
                   double       r_bottom,
 | 
			
		||||
                   double       r_top,
 | 
			
		||||
                   const Vec3d &pos,
 | 
			
		||||
                   size_t       steps)
 | 
			
		||||
indexed_triangle_set halfcone(double       baseheight,
 | 
			
		||||
                              double       r_bottom,
 | 
			
		||||
                              double       r_top,
 | 
			
		||||
                              const Vec3d &pos,
 | 
			
		||||
                              size_t       steps)
 | 
			
		||||
{
 | 
			
		||||
    assert(steps > 0);
 | 
			
		||||
 | 
			
		||||
    if (baseheight <= 0 || steps <= 0) return {};
 | 
			
		||||
 | 
			
		||||
    Contour3D base;
 | 
			
		||||
    indexed_triangle_set base;
 | 
			
		||||
 | 
			
		||||
    double a    = 2 * PI / steps;
 | 
			
		||||
    auto   last = int(steps - 1);
 | 
			
		||||
    Vec3d  ep{pos.x(), pos.y(), pos.z() + baseheight};
 | 
			
		||||
    for (size_t i = 0; i < steps; ++i) {
 | 
			
		||||
        double phi = i * a;
 | 
			
		||||
        double x   = pos.x() + r_top * std::cos(phi);
 | 
			
		||||
        double y   = pos.y() + r_top * std::sin(phi);
 | 
			
		||||
        base.points.emplace_back(x, y, ep.z());
 | 
			
		||||
        auto x   = float(pos.x() + r_top * std::cos(phi));
 | 
			
		||||
        auto y   = float(pos.y() + r_top * std::sin(phi));
 | 
			
		||||
        base.vertices.emplace_back(x, y, float(ep.z()));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    for (size_t i = 0; i < steps; ++i) {
 | 
			
		||||
        double phi = i * a;
 | 
			
		||||
        double x   = pos.x() + r_bottom * std::cos(phi);
 | 
			
		||||
        double y   = pos.y() + r_bottom * std::sin(phi);
 | 
			
		||||
        base.points.emplace_back(x, y, pos.z());
 | 
			
		||||
        auto x   = float(pos.x() + r_bottom * std::cos(phi));
 | 
			
		||||
        auto y   = float(pos.y() + r_bottom * std::sin(phi));
 | 
			
		||||
        base.vertices.emplace_back(x, y, float(pos.z()));
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    base.points.emplace_back(pos);
 | 
			
		||||
    base.points.emplace_back(ep);
 | 
			
		||||
    base.vertices.emplace_back(pos.cast<float>());
 | 
			
		||||
    base.vertices.emplace_back(ep.cast<float>());
 | 
			
		||||
 | 
			
		||||
    auto &indices = base.faces3;
 | 
			
		||||
    auto  hcenter = int(base.points.size() - 1);
 | 
			
		||||
    auto  lcenter = int(base.points.size() - 2);
 | 
			
		||||
    auto &indices = base.indices;
 | 
			
		||||
    auto  hcenter = int(base.vertices.size() - 1);
 | 
			
		||||
    auto  lcenter = int(base.vertices.size() - 2);
 | 
			
		||||
    auto  offs    = int(steps);
 | 
			
		||||
    for (int i = 0; i < last; ++i) {
 | 
			
		||||
        indices.emplace_back(i, i + offs, offs + i + 1);
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -4,7 +4,8 @@
 | 
			
		|||
#include "libslic3r/Point.hpp"
 | 
			
		||||
 | 
			
		||||
#include "libslic3r/SLA/SupportTreeBuilder.hpp"
 | 
			
		||||
#include "libslic3r/SLA/Contour3D.hpp"
 | 
			
		||||
#include "libslic3r/TriangleMesh.hpp"
 | 
			
		||||
//#include "libslic3r/SLA/Contour3D.hpp"
 | 
			
		||||
 | 
			
		||||
namespace Slic3r { namespace sla {
 | 
			
		||||
 | 
			
		||||
| 
						 | 
				
			
			@ -15,48 +16,53 @@ inline Portion make_portion(double a, double b)
 | 
			
		|||
    return std::make_tuple(a, b);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
Contour3D sphere(double  rho,
 | 
			
		||||
                 Portion portion = make_portion(0., 2. * PI),
 | 
			
		||||
                 double  fa      = (2. * PI / 360.));
 | 
			
		||||
indexed_triangle_set sphere(double  rho,
 | 
			
		||||
                            Portion portion = make_portion(0., 2. * PI),
 | 
			
		||||
                            double  fa      = (2. * PI / 360.));
 | 
			
		||||
 | 
			
		||||
// Down facing cylinder in Z direction with arguments:
 | 
			
		||||
// r: radius
 | 
			
		||||
// h: Height
 | 
			
		||||
// ssteps: how many edges will create the base circle
 | 
			
		||||
// sp: starting point
 | 
			
		||||
Contour3D cylinder(double       r,
 | 
			
		||||
                   double       h,
 | 
			
		||||
                   size_t       steps = 45,
 | 
			
		||||
                   const Vec3d &sp    = Vec3d::Zero());
 | 
			
		||||
indexed_triangle_set cylinder(double       r,
 | 
			
		||||
                              double       h,
 | 
			
		||||
                              size_t       steps = 45,
 | 
			
		||||
                              const Vec3d &sp    = Vec3d::Zero());
 | 
			
		||||
 | 
			
		||||
Contour3D pinhead(double r_pin, double r_back, double length, size_t steps = 45);
 | 
			
		||||
indexed_triangle_set pinhead(double r_pin,
 | 
			
		||||
                             double r_back,
 | 
			
		||||
                             double length,
 | 
			
		||||
                             size_t steps = 45);
 | 
			
		||||
 | 
			
		||||
Contour3D halfcone(double       baseheight,
 | 
			
		||||
                   double       r_bottom,
 | 
			
		||||
                   double       r_top,
 | 
			
		||||
                   const Vec3d &pt    = Vec3d::Zero(),
 | 
			
		||||
                   size_t       steps = 45);
 | 
			
		||||
indexed_triangle_set halfcone(double       baseheight,
 | 
			
		||||
                              double       r_bottom,
 | 
			
		||||
                              double       r_top,
 | 
			
		||||
                              const Vec3d &pt    = Vec3d::Zero(),
 | 
			
		||||
                              size_t       steps = 45);
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const Head &h, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const Head &h, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    Contour3D mesh = pinhead(h.r_pin_mm, h.r_back_mm, h.width_mm, steps);
 | 
			
		||||
    indexed_triangle_set mesh = pinhead(h.r_pin_mm, h.r_back_mm, h.width_mm, steps);
 | 
			
		||||
 | 
			
		||||
    for(auto& p : mesh.points) p.z() -= (h.fullwidth() - h.r_back_mm);
 | 
			
		||||
    for (auto& p : mesh.vertices) p.z() -= (h.fullwidth() - h.r_back_mm);
 | 
			
		||||
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<double>;
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<float>;
 | 
			
		||||
 | 
			
		||||
    // We rotate the head to the specified direction. The head's pointing
 | 
			
		||||
    // side is facing upwards so this means that it would hold a support
 | 
			
		||||
    // point with a normal pointing straight down. This is the reason of
 | 
			
		||||
    // the -1 z coordinate
 | 
			
		||||
    auto quatern = Quaternion::FromTwoVectors(Vec3d{0, 0, -1}, h.dir);
 | 
			
		||||
    auto quatern = Quaternion::FromTwoVectors(Vec3f{0.f, 0.f, -1.f},
 | 
			
		||||
                                              h.dir.cast<float>());
 | 
			
		||||
 | 
			
		||||
    for(auto& p : mesh.points) p = quatern * p + h.pos;
 | 
			
		||||
    Vec3f pos = h.pos.cast<float>();
 | 
			
		||||
    for (auto& p : mesh.vertices) p = quatern * p + pos;
 | 
			
		||||
 | 
			
		||||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const Pillar &p, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const Pillar &p, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    if(p.height > EPSILON) { // Endpoint is below the starting point
 | 
			
		||||
        // We just create a bridge geometry with the pillar parameters and
 | 
			
		||||
| 
						 | 
				
			
			@ -67,47 +73,53 @@ inline Contour3D get_mesh(const Pillar &p, size_t steps)
 | 
			
		|||
    return {};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const Pedestal &p, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const Pedestal &p, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    return halfcone(p.height, p.r_bottom, p.r_top, p.pos, steps);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const Junction &j, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const Junction &j, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    Contour3D mesh = sphere(j.r, make_portion(0, PI), 2 *PI / steps);
 | 
			
		||||
    for(auto& p : mesh.points) p += j.pos;
 | 
			
		||||
    indexed_triangle_set mesh = sphere(j.r, make_portion(0, PI), 2 *PI / steps);
 | 
			
		||||
    Vec3f pos = j.pos.cast<float>();
 | 
			
		||||
    for(auto& p : mesh.vertices) p += pos;
 | 
			
		||||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const Bridge &br, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const Bridge &br, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<double>;
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<float>;
 | 
			
		||||
    Vec3d v = (br.endp - br.startp);
 | 
			
		||||
    Vec3d dir = v.normalized();
 | 
			
		||||
    double d = v.norm();
 | 
			
		||||
 | 
			
		||||
    Contour3D mesh = cylinder(br.r, d, steps);
 | 
			
		||||
    indexed_triangle_set mesh = cylinder(br.r, d, steps);
 | 
			
		||||
 | 
			
		||||
    auto quater = Quaternion::FromTwoVectors(Vec3d{0,0,1}, dir);
 | 
			
		||||
    for(auto& p : mesh.points) p = quater * p + br.startp;
 | 
			
		||||
    auto quater = Quaternion::FromTwoVectors(Vec3f{0.f, 0.f, 1.f},
 | 
			
		||||
                                             dir.cast<float>());
 | 
			
		||||
 | 
			
		||||
    Vec3f startp = br.startp.cast<float>();
 | 
			
		||||
    for(auto& p : mesh.vertices) p = quater * p + startp;
 | 
			
		||||
 | 
			
		||||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline Contour3D get_mesh(const DiffBridge &br, size_t steps)
 | 
			
		||||
inline indexed_triangle_set get_mesh(const DiffBridge &br, size_t steps)
 | 
			
		||||
{
 | 
			
		||||
    double h = br.get_length();
 | 
			
		||||
    Contour3D mesh = halfcone(h, br.r, br.end_r, Vec3d::Zero(), steps);
 | 
			
		||||
    indexed_triangle_set mesh = halfcone(h, br.r, br.end_r, Vec3d::Zero(), steps);
 | 
			
		||||
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<double>;
 | 
			
		||||
    using Quaternion = Eigen::Quaternion<float>;
 | 
			
		||||
 | 
			
		||||
    // We rotate the head to the specified direction. The head's pointing
 | 
			
		||||
    // side is facing upwards so this means that it would hold a support
 | 
			
		||||
    // point with a normal pointing straight down. This is the reason of
 | 
			
		||||
    // the -1 z coordinate
 | 
			
		||||
    auto quatern = Quaternion::FromTwoVectors(Vec3d{0, 0, 1}, br.get_dir());
 | 
			
		||||
    auto quatern = Quaternion::FromTwoVectors(Vec3f{0.f, 0.f, 1.f},
 | 
			
		||||
                                              br.get_dir().cast<float>());
 | 
			
		||||
 | 
			
		||||
    for(auto& p : mesh.points) p = quatern * p + br.startp;
 | 
			
		||||
    Vec3f startp = br.startp.cast<float>();
 | 
			
		||||
    for(auto& p : mesh.vertices) p = quatern * p + startp;
 | 
			
		||||
 | 
			
		||||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -109,7 +109,7 @@ sla::PadConfig make_pad_cfg(const SLAPrintObjectConfig& c)
 | 
			
		|||
    return pcfg;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
bool validate_pad(const TriangleMesh &pad, const sla::PadConfig &pcfg) 
 | 
			
		||||
bool validate_pad(const indexed_triangle_set &pad, const sla::PadConfig &pcfg)
 | 
			
		||||
{
 | 
			
		||||
    // An empty pad can only be created if embed_object mode is enabled
 | 
			
		||||
    // and the pad is not forced everywhere
 | 
			
		||||
| 
						 | 
				
			
			@ -1129,20 +1129,16 @@ TriangleMesh SLAPrintObject::get_mesh(SLAPrintObjectStep step) const
 | 
			
		|||
 | 
			
		||||
const TriangleMesh& SLAPrintObject::support_mesh() const
 | 
			
		||||
{
 | 
			
		||||
    sla::SupportTree::UPtr &stree = m_supportdata->support_tree_ptr;
 | 
			
		||||
    
 | 
			
		||||
    if(m_config.supports_enable.getBool() && m_supportdata && stree)
 | 
			
		||||
        return stree->retrieve_mesh(sla::MeshType::Support);
 | 
			
		||||
    if(m_config.supports_enable.getBool() && m_supportdata)
 | 
			
		||||
        return m_supportdata->tree_mesh;
 | 
			
		||||
    
 | 
			
		||||
    return EMPTY_MESH;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
const TriangleMesh& SLAPrintObject::pad_mesh() const
 | 
			
		||||
{
 | 
			
		||||
    sla::SupportTree::UPtr &stree = m_supportdata->support_tree_ptr;
 | 
			
		||||
    
 | 
			
		||||
    if(m_config.pad_enable.getBool() && m_supportdata && stree)
 | 
			
		||||
        return stree->retrieve_mesh(sla::MeshType::Pad);
 | 
			
		||||
    if(m_config.pad_enable.getBool() && m_supportdata)
 | 
			
		||||
        return m_supportdata->pad_mesh;
 | 
			
		||||
 | 
			
		||||
    return EMPTY_MESH;
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -313,16 +313,27 @@ private:
 | 
			
		|||
    public:
 | 
			
		||||
        sla::SupportTree::UPtr  support_tree_ptr; // the supports
 | 
			
		||||
        std::vector<ExPolygons> support_slices;   // sliced supports
 | 
			
		||||
        TriangleMesh tree_mesh, pad_mesh, full_mesh;
 | 
			
		||||
        
 | 
			
		||||
        inline SupportData(const TriangleMesh &t)
 | 
			
		||||
            : sla::SupportableMesh{t, {}, {}}
 | 
			
		||||
            : sla::SupportableMesh{t.its, {}, {}}
 | 
			
		||||
        {}
 | 
			
		||||
        
 | 
			
		||||
        sla::SupportTree::UPtr &create_support_tree(const sla::JobController &ctl)
 | 
			
		||||
        {
 | 
			
		||||
            support_tree_ptr = sla::SupportTree::create(*this, ctl);
 | 
			
		||||
            tree_mesh = TriangleMesh{support_tree_ptr->retrieve_mesh(sla::MeshType::Support)};
 | 
			
		||||
            return support_tree_ptr;
 | 
			
		||||
        }
 | 
			
		||||
 | 
			
		||||
        void create_pad(const ExPolygons &blueprint, const sla::PadConfig &pcfg)
 | 
			
		||||
        {
 | 
			
		||||
            if (!support_tree_ptr)
 | 
			
		||||
                return;
 | 
			
		||||
 | 
			
		||||
            support_tree_ptr->add_pad(blueprint, pcfg);
 | 
			
		||||
            pad_mesh = TriangleMesh{support_tree_ptr->retrieve_mesh(sla::MeshType::Pad)};
 | 
			
		||||
        }
 | 
			
		||||
    };
 | 
			
		||||
    
 | 
			
		||||
    std::unique_ptr<SupportData> m_supportdata;
 | 
			
		||||
| 
						 | 
				
			
			@ -569,7 +580,7 @@ sla::PadConfig::EmbedObject builtin_pad_cfg(const SLAPrintObjectConfig& c);
 | 
			
		|||
 | 
			
		||||
sla::PadConfig make_pad_cfg(const SLAPrintObjectConfig& c);
 | 
			
		||||
 | 
			
		||||
bool validate_pad(const TriangleMesh &pad, const sla::PadConfig &pcfg);
 | 
			
		||||
bool validate_pad(const indexed_triangle_set &pad, const sla::PadConfig &pcfg);
 | 
			
		||||
 | 
			
		||||
 | 
			
		||||
} // namespace Slic3r
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -360,7 +360,7 @@ void SLAPrint::Steps::drill_holes(SLAPrintObject &po)
 | 
			
		|||
        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());
 | 
			
		||||
        TriangleMesh m{holept.to_mesh()};
 | 
			
		||||
        m.require_shared_vertices();
 | 
			
		||||
 | 
			
		||||
        part_to_drill.indices.clear();
 | 
			
		||||
| 
						 | 
				
			
			@ -667,15 +667,14 @@ void SLAPrint::Steps::generate_pad(SLAPrintObject &po) {
 | 
			
		|||
            // we sometimes call it "builtin pad" is enabled so we will
 | 
			
		||||
            // get a sample from the bottom of the mesh and use it for pad
 | 
			
		||||
            // creation.
 | 
			
		||||
            sla::pad_blueprint(trmesh, bp, float(pad_h),
 | 
			
		||||
            sla::pad_blueprint(trmesh.its, bp, float(pad_h),
 | 
			
		||||
                               float(po.m_config.layer_height.getFloat()),
 | 
			
		||||
                               [this](){ throw_if_canceled(); });
 | 
			
		||||
        }
 | 
			
		||||
 | 
			
		||||
        po.m_supportdata->support_tree_ptr->add_pad(bp, pcfg);
 | 
			
		||||
        auto &pad_mesh = po.m_supportdata->support_tree_ptr->retrieve_mesh(sla::MeshType::Pad);
 | 
			
		||||
        po.m_supportdata->create_pad(bp, pcfg);
 | 
			
		||||
 | 
			
		||||
        if (!validate_pad(pad_mesh, pcfg))
 | 
			
		||||
        if (!validate_pad(po.m_supportdata->support_tree_ptr->retrieve_mesh(sla::MeshType::Pad), pcfg))
 | 
			
		||||
            throw Slic3r::SlicingError(
 | 
			
		||||
                    L("No pad can be generated for this model with the "
 | 
			
		||||
                      "current configuration"));
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -1130,4 +1130,35 @@ TriangleMesh make_sphere(double radius, double fa)
 | 
			
		|||
    return mesh;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const indexed_triangle_set &B)
 | 
			
		||||
{
 | 
			
		||||
    auto N   = int(A.vertices.size());
 | 
			
		||||
    auto N_f = A.indices.size();
 | 
			
		||||
 | 
			
		||||
    A.vertices.insert(A.vertices.end(), B.vertices.begin(), B.vertices.end());
 | 
			
		||||
    A.indices.insert(A.indices.end(), B.indices.begin(), B.indices.end());
 | 
			
		||||
 | 
			
		||||
    for(size_t n = N_f; n < A.indices.size(); n++)
 | 
			
		||||
        A.indices[n] += Vec3i{N, N, N};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const std::vector<Vec3f> &triangles)
 | 
			
		||||
{
 | 
			
		||||
    const size_t offs = A.vertices.size();
 | 
			
		||||
    A.vertices.insert(A.vertices.end(), triangles.begin(), triangles.end());
 | 
			
		||||
    A.indices.reserve(A.indices.size() + A.vertices.size() / 3);
 | 
			
		||||
 | 
			
		||||
    for(int i = int(offs); i < int(A.vertices.size()); i += 3)
 | 
			
		||||
        A.indices.emplace_back(i, i + 1, i + 2);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const Pointf3s &triangles)
 | 
			
		||||
{
 | 
			
		||||
    auto trianglesf = reserve_vector<Vec3f> (triangles.size());
 | 
			
		||||
    for (auto &t : triangles)
 | 
			
		||||
        trianglesf.emplace_back(t.cast<float>());
 | 
			
		||||
 | 
			
		||||
    its_merge(A, trianglesf);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -147,11 +147,48 @@ void its_collect_mesh_projection_points_above(const indexed_triangle_set &its, c
 | 
			
		|||
Polygon its_convex_hull_2d_above(const indexed_triangle_set &its, const Matrix3f &m, const float z);
 | 
			
		||||
Polygon its_convex_hull_2d_above(const indexed_triangle_set &its, const Transform3f &t, const float z);
 | 
			
		||||
 | 
			
		||||
using its_triangle = std::array<stl_vertex, 3>;
 | 
			
		||||
 | 
			
		||||
inline its_triangle its_triangle_vertices(const indexed_triangle_set &its,
 | 
			
		||||
                                          size_t                      face_id)
 | 
			
		||||
{
 | 
			
		||||
    return {its.vertices[its.indices[face_id](0)],
 | 
			
		||||
            its.vertices[its.indices[face_id](1)],
 | 
			
		||||
            its.vertices[its.indices[face_id](2)]};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
inline stl_normal its_unnormalized_normal(const indexed_triangle_set &its,
 | 
			
		||||
                                          size_t                      face_id)
 | 
			
		||||
{
 | 
			
		||||
    its_triangle tri = its_triangle_vertices(its, face_id);
 | 
			
		||||
    return (tri[1] - tri[0]).cross(tri[2] - tri[0]);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const indexed_triangle_set &B);
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const std::vector<Vec3f> &triangles);
 | 
			
		||||
void its_merge(indexed_triangle_set &A, const Pointf3s &triangles);
 | 
			
		||||
 | 
			
		||||
TriangleMesh make_cube(double x, double y, double z);
 | 
			
		||||
TriangleMesh make_cylinder(double r, double h, double fa=(2*PI/360));
 | 
			
		||||
TriangleMesh make_cone(double r, double h, double fa=(2*PI/360));
 | 
			
		||||
TriangleMesh make_sphere(double rho, double fa=(2*PI/360));
 | 
			
		||||
 | 
			
		||||
inline BoundingBoxf3 bounding_box(const TriangleMesh &m) { return m.bounding_box(); }
 | 
			
		||||
inline BoundingBoxf3 bounding_box(const indexed_triangle_set& its)
 | 
			
		||||
{
 | 
			
		||||
    if (its.vertices.empty())
 | 
			
		||||
        return {};
 | 
			
		||||
 | 
			
		||||
    Vec3f bmin = its.vertices.front(), bmax = its.vertices.front();
 | 
			
		||||
 | 
			
		||||
    for (const Vec3f &p : its.vertices) {
 | 
			
		||||
        bmin = p.cwiseMin(bmin);
 | 
			
		||||
        bmax = p.cwiseMax(bmax);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    return {bmin.cast<double>(), bmax.cast<double>()};
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
// Serialization through the Cereal library
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -3,131 +3,157 @@
 | 
			
		|||
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
 | 
			
		||||
class Ring {
 | 
			
		||||
    size_t idx = 0, nextidx = 1, startidx = 0, begin = 0, end = 0;
 | 
			
		||||
//class Ring {
 | 
			
		||||
//    size_t idx = 0, nextidx = 1, startidx = 0, begin = 0, end = 0;
 | 
			
		||||
    
 | 
			
		||||
public:
 | 
			
		||||
    explicit Ring(size_t from, size_t to) : begin(from), end(to) { init(begin); }
 | 
			
		||||
//public:
 | 
			
		||||
//    explicit Ring(size_t from, size_t to) : begin(from), end(to) { init(begin); }
 | 
			
		||||
 | 
			
		||||
    size_t size() const { return end - begin; }
 | 
			
		||||
    std::pair<size_t, size_t> pos() const { return {idx, nextidx}; }
 | 
			
		||||
    bool is_lower() const { return idx < size(); }
 | 
			
		||||
//    size_t size() const { return end - begin; }
 | 
			
		||||
//    std::pair<size_t, size_t> pos() const { return {idx, nextidx}; }
 | 
			
		||||
//    bool is_lower() const { return idx < size(); }
 | 
			
		||||
    
 | 
			
		||||
    void inc()
 | 
			
		||||
    {
 | 
			
		||||
        if (nextidx != startidx) nextidx++;
 | 
			
		||||
        if (nextidx == end) nextidx = begin;
 | 
			
		||||
        idx ++;
 | 
			
		||||
        if (idx == end) idx = begin;
 | 
			
		||||
    }
 | 
			
		||||
//    void inc()
 | 
			
		||||
//    {
 | 
			
		||||
//        if (nextidx != startidx) nextidx++;
 | 
			
		||||
//        if (nextidx == end) nextidx = begin;
 | 
			
		||||
//        idx ++;
 | 
			
		||||
//        if (idx == end) idx = begin;
 | 
			
		||||
//    }
 | 
			
		||||
    
 | 
			
		||||
    void init(size_t pos)
 | 
			
		||||
    {
 | 
			
		||||
        startidx = begin + (pos - begin) % size();
 | 
			
		||||
        idx = startidx;
 | 
			
		||||
        nextidx = begin + (idx + 1 - begin) % size();
 | 
			
		||||
    }
 | 
			
		||||
//    void init(size_t pos)
 | 
			
		||||
//    {
 | 
			
		||||
//        startidx = begin + (pos - begin) % size();
 | 
			
		||||
//        idx = startidx;
 | 
			
		||||
//        nextidx = begin + (idx + 1 - begin) % size();
 | 
			
		||||
//    }
 | 
			
		||||
    
 | 
			
		||||
    bool is_finished() const { return nextidx == idx; }
 | 
			
		||||
};
 | 
			
		||||
//    bool is_finished() const { return nextidx == idx; }
 | 
			
		||||
//};
 | 
			
		||||
 | 
			
		||||
static double sq_dst(const Vec3d &v1, const Vec3d& v2)
 | 
			
		||||
{
 | 
			
		||||
    Vec3d v = v1 - v2;
 | 
			
		||||
    return v.x() * v.x() + v.y() * v.y() /*+ v.z() * v.z()*/;
 | 
			
		||||
}
 | 
			
		||||
//template<class Sc>
 | 
			
		||||
//static Sc sq_dst(const Vec<3, Sc> &v1, const Vec<3, Sc>& v2)
 | 
			
		||||
//{
 | 
			
		||||
//    Vec<3, Sc> v = v1 - v2;
 | 
			
		||||
//    return v.x() * v.x() + v.y() * v.y() /*+ v.z() * v.z()*/;
 | 
			
		||||
//}
 | 
			
		||||
 | 
			
		||||
static double score(const Ring& onring, const Ring &offring,
 | 
			
		||||
                    const std::vector<Vec3d> &pts)
 | 
			
		||||
{
 | 
			
		||||
    double a = sq_dst(pts[onring.pos().first], pts[offring.pos().first]);
 | 
			
		||||
    double b = sq_dst(pts[onring.pos().second], pts[offring.pos().first]);
 | 
			
		||||
    return (std::abs(a) + std::abs(b)) / 2.;
 | 
			
		||||
}
 | 
			
		||||
//template<class Sc>
 | 
			
		||||
//static Sc trscore(const Ring &                   onring,
 | 
			
		||||
//                  const Ring &                   offring,
 | 
			
		||||
//                  const std::vector<Vec<3, Sc>> &pts)
 | 
			
		||||
//{
 | 
			
		||||
//    Sc a = sq_dst(pts[onring.pos().first], pts[offring.pos().first]);
 | 
			
		||||
//    Sc b = sq_dst(pts[onring.pos().second], pts[offring.pos().first]);
 | 
			
		||||
//    return (std::abs(a) + std::abs(b)) / 2.;
 | 
			
		||||
//}
 | 
			
		||||
 | 
			
		||||
class Triangulator {
 | 
			
		||||
    const std::vector<Vec3d> *pts;
 | 
			
		||||
    Ring *onring, *offring;
 | 
			
		||||
//template<class Sc>
 | 
			
		||||
//class Triangulator {
 | 
			
		||||
//    const std::vector<Vec<3, Sc>> *pts;
 | 
			
		||||
//    Ring *onring, *offring;
 | 
			
		||||
    
 | 
			
		||||
    double calc_score() const
 | 
			
		||||
    {
 | 
			
		||||
        return Slic3r::score(*onring, *offring, *pts);
 | 
			
		||||
    }
 | 
			
		||||
//    double calc_score() const
 | 
			
		||||
//    {
 | 
			
		||||
//        return trscore(*onring, *offring, *pts);
 | 
			
		||||
//    }
 | 
			
		||||
    
 | 
			
		||||
    void synchronize_rings()
 | 
			
		||||
    {
 | 
			
		||||
        Ring lring = *offring;
 | 
			
		||||
        auto minsc = Slic3r::score(*onring, lring, *pts);
 | 
			
		||||
        size_t imin = lring.pos().first;
 | 
			
		||||
//    void synchronize_rings()
 | 
			
		||||
//    {
 | 
			
		||||
//        Ring lring = *offring;
 | 
			
		||||
//        auto minsc = trscore(*onring, lring, *pts);
 | 
			
		||||
//        size_t imin = lring.pos().first;
 | 
			
		||||
        
 | 
			
		||||
        lring.inc();
 | 
			
		||||
//        lring.inc();
 | 
			
		||||
        
 | 
			
		||||
        while(!lring.is_finished()) {
 | 
			
		||||
            double score = Slic3r::score(*onring, lring, *pts);
 | 
			
		||||
            if (score < minsc) { minsc = score; imin = lring.pos().first; }
 | 
			
		||||
            lring.inc();
 | 
			
		||||
        }
 | 
			
		||||
//        while(!lring.is_finished()) {
 | 
			
		||||
//            double score = trscore(*onring, lring, *pts);
 | 
			
		||||
//            if (score < minsc) { minsc = score; imin = lring.pos().first; }
 | 
			
		||||
//            lring.inc();
 | 
			
		||||
//        }
 | 
			
		||||
        
 | 
			
		||||
        offring->init(imin);
 | 
			
		||||
    }
 | 
			
		||||
//        offring->init(imin);
 | 
			
		||||
//    }
 | 
			
		||||
    
 | 
			
		||||
    void emplace_indices(std::vector<Vec3i> &indices)
 | 
			
		||||
    {
 | 
			
		||||
        Vec3i tr{int(onring->pos().first), int(onring->pos().second),
 | 
			
		||||
                 int(offring->pos().first)};
 | 
			
		||||
        if (onring->is_lower()) std::swap(tr(0), tr(1));
 | 
			
		||||
        indices.emplace_back(tr);
 | 
			
		||||
    }
 | 
			
		||||
//    void emplace_indices(std::vector<Vec3i> &indices)
 | 
			
		||||
//    {
 | 
			
		||||
//        Vec3i tr{int(onring->pos().first), int(onring->pos().second),
 | 
			
		||||
//                 int(offring->pos().first)};
 | 
			
		||||
//        if (onring->is_lower()) std::swap(tr(0), tr(1));
 | 
			
		||||
//        indices.emplace_back(tr);
 | 
			
		||||
//    }
 | 
			
		||||
    
 | 
			
		||||
public:
 | 
			
		||||
    void run(std::vector<Vec3i> &indices)
 | 
			
		||||
    {   
 | 
			
		||||
        synchronize_rings();
 | 
			
		||||
//public:
 | 
			
		||||
//    void run(std::vector<Vec3i> &indices)
 | 
			
		||||
//    {
 | 
			
		||||
//        synchronize_rings();
 | 
			
		||||
        
 | 
			
		||||
        double score = 0, prev_score = 0;        
 | 
			
		||||
        while (!onring->is_finished() || !offring->is_finished()) {
 | 
			
		||||
            prev_score = score;
 | 
			
		||||
            if (onring->is_finished() || (score = calc_score()) > prev_score) {
 | 
			
		||||
                std::swap(onring, offring);
 | 
			
		||||
            } else {
 | 
			
		||||
                emplace_indices(indices);
 | 
			
		||||
                onring->inc();
 | 
			
		||||
            }
 | 
			
		||||
        }
 | 
			
		||||
    }
 | 
			
		||||
//        double score = 0, prev_score = 0;
 | 
			
		||||
//        while (!onring->is_finished() || !offring->is_finished()) {
 | 
			
		||||
//            prev_score = score;
 | 
			
		||||
//            if (onring->is_finished() || (score = calc_score()) > prev_score) {
 | 
			
		||||
//                std::swap(onring, offring);
 | 
			
		||||
//            } else {
 | 
			
		||||
//                emplace_indices(indices);
 | 
			
		||||
//                onring->inc();
 | 
			
		||||
//            }
 | 
			
		||||
//        }
 | 
			
		||||
//    }
 | 
			
		||||
 | 
			
		||||
    explicit Triangulator(const std::vector<Vec3d> *points,
 | 
			
		||||
                          Ring &                    lower,
 | 
			
		||||
                          Ring &                    upper)
 | 
			
		||||
        : pts{points}, onring{&upper}, offring{&lower}
 | 
			
		||||
    {}
 | 
			
		||||
};
 | 
			
		||||
//    explicit Triangulator(const std::vector<Vec<3, Sc>> *points,
 | 
			
		||||
//                          Ring &                    lower,
 | 
			
		||||
//                          Ring &                    upper)
 | 
			
		||||
//        : pts{points}, onring{&upper}, offring{&lower}
 | 
			
		||||
//    {}
 | 
			
		||||
//};
 | 
			
		||||
 | 
			
		||||
Wall triangulate_wall(
 | 
			
		||||
    const Polygon &          lower,
 | 
			
		||||
    const Polygon &          upper,
 | 
			
		||||
    double                   lower_z_mm,
 | 
			
		||||
    double                   upper_z_mm)
 | 
			
		||||
{
 | 
			
		||||
    if (upper.points.size() < 3 || lower.points.size() < 3) return {};
 | 
			
		||||
    
 | 
			
		||||
    Wall wall;
 | 
			
		||||
    auto &pts = wall.first;
 | 
			
		||||
    auto &ind = wall.second;
 | 
			
		||||
//template<class Sc, class I>
 | 
			
		||||
//void triangulate_wall(std::vector<Vec<3, Sc>> &pts,
 | 
			
		||||
//                      std::vector<Vec<3, I>> & ind,
 | 
			
		||||
//                      const Polygon &          lower,
 | 
			
		||||
//                      const Polygon &          upper,
 | 
			
		||||
//                      double                   lower_z_mm,
 | 
			
		||||
//                      double                   upper_z_mm)
 | 
			
		||||
//{
 | 
			
		||||
//    if (upper.points.size() < 3 || lower.points.size() < 3) return;
 | 
			
		||||
 | 
			
		||||
    pts.reserve(lower.points.size() + upper.points.size());
 | 
			
		||||
    for (auto &p : lower.points)
 | 
			
		||||
        wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
 | 
			
		||||
    for (auto &p : upper.points)
 | 
			
		||||
        wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
 | 
			
		||||
//    pts.reserve(lower.points.size() + upper.points.size());
 | 
			
		||||
//    for (auto &p : lower.points)
 | 
			
		||||
//        pts.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
 | 
			
		||||
//    for (auto &p : upper.points)
 | 
			
		||||
//        pts.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
 | 
			
		||||
 | 
			
		||||
//    ind.reserve(2 * (lower.size() + upper.size()));
 | 
			
		||||
 | 
			
		||||
//    Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
 | 
			
		||||
//    Triangulator t{&pts, lring, uring};
 | 
			
		||||
//    t.run(ind);
 | 
			
		||||
//}
 | 
			
		||||
 | 
			
		||||
//Wall triangulate_wall(const Polygon &lower,
 | 
			
		||||
//                      const Polygon &upper,
 | 
			
		||||
//                      double         lower_z_mm,
 | 
			
		||||
//                      double         upper_z_mm)
 | 
			
		||||
//{
 | 
			
		||||
//    if (upper.points.size() < 3 || lower.points.size() < 3) return {};
 | 
			
		||||
    
 | 
			
		||||
    ind.reserve(2 * (lower.size() + upper.size()));
 | 
			
		||||
//    Wall wall;
 | 
			
		||||
//    auto &pts = wall.first;
 | 
			
		||||
//    auto &ind = wall.second;
 | 
			
		||||
 | 
			
		||||
//    pts.reserve(lower.points.size() + upper.points.size());
 | 
			
		||||
//    for (auto &p : lower.points)
 | 
			
		||||
//        wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
 | 
			
		||||
//    for (auto &p : upper.points)
 | 
			
		||||
//        wall.first.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
 | 
			
		||||
    
 | 
			
		||||
    Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
 | 
			
		||||
    Triangulator t{&pts, lring, uring};
 | 
			
		||||
    t.run(ind);
 | 
			
		||||
//    ind.reserve(2 * (lower.size() + upper.size()));
 | 
			
		||||
    
 | 
			
		||||
    return wall;
 | 
			
		||||
}
 | 
			
		||||
//    Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
 | 
			
		||||
//    Triangulator t{&pts, lring, uring};
 | 
			
		||||
//    t.run(ind);
 | 
			
		||||
    
 | 
			
		||||
//    return wall;
 | 
			
		||||
//}
 | 
			
		||||
 | 
			
		||||
} // namespace Slic3r
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -5,13 +5,148 @@
 | 
			
		|||
 | 
			
		||||
namespace Slic3r {
 | 
			
		||||
 | 
			
		||||
using Wall = std::pair<std::vector<Vec3d>, std::vector<Vec3i>>;
 | 
			
		||||
namespace trianglulate_wall_detail {
 | 
			
		||||
 | 
			
		||||
Wall triangulate_wall(
 | 
			
		||||
    const Polygon &       lower,
 | 
			
		||||
    const Polygon &       upper,
 | 
			
		||||
    double                lower_z_mm,
 | 
			
		||||
    double                upper_z_mm);
 | 
			
		||||
class Ring {
 | 
			
		||||
    size_t idx = 0, nextidx = 1, startidx = 0, begin = 0, end = 0;
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
    explicit Ring(size_t from, size_t to) : begin(from), end(to) { init(begin); }
 | 
			
		||||
 | 
			
		||||
    size_t size() const { return end - begin; }
 | 
			
		||||
    std::pair<size_t, size_t> pos() const { return {idx, nextidx}; }
 | 
			
		||||
    bool is_lower() const { return idx < size(); }
 | 
			
		||||
 | 
			
		||||
    void inc()
 | 
			
		||||
    {
 | 
			
		||||
        if (nextidx != startidx) nextidx++;
 | 
			
		||||
        if (nextidx == end) nextidx = begin;
 | 
			
		||||
        idx ++;
 | 
			
		||||
        if (idx == end) idx = begin;
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    void init(size_t pos)
 | 
			
		||||
    {
 | 
			
		||||
        startidx = begin + (pos - begin) % size();
 | 
			
		||||
        idx = startidx;
 | 
			
		||||
        nextidx = begin + (idx + 1 - begin) % size();
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    bool is_finished() const { return nextidx == idx; }
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
template<class Sc>
 | 
			
		||||
static Sc sq_dst(const Vec<3, Sc> &v1, const Vec<3, Sc>& v2)
 | 
			
		||||
{
 | 
			
		||||
    Vec<3, Sc> v = v1 - v2;
 | 
			
		||||
    return v.x() * v.x() + v.y() * v.y() /*+ v.z() * v.z()*/;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
template<class Sc>
 | 
			
		||||
static Sc trscore(const Ring &                   onring,
 | 
			
		||||
                  const Ring &                   offring,
 | 
			
		||||
                  const std::vector<Vec<3, Sc>> &pts)
 | 
			
		||||
{
 | 
			
		||||
    Sc a = sq_dst(pts[onring.pos().first], pts[offring.pos().first]);
 | 
			
		||||
    Sc b = sq_dst(pts[onring.pos().second], pts[offring.pos().first]);
 | 
			
		||||
    return (std::abs(a) + std::abs(b)) / 2.;
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
template<class Sc>
 | 
			
		||||
class Triangulator {
 | 
			
		||||
    const std::vector<Vec<3, Sc>> *pts;
 | 
			
		||||
    Ring *onring, *offring;
 | 
			
		||||
 | 
			
		||||
    double calc_score() const
 | 
			
		||||
    {
 | 
			
		||||
        return trscore(*onring, *offring, *pts);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    void synchronize_rings()
 | 
			
		||||
    {
 | 
			
		||||
        Ring lring = *offring;
 | 
			
		||||
        auto minsc = trscore(*onring, lring, *pts);
 | 
			
		||||
        size_t imin = lring.pos().first;
 | 
			
		||||
 | 
			
		||||
        lring.inc();
 | 
			
		||||
 | 
			
		||||
        while(!lring.is_finished()) {
 | 
			
		||||
            double score = trscore(*onring, lring, *pts);
 | 
			
		||||
            if (score < minsc) { minsc = score; imin = lring.pos().first; }
 | 
			
		||||
            lring.inc();
 | 
			
		||||
        }
 | 
			
		||||
 | 
			
		||||
        offring->init(imin);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    void emplace_indices(std::vector<Vec3i> &indices)
 | 
			
		||||
    {
 | 
			
		||||
        Vec3i tr{int(onring->pos().first), int(onring->pos().second),
 | 
			
		||||
                 int(offring->pos().first)};
 | 
			
		||||
        if (onring->is_lower()) std::swap(tr(0), tr(1));
 | 
			
		||||
        indices.emplace_back(tr);
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
public:
 | 
			
		||||
    void run(std::vector<Vec3i> &indices)
 | 
			
		||||
    {
 | 
			
		||||
        synchronize_rings();
 | 
			
		||||
 | 
			
		||||
        double score = 0, prev_score = 0;
 | 
			
		||||
        while (!onring->is_finished() || !offring->is_finished()) {
 | 
			
		||||
            prev_score = score;
 | 
			
		||||
            if (onring->is_finished() || (score = calc_score()) > prev_score) {
 | 
			
		||||
                std::swap(onring, offring);
 | 
			
		||||
            } else {
 | 
			
		||||
                emplace_indices(indices);
 | 
			
		||||
                onring->inc();
 | 
			
		||||
            }
 | 
			
		||||
        }
 | 
			
		||||
    }
 | 
			
		||||
 | 
			
		||||
    explicit Triangulator(const std::vector<Vec<3, Sc>> *points,
 | 
			
		||||
                          Ring &                    lower,
 | 
			
		||||
                          Ring &                    upper)
 | 
			
		||||
        : pts{points}, onring{&upper}, offring{&lower}
 | 
			
		||||
    {}
 | 
			
		||||
};
 | 
			
		||||
 | 
			
		||||
} // namespace trianglulate_wall_detail
 | 
			
		||||
 | 
			
		||||
template<class Sc, class I>
 | 
			
		||||
void triangulate_wall(std::vector<Vec<3, Sc>> &pts,
 | 
			
		||||
                      std::vector<Vec<3, I>> & ind,
 | 
			
		||||
                      const Polygon &          lower,
 | 
			
		||||
                      const Polygon &          upper,
 | 
			
		||||
                      double                   lower_z_mm,
 | 
			
		||||
                      double                   upper_z_mm)
 | 
			
		||||
{
 | 
			
		||||
    using namespace trianglulate_wall_detail;
 | 
			
		||||
 | 
			
		||||
    if (upper.points.size() < 3 || lower.points.size() < 3) return;
 | 
			
		||||
 | 
			
		||||
    pts.reserve(lower.points.size() + upper.points.size());
 | 
			
		||||
    for (auto &p : lower.points)
 | 
			
		||||
        pts.emplace_back(unscaled(p.x()), unscaled(p.y()), lower_z_mm);
 | 
			
		||||
    for (auto &p : upper.points)
 | 
			
		||||
        pts.emplace_back(unscaled(p.x()), unscaled(p.y()), upper_z_mm);
 | 
			
		||||
 | 
			
		||||
    ind.reserve(2 * (lower.size() + upper.size()));
 | 
			
		||||
 | 
			
		||||
    Ring lring{0, lower.points.size()}, uring{lower.points.size(), pts.size()};
 | 
			
		||||
    Triangulator t{&pts, lring, uring};
 | 
			
		||||
    t.run(ind);
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
//using Wall = std::pair<std::vector<Vec3d>, std::vector<Vec3i>>;
 | 
			
		||||
 | 
			
		||||
//Wall triangulate_wall(
 | 
			
		||||
//    const Polygon &       lower,
 | 
			
		||||
//    const Polygon &       upper,
 | 
			
		||||
//    double                lower_z_mm,
 | 
			
		||||
//    double                upper_z_mm);
 | 
			
		||||
//}
 | 
			
		||||
 | 
			
		||||
} // namespace Slic3r
 | 
			
		||||
 | 
			
		||||
#endif // TRIANGULATEWALL_HPP
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -236,10 +236,10 @@ TEST_CASE("Triangle mesh conversions should be correct", "[SLAConversions]")
 | 
			
		|||
TEST_CASE("halfcone test", "[halfcone]") {
 | 
			
		||||
    sla::DiffBridge br{Vec3d{1., 1., 1.}, Vec3d{10., 10., 10.}, 0.25, 0.5};
 | 
			
		||||
 | 
			
		||||
    TriangleMesh m = sla::to_triangle_mesh(sla::get_mesh(br, 45));
 | 
			
		||||
    indexed_triangle_set m = sla::get_mesh(br, 45);
 | 
			
		||||
 | 
			
		||||
    m.require_shared_vertices();
 | 
			
		||||
    m.WriteOBJFile("Halfcone.obj");
 | 
			
		||||
    its_merge_vertices(m);
 | 
			
		||||
    its_write_obj(m, "Halfcone.obj");
 | 
			
		||||
}
 | 
			
		||||
 | 
			
		||||
TEST_CASE("Test concurrency")
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
| 
						 | 
				
			
			@ -69,9 +69,10 @@ void export_failed_case(const std::vector<ExPolygons> &support_slices, const Sup
 | 
			
		|||
            svg.Close();
 | 
			
		||||
        }
 | 
			
		||||
    }
 | 
			
		||||
    
 | 
			
		||||
    TriangleMesh m;
 | 
			
		||||
    byproducts.supporttree.retrieve_full_mesh(m);
 | 
			
		||||
 | 
			
		||||
    indexed_triangle_set its;
 | 
			
		||||
    byproducts.supporttree.retrieve_full_mesh(its);
 | 
			
		||||
    TriangleMesh m{its};
 | 
			
		||||
    m.merge(byproducts.input_mesh);
 | 
			
		||||
    m.repair();
 | 
			
		||||
    m.require_shared_vertices();
 | 
			
		||||
| 
						 | 
				
			
			@ -151,7 +152,7 @@ void test_supports(const std::string          &obj_filename,
 | 
			
		|||
    
 | 
			
		||||
    check_support_tree_integrity(treebuilder, supportcfg);
 | 
			
		||||
    
 | 
			
		||||
    const TriangleMesh &output_mesh = treebuilder.retrieve_mesh();
 | 
			
		||||
    TriangleMesh output_mesh{treebuilder.retrieve_mesh(sla::MeshType::Support)};
 | 
			
		||||
    
 | 
			
		||||
    check_validity(output_mesh, validityflags);
 | 
			
		||||
    
 | 
			
		||||
| 
						 | 
				
			
			@ -228,14 +229,16 @@ void test_pad(const std::string &obj_filename, const sla::PadConfig &padcfg, Pad
 | 
			
		|||
    REQUIRE_FALSE(mesh.empty());
 | 
			
		||||
    
 | 
			
		||||
    // Create pad skeleton only from the model
 | 
			
		||||
    Slic3r::sla::pad_blueprint(mesh, out.model_contours);
 | 
			
		||||
    Slic3r::sla::pad_blueprint(mesh.its, out.model_contours);
 | 
			
		||||
    
 | 
			
		||||
    test_concave_hull(out.model_contours);
 | 
			
		||||
    
 | 
			
		||||
    REQUIRE_FALSE(out.model_contours.empty());
 | 
			
		||||
    
 | 
			
		||||
    // Create the pad geometry for the model contours only
 | 
			
		||||
    Slic3r::sla::create_pad({}, out.model_contours, out.mesh, padcfg);
 | 
			
		||||
    indexed_triangle_set out_its;
 | 
			
		||||
    Slic3r::sla::create_pad({}, out.model_contours, out_its, padcfg);
 | 
			
		||||
    out.mesh = TriangleMesh{out_its};
 | 
			
		||||
    
 | 
			
		||||
    check_validity(out.mesh);
 | 
			
		||||
    
 | 
			
		||||
| 
						 | 
				
			
			
 | 
			
		|||
		Loading…
	
	Add table
		Add a link
		
	
		Reference in a new issue