Merge branch 'tm_openvdb_integration' into lm_tm_hollowing

* Refactor file names in SLA dir
This commit is contained in:
tamasmeszaros 2019-11-11 11:41:14 +01:00
commit c22423a219
55 changed files with 1644 additions and 592 deletions

View File

@ -0,0 +1,25 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.0.3, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.0" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 16 16" enable-background="new 0 0 16 16" xml:space="preserve">
<g id="support">
<polygon fill="none" stroke="#808080" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" points="8,1
2.31,4.79 2.31,8.57 2.31,8.79 2.31,10.47 8,14.25 13.69,10.47 13.69,8.79 13.69,8.57 13.69,4.79 "/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="12.69" y1="15" x2="12.69" y2="12.44"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="13.87" y1="15" x2="13.87" y2="11.64"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="2.13" y1="15" x2="2.13" y2="11.64"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="3.33" y1="15" x2="3.33" y2="12.44"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="4.51" y1="15" x2="4.51" y2="13.22"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="5.66" y1="15" x2="5.66" y2="14"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="10.34" y1="15" x2="10.34" y2="14"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="11.5" y1="15" x2="11.5" y2="13.22"/>
</g>
</svg>

After

Width:  |  Height:  |  Size: 1.7 KiB

View File

@ -0,0 +1,25 @@
<?xml version="1.0" encoding="utf-8"?>
<!-- Generator: Adobe Illustrator 23.0.3, SVG Export Plug-In . SVG Version: 6.00 Build 0) -->
<svg version="1.0" id="Layer_1" xmlns="http://www.w3.org/2000/svg" xmlns:xlink="http://www.w3.org/1999/xlink" x="0px" y="0px"
viewBox="0 0 16 16" enable-background="new 0 0 16 16" xml:space="preserve">
<g id="support">
<polygon fill="none" stroke="#808080" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" points="8,1
2.31,4.79 2.31,8.57 2.31,8.79 2.31,10.47 8,14.25 13.69,10.47 13.69,8.79 13.69,8.57 13.69,4.79 "/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="12.69" y1="15" x2="12.69" y2="12.44"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="13.87" y1="15" x2="13.87" y2="11.64"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="2.13" y1="15" x2="2.13" y2="11.64"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="3.33" y1="15" x2="3.33" y2="12.44"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="4.51" y1="15" x2="4.51" y2="13.22"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="5.66" y1="15" x2="5.66" y2="14"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="10.34" y1="15" x2="10.34" y2="14"/>
<line fill="none" stroke="#ED6B21" stroke-linecap="round" stroke-linejoin="round" stroke-miterlimit="10" x1="11.5" y1="15" x2="11.5" y2="13.22"/>
</g>
</svg>

After

Width:  |  Height:  |  Size: 1.7 KiB

View File

@ -151,8 +151,6 @@ add_library(libslic3r STATIC
ShortestPath.hpp
SLAPrint.cpp
SLAPrint.hpp
SLA/SLAAutoSupports.hpp
SLA/SLAAutoSupports.cpp
Slicing.cpp
Slicing.hpp
SlicingAdaptive.cpp
@ -182,28 +180,38 @@ add_library(libslic3r STATIC
miniz_extension.hpp
miniz_extension.cpp
${OpenVDBUtils_SOURCES}
SLA/SLACommon.hpp
SLA/SLACommon.cpp
SLA/SLAPad.hpp
SLA/SLAPad.cpp
SLA/SLASupportTreeBuilder.hpp
SLA/SLASupportTreeBuildsteps.hpp
SLA/SLASupportTreeBuildsteps.cpp
SLA/SLASupportTreeBuilder.cpp
SLA/SLAConcurrency.hpp
SLA/SLASupportTree.hpp
SLA/SLASupportTree.cpp
SLA/SLASupportTreeIGL.cpp
SLA/SLARotfinder.hpp
SLA/SLARotfinder.cpp
SLA/SLABoostAdapter.hpp
SLA/SLASpatIndex.hpp
SLA/SLARaster.hpp
SLA/SLARaster.cpp
SLA/SLARasterWriter.hpp
SLA/SLARasterWriter.cpp
SLA/Common.hpp
SLA/Common.cpp
SLA/Pad.hpp
SLA/Pad.cpp
SLA/SupportTreeBuilder.hpp
SLA/SupportTreeBuildsteps.hpp
SLA/SupportTreeBuildsteps.cpp
SLA/SupportTreeBuilder.cpp
SLA/Concurrency.hpp
SLA/SupportTree.hpp
SLA/SupportTree.cpp
# SLA/SupportTreeIGL.cpp
SLA/Rotfinder.hpp
SLA/Rotfinder.cpp
SLA/BoostAdapter.hpp
SLA/SpatIndex.hpp
SLA/Raster.hpp
SLA/Raster.cpp
SLA/RasterWriter.hpp
SLA/RasterWriter.cpp
SLA/ConcaveHull.hpp
SLA/ConcaveHull.cpp
SLA/Hollowing.hpp
SLA/Hollowing.cpp
SLA/JobController.hpp
SLA/SupportPoint.hpp
SLA/SupportPointGenerator.hpp
SLA/SupportPointGenerator.cpp
SLA/Contour3D.hpp
SLA/Contour3D.cpp
SLA/EigenMesh3D.hpp
SLA/Clustering.hpp
)
encoding_check(libslic3r)

View File

@ -1146,7 +1146,8 @@ ModelObjectPtrs ModelObject::cut(size_t instance, coordf_t z, bool keep_upper, b
if (keep_upper) { upper->add_volume(*volume); }
if (keep_lower) { lower->add_volume(*volume); }
}
else {
else if (! volume->mesh().empty()) {
TriangleMesh upper_mesh, lower_mesh;
// Transform the mesh by the combined transformation matrix.
@ -1154,7 +1155,9 @@ ModelObjectPtrs ModelObject::cut(size_t instance, coordf_t z, bool keep_upper, b
TriangleMesh mesh(volume->mesh());
mesh.transform(instance_matrix * volume_matrix, true);
volume->reset_mesh();
mesh.require_shared_vertices();
// Perform cut
TriangleMeshSlicer tms(&mesh);
tms.cut(float(z), &upper_mesh, &lower_mesh);

View File

@ -8,7 +8,8 @@
#include "Point.hpp"
#include "PrintConfig.hpp"
#include "Slicing.hpp"
#include "SLA/SLACommon.hpp"
#include "SLA/SupportPoint.hpp"
#include "SLA/Hollowing.hpp"
#include "TriangleMesh.hpp"
#include "Arrange.hpp"

View File

@ -2,6 +2,9 @@
#include "OpenVDBUtils.hpp"
#include <openvdb/tools/MeshToVolume.h>
#include <openvdb/tools/VolumeToMesh.h>
#include <openvdb/tools/LevelSetRebuild.h>
//#include "MTUtils.hpp"
namespace Slic3r {
@ -50,7 +53,12 @@ void Contour3DDataAdapter::getIndexSpacePoint(size_t n,
pos = {p.x(), p.y(), p.z()};
}
openvdb::FloatGrid::Ptr meshToVolume(const TriangleMesh &mesh,
// TODO: Do I need to call initialize? Seems to work without it as well but the
// docs say it should be called ones. It does a mutex lock-unlock sequence all
// even if was called previously.
openvdb::FloatGrid::Ptr mesh_to_grid(const TriangleMesh &mesh,
const openvdb::math::Transform &tr,
float exteriorBandWidth,
float interiorBandWidth,
@ -62,11 +70,7 @@ openvdb::FloatGrid::Ptr meshToVolume(const TriangleMesh &mesh,
interiorBandWidth, flags);
}
// TODO: Do I need to call initialize? Seems to work without it as well but the
// docs say it should be called ones. It does a mutex lock-unlock sequence all
// even if was called previously.
openvdb::FloatGrid::Ptr meshToVolume(const sla::Contour3D & mesh,
openvdb::FloatGrid::Ptr mesh_to_grid(const sla::Contour3D &mesh,
const openvdb::math::Transform &tr,
float exteriorBandWidth,
float interiorBandWidth,
@ -78,16 +82,11 @@ openvdb::FloatGrid::Ptr meshToVolume(const sla::Contour3D & mesh,
flags);
}
inline Vec3f to_vec3f(const openvdb::Vec3s &v) { return Vec3f{v.x(), v.y(), v.z()}; }
inline Vec3d to_vec3d(const openvdb::Vec3s &v) { return to_vec3f(v).cast<double>(); }
inline Vec3i to_vec3i(const openvdb::Vec3I &v) { return Vec3i{int(v[0]), int(v[1]), int(v[2])}; }
inline Vec4i to_vec4i(const openvdb::Vec4I &v) { return Vec4i{int(v[0]), int(v[1]), int(v[2]), int(v[3])}; }
template<class Grid>
sla::Contour3D _volumeToMesh(const Grid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
{
openvdb::initialize();
@ -102,20 +101,35 @@ sla::Contour3D _volumeToMesh(const Grid &grid,
ret.points.reserve(points.size());
ret.faces3.reserve(triangles.size());
ret.faces4.reserve(quads.size());
for (auto &v : points) ret.points.emplace_back(to_vec3d(v));
for (auto &v : triangles) ret.faces3.emplace_back(to_vec3i(v));
for (auto &v : quads) ret.faces4.emplace_back(to_vec4i(v));
return ret;
}
sla::Contour3D volumeToMesh(const openvdb::FloatGrid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
TriangleMesh grid_to_mesh(const openvdb::FloatGrid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
{
return _volumeToMesh(grid, isovalue, adaptivity, relaxDisorientedTriangles);
return to_triangle_mesh(
_volumeToMesh(grid, isovalue, adaptivity, relaxDisorientedTriangles));
}
sla::Contour3D grid_to_contour3d(const openvdb::FloatGrid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
{
return _volumeToMesh(grid, isovalue, adaptivity,
relaxDisorientedTriangles);
}
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid, double iso, double er, double ir)
{
return openvdb::tools::levelSetRebuild(grid, float(iso), float(er), float(ir));
}
} // namespace Slic3r

View File

@ -2,27 +2,43 @@
#define OPENVDBUTILS_HPP
#include <libslic3r/TriangleMesh.hpp>
#include <libslic3r/SLA/SLACommon.hpp>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
#include <openvdb/openvdb.h>
namespace Slic3r {
openvdb::FloatGrid::Ptr meshToVolume(const TriangleMesh & mesh,
inline Vec3f to_vec3f(const openvdb::Vec3s &v) { return Vec3f{v.x(), v.y(), v.z()}; }
inline Vec3d to_vec3d(const openvdb::Vec3s &v) { return to_vec3f(v).cast<double>(); }
inline Vec3i to_vec3i(const openvdb::Vec3I &v) { return Vec3i{int(v[0]), int(v[1]), int(v[2])}; }
inline Vec4i to_vec4i(const openvdb::Vec4I &v) { return Vec4i{int(v[0]), int(v[1]), int(v[2]), int(v[3])}; }
openvdb::FloatGrid::Ptr mesh_to_grid(const TriangleMesh & mesh,
const openvdb::math::Transform &tr = {},
float exteriorBandWidth = 3.0f,
float interiorBandWidth = 3.0f,
int flags = 0);
openvdb::FloatGrid::Ptr meshToVolume(const sla::Contour3D & mesh,
openvdb::FloatGrid::Ptr mesh_to_grid(const sla::Contour3D & mesh,
const openvdb::math::Transform &tr = {},
float exteriorBandWidth = 3.0f,
float interiorBandWidth = 3.0f,
int flags = 0);
sla::Contour3D volumeToMesh(const openvdb::FloatGrid &grid,
double isovalue = 0.0,
double adaptivity = 0.0,
bool relaxDisorientedTriangles = true);
sla::Contour3D grid_to_contour3d(const openvdb::FloatGrid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles = true);
TriangleMesh grid_to_mesh(const openvdb::FloatGrid &grid,
double isovalue = 0.0,
double adaptivity = 0.0,
bool relaxDisorientedTriangles = true);
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid,
double iso,
double ext_range = 3.,
double int_range = 3.);
} // namespace Slic3r

View File

@ -2830,6 +2830,39 @@ void PrintConfigDef::init_sla_params()
def->min = 0;
def->mode = comExpert;
def->set_default_value(new ConfigOptionFloat(0.3));
def = this->add("hollowing_enable", coBool);
def->label = L("Enable hollowing");
def->category = L("Hollowing");
def->tooltip = L("Hollow out a model to have an empty interior");
def->mode = comSimple;
def->set_default_value(new ConfigOptionBool(false));
def = this->add("hollowing_min_thickness", coFloat);
def->label = L("Hollowing thickness");
def->category = L("Hollowing");
def->tooltip = L("Minimum wall thickness of a hollowed model.");
def->sidetext = L("mm");
def->min = 1;
def->mode = comSimple;
def->set_default_value(new ConfigOptionFloat(4));
def = this->add("hollowing_quality", coFloat);
def->label = L("Hollowing accuracy");
def->category = L("Hollowing");
def->tooltip = L("Performance vs accuracy of calculation. Lower values may produce unwanted artifacts.");
def->min = 0;
def->max = 1;
def->mode = comExpert;
def->set_default_value(new ConfigOptionFloat(0.5));
def = this->add("hollowing_closing_distance", coFloat);
def->label = L("Hollowing closing distance");
def->category = L("Hollowing");
def->tooltip = L("");
def->min = 0;
def->mode = comExpert;
def->set_default_value(new ConfigOptionFloat(2.0));
}
void PrintConfigDef::handle_legacy(t_config_option_key &opt_key, std::string &value)

View File

@ -1014,7 +1014,7 @@ public:
ConfigOptionFloat support_base_height /*= 1.0*/;
// The minimum distance of the pillar base from the model in mm.
ConfigOptionFloat support_base_safety_distance; /*= 1.0*/;
ConfigOptionFloat support_base_safety_distance; /*= 1.0*/
// The default angle for connecting support sticks and junctions.
ConfigOptionFloat support_critical_angle /*= 45*/;
@ -1059,7 +1059,7 @@ public:
// /////////////////////////////////////////////////////////////////////////
// Zero elevation mode parameters:
// - The object pad will be derived from the the model geometry.
// - The object pad will be derived from the model geometry.
// - There will be a gap between the object pad and the generated pad
// according to the support_base_safety_distance parameter.
// - The two pads will be connected with tiny connector sticks
@ -1081,6 +1081,28 @@ public:
// How much should the tiny connectors penetrate into the model body
ConfigOptionFloat pad_object_connector_penetration;
// /////////////////////////////////////////////////////////////////////////
// Model hollowing parameters:
// - Models can be hollowed out as part of the SLA print process
// - Thickness of the hollowed model walls can be adjusted
// -
// - Additional holes will be drilled into the hollow model to allow for
// - resin removal.
// /////////////////////////////////////////////////////////////////////////
ConfigOptionBool hollowing_enable;
// The minimum thickness of the model walls to maintain. Note that the
// resulting walls may be thicker due to smoothing out fine cavities where
// resin could stuck.
ConfigOptionFloat hollowing_min_thickness;
// Indirectly controls the voxel size (resolution) used by openvdb
ConfigOptionFloat hollowing_quality;
// Indirectly controls the minimum size of created cavities.
ConfigOptionFloat hollowing_closing_distance;
protected:
void initialize(StaticCacheBase &cache, const char *base_ptr)
@ -1118,6 +1140,10 @@ protected:
OPT_PTR(pad_object_connector_stride);
OPT_PTR(pad_object_connector_width);
OPT_PTR(pad_object_connector_penetration);
OPT_PTR(hollowing_enable);
OPT_PTR(hollowing_min_thickness);
OPT_PTR(hollowing_quality);
OPT_PTR(hollowing_closing_distance);
}
};

View File

@ -1,7 +1,7 @@
#ifndef SLABOOSTADAPTER_HPP
#define SLABOOSTADAPTER_HPP
#ifndef SLA_BOOSTADAPTER_HPP
#define SLA_BOOSTADAPTER_HPP
#include "SLA/SLACommon.hpp"
#include <libslic3r/SLA/Common.hpp>
#include <boost/geometry.hpp>
namespace boost {

View File

@ -0,0 +1,30 @@
#ifndef SLA_CLUSTERING_HPP
#define SLA_CLUSTERING_HPP
#include <vector>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SpatIndex.hpp>
namespace Slic3r { namespace sla {
using ClusterEl = std::vector<unsigned>;
using ClusteredPoints = std::vector<ClusterEl>;
// Clustering a set of points by the given distance.
ClusteredPoints cluster(const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
double dist,
unsigned max_points);
ClusteredPoints cluster(const PointSet& points,
double dist,
unsigned max_points);
ClusteredPoints cluster(
const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
std::function<bool(const PointIndexEl&, const PointIndexEl&)> predicate,
unsigned max_points);
}}
#endif // CLUSTERING_HPP

View File

@ -0,0 +1,623 @@
#include <cmath>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SupportTree.hpp>
#include <libslic3r/SLA/SpatIndex.hpp>
#include <libslic3r/SLA/EigenMesh3D.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
#include <libslic3r/SLA/Clustering.hpp>
// Workaround: IGL signed_distance.h will define PI in the igl namespace.
#undef PI
// HEAVY headers... takes eternity to compile
// for concave hull merging decisions
#include <libslic3r/SLA/BoostAdapter.hpp>
#include "boost/geometry/index/rtree.hpp"
#ifdef _MSC_VER
#pragma warning(push)
#pragma warning(disable: 4244)
#pragma warning(disable: 4267)
#endif
#include <igl/ray_mesh_intersect.h>
#include <igl/point_mesh_squared_distance.h>
#include <igl/remove_duplicate_vertices.h>
#include <igl/signed_distance.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif
#include <tbb/parallel_for.h>
#include "ClipperUtils.hpp"
namespace Slic3r {
namespace sla {
// Bring back PI from the igl namespace
using igl::PI;
/* **************************************************************************
* PointIndex implementation
* ************************************************************************** */
class PointIndex::Impl {
public:
using BoostIndex = boost::geometry::index::rtree< PointIndexEl,
boost::geometry::index::rstar<16, 4> /* ? */ >;
BoostIndex m_store;
};
PointIndex::PointIndex(): m_impl(new Impl()) {}
PointIndex::~PointIndex() {}
PointIndex::PointIndex(const PointIndex &cpy): m_impl(new Impl(*cpy.m_impl)) {}
PointIndex::PointIndex(PointIndex&& cpy): m_impl(std::move(cpy.m_impl)) {}
PointIndex& PointIndex::operator=(const PointIndex &cpy)
{
m_impl.reset(new Impl(*cpy.m_impl));
return *this;
}
PointIndex& PointIndex::operator=(PointIndex &&cpy)
{
m_impl.swap(cpy.m_impl);
return *this;
}
void PointIndex::insert(const PointIndexEl &el)
{
m_impl->m_store.insert(el);
}
bool PointIndex::remove(const PointIndexEl& el)
{
return m_impl->m_store.remove(el) == 1;
}
std::vector<PointIndexEl>
PointIndex::query(std::function<bool(const PointIndexEl &)> fn) const
{
namespace bgi = boost::geometry::index;
std::vector<PointIndexEl> ret;
m_impl->m_store.query(bgi::satisfies(fn), std::back_inserter(ret));
return ret;
}
std::vector<PointIndexEl> PointIndex::nearest(const Vec3d &el, unsigned k = 1) const
{
namespace bgi = boost::geometry::index;
std::vector<PointIndexEl> ret; ret.reserve(k);
m_impl->m_store.query(bgi::nearest(el, k), std::back_inserter(ret));
return ret;
}
size_t PointIndex::size() const
{
return m_impl->m_store.size();
}
void PointIndex::foreach(std::function<void (const PointIndexEl &)> fn)
{
for(auto& el : m_impl->m_store) fn(el);
}
void PointIndex::foreach(std::function<void (const PointIndexEl &)> fn) const
{
for(const auto &el : m_impl->m_store) fn(el);
}
/* **************************************************************************
* BoxIndex implementation
* ************************************************************************** */
class BoxIndex::Impl {
public:
using BoostIndex = boost::geometry::index::
rtree<BoxIndexEl, boost::geometry::index::rstar<16, 4> /* ? */>;
BoostIndex m_store;
};
BoxIndex::BoxIndex(): m_impl(new Impl()) {}
BoxIndex::~BoxIndex() {}
BoxIndex::BoxIndex(const BoxIndex &cpy): m_impl(new Impl(*cpy.m_impl)) {}
BoxIndex::BoxIndex(BoxIndex&& cpy): m_impl(std::move(cpy.m_impl)) {}
BoxIndex& BoxIndex::operator=(const BoxIndex &cpy)
{
m_impl.reset(new Impl(*cpy.m_impl));
return *this;
}
BoxIndex& BoxIndex::operator=(BoxIndex &&cpy)
{
m_impl.swap(cpy.m_impl);
return *this;
}
void BoxIndex::insert(const BoxIndexEl &el)
{
m_impl->m_store.insert(el);
}
bool BoxIndex::remove(const BoxIndexEl& el)
{
return m_impl->m_store.remove(el) == 1;
}
std::vector<BoxIndexEl> BoxIndex::query(const BoundingBox &qrbb,
BoxIndex::QueryType qt)
{
namespace bgi = boost::geometry::index;
std::vector<BoxIndexEl> ret; ret.reserve(m_impl->m_store.size());
switch (qt) {
case qtIntersects:
m_impl->m_store.query(bgi::intersects(qrbb), std::back_inserter(ret));
break;
case qtWithin:
m_impl->m_store.query(bgi::within(qrbb), std::back_inserter(ret));
}
return ret;
}
size_t BoxIndex::size() const
{
return m_impl->m_store.size();
}
void BoxIndex::foreach(std::function<void (const BoxIndexEl &)> fn)
{
for(auto& el : m_impl->m_store) fn(el);
}
/* ****************************************************************************
* EigenMesh3D implementation
* ****************************************************************************/
class EigenMesh3D::AABBImpl: public igl::AABB<Eigen::MatrixXd, 3> {
public:
#ifdef SLIC3R_SLA_NEEDS_WINDTREE
igl::WindingNumberAABB<Vec3d, Eigen::MatrixXd, Eigen::MatrixXi> windtree;
#endif /* SLIC3R_SLA_NEEDS_WINDTREE */
};
EigenMesh3D::EigenMesh3D(const TriangleMesh& tmesh): m_aabb(new AABBImpl()) {
static const double dEPS = 1e-6;
const stl_file& stl = tmesh.stl;
auto&& bb = tmesh.bounding_box();
m_ground_level += bb.min(Z);
Eigen::MatrixXd V;
Eigen::MatrixXi F;
V.resize(3*stl.stats.number_of_facets, 3);
F.resize(stl.stats.number_of_facets, 3);
for (unsigned int i = 0; i < stl.stats.number_of_facets; ++i) {
const stl_facet &facet = stl.facet_start[i];
V.block<1, 3>(3 * i + 0, 0) = facet.vertex[0].cast<double>();
V.block<1, 3>(3 * i + 1, 0) = facet.vertex[1].cast<double>();
V.block<1, 3>(3 * i + 2, 0) = facet.vertex[2].cast<double>();
F(i, 0) = int(3*i+0);
F(i, 1) = int(3*i+1);
F(i, 2) = int(3*i+2);
}
// We will convert this to a proper 3d mesh with no duplicate points.
Eigen::VectorXi SVI, SVJ;
igl::remove_duplicate_vertices(V, F, dEPS, m_V, SVI, SVJ, m_F);
// Build the AABB accelaration tree
m_aabb->init(m_V, m_F);
#ifdef SLIC3R_SLA_NEEDS_WINDTREE
m_aabb->windtree.set_mesh(m_V, m_F);
#endif /* SLIC3R_SLA_NEEDS_WINDTREE */
}
EigenMesh3D::~EigenMesh3D() {}
EigenMesh3D::EigenMesh3D(const EigenMesh3D &other):
m_V(other.m_V), m_F(other.m_F), m_ground_level(other.m_ground_level),
m_aabb( new AABBImpl(*other.m_aabb) ) {}
EigenMesh3D::EigenMesh3D(const Contour3D &other)
{
m_V.resize(Eigen::Index(other.points.size()), 3);
m_F.resize(Eigen::Index(other.faces3.size() + 2 * other.faces4.size()), 3);
for (Eigen::Index i = 0; i < Eigen::Index(other.points.size()); ++i)
m_V.row(i) = other.points[size_t(i)];
for (Eigen::Index i = 0; i < Eigen::Index(other.faces3.size()); ++i)
m_F.row(i) = other.faces3[size_t(i)];
size_t N = other.faces3.size() + 2 * other.faces4.size();
for (size_t i = other.faces3.size(); i < N; i += 2) {
size_t quad_idx = (i - other.faces3.size()) / 2;
auto & quad = other.faces4[quad_idx];
m_F.row(Eigen::Index(i)) = Vec3i{quad(0), quad(1), quad(2)};
m_F.row(Eigen::Index(i + 1)) = Vec3i{quad(2), quad(3), quad(0)};
}
}
EigenMesh3D &EigenMesh3D::operator=(const EigenMesh3D &other)
{
m_V = other.m_V;
m_F = other.m_F;
m_ground_level = other.m_ground_level;
m_aabb.reset(new AABBImpl(*other.m_aabb)); return *this;
}
EigenMesh3D::hit_result
EigenMesh3D::query_ray_hit(const Vec3d &s, const Vec3d &dir) const
{
igl::Hit hit;
hit.t = std::numeric_limits<float>::infinity();
m_aabb->intersect_ray(m_V, m_F, s, dir, hit);
hit_result ret(*this);
ret.m_t = double(hit.t);
ret.m_dir = dir;
ret.m_source = s;
if(!std::isinf(hit.t) && !std::isnan(hit.t)) ret.m_face_id = hit.id;
return ret;
}
std::vector<EigenMesh3D::hit_result>
EigenMesh3D::query_ray_hits(const Vec3d &s, const Vec3d &dir) const
{
std::vector<EigenMesh3D::hit_result> outs;
std::vector<igl::Hit> hits;
m_aabb->intersect_ray(m_V, m_F, s, dir, hits);
// The sort is necessary, the hits are not always sorted.
std::sort(hits.begin(), hits.end(),
[](const igl::Hit& a, const igl::Hit& b) { return a.t < b.t; });
// Convert the igl::Hit into hit_result
outs.reserve(hits.size());
for (const igl::Hit& hit : hits) {
outs.emplace_back(EigenMesh3D::hit_result(*this));
outs.back().m_t = double(hit.t);
outs.back().m_dir = dir;
outs.back().m_source = s;
if(!std::isinf(hit.t) && !std::isnan(hit.t))
outs.back().m_face_id = hit.id;
}
return outs;
}
#ifdef SLIC3R_SLA_NEEDS_WINDTREE
EigenMesh3D::si_result EigenMesh3D::signed_distance(const Vec3d &p) const {
double sign = 0; double sqdst = 0; int i = 0; Vec3d c;
igl::signed_distance_winding_number(*m_aabb, m_V, m_F, m_aabb->windtree,
p, sign, sqdst, i, c);
return si_result(sign * std::sqrt(sqdst), i, c);
}
bool EigenMesh3D::inside(const Vec3d &p) const {
return m_aabb->windtree.inside(p);
}
#endif /* SLIC3R_SLA_NEEDS_WINDTREE */
double EigenMesh3D::squared_distance(const Vec3d &p, int& i, Vec3d& c) const {
double sqdst = 0;
Eigen::Matrix<double, 1, 3> pp = p;
Eigen::Matrix<double, 1, 3> cc;
sqdst = m_aabb->squared_distance(m_V, m_F, pp, i, cc);
c = cc;
return sqdst;
}
/* ****************************************************************************
* Misc functions
* ****************************************************************************/
namespace {
bool point_on_edge(const Vec3d& p, const Vec3d& e1, const Vec3d& e2,
double eps = 0.05)
{
using Line3D = Eigen::ParametrizedLine<double, 3>;
auto line = Line3D::Through(e1, e2);
double d = line.distance(p);
return std::abs(d) < eps;
}
template<class Vec> double distance(const Vec& pp1, const Vec& pp2) {
auto p = pp2 - pp1;
return std::sqrt(p.transpose() * p);
}
}
PointSet normals(const PointSet& points,
const EigenMesh3D& mesh,
double eps,
std::function<void()> thr, // throw on cancel
const std::vector<unsigned>& pt_indices)
{
if(points.rows() == 0 || mesh.V().rows() == 0 || mesh.F().rows() == 0)
return {};
std::vector<unsigned> range = pt_indices;
if(range.empty()) {
range.resize(size_t(points.rows()), 0);
std::iota(range.begin(), range.end(), 0);
}
PointSet ret(range.size(), 3);
// for (size_t ridx = 0; ridx < range.size(); ++ridx)
tbb::parallel_for(size_t(0), range.size(),
[&ret, &range, &mesh, &points, thr, eps](size_t ridx)
{
thr();
auto eidx = Eigen::Index(range[ridx]);
int faceid = 0;
Vec3d p;
mesh.squared_distance(points.row(eidx), faceid, p);
auto trindex = mesh.F().row(faceid);
const Vec3d& p1 = mesh.V().row(trindex(0));
const Vec3d& p2 = mesh.V().row(trindex(1));
const Vec3d& p3 = mesh.V().row(trindex(2));
// We should check if the point lies on an edge of the hosting triangle.
// If it does then all the other triangles using the same two points
// have to be searched and the final normal should be some kind of
// aggregation of the participating triangle normals. We should also
// consider the cases where the support point lies right on a vertex
// of its triangle. The procedure is the same, get the neighbor
// triangles and calculate an average normal.
// mark the vertex indices of the edge. ia and ib marks and edge ic
// will mark a single vertex.
int ia = -1, ib = -1, ic = -1;
if(std::abs(distance(p, p1)) < eps) {
ic = trindex(0);
}
else if(std::abs(distance(p, p2)) < eps) {
ic = trindex(1);
}
else if(std::abs(distance(p, p3)) < eps) {
ic = trindex(2);
}
else if(point_on_edge(p, p1, p2, eps)) {
ia = trindex(0); ib = trindex(1);
}
else if(point_on_edge(p, p2, p3, eps)) {
ia = trindex(1); ib = trindex(2);
}
else if(point_on_edge(p, p1, p3, eps)) {
ia = trindex(0); ib = trindex(2);
}
// vector for the neigboring triangles including the detected one.
std::vector<Vec3i> neigh;
if(ic >= 0) { // The point is right on a vertex of the triangle
for(int n = 0; n < mesh.F().rows(); ++n) {
thr();
Vec3i ni = mesh.F().row(n);
if((ni(X) == ic || ni(Y) == ic || ni(Z) == ic))
neigh.emplace_back(ni);
}
}
else if(ia >= 0 && ib >= 0) { // the point is on and edge
// now get all the neigboring triangles
for(int n = 0; n < mesh.F().rows(); ++n) {
thr();
Vec3i ni = mesh.F().row(n);
if((ni(X) == ia || ni(Y) == ia || ni(Z) == ia) &&
(ni(X) == ib || ni(Y) == ib || ni(Z) == ib))
neigh.emplace_back(ni);
}
}
// Calculate the normals for the neighboring triangles
std::vector<Vec3d> neighnorms; neighnorms.reserve(neigh.size());
for(const Vec3i& tri : neigh) {
const Vec3d& pt1 = mesh.V().row(tri(0));
const Vec3d& pt2 = mesh.V().row(tri(1));
const Vec3d& pt3 = mesh.V().row(tri(2));
Eigen::Vector3d U = pt2 - pt1;
Eigen::Vector3d V = pt3 - pt1;
neighnorms.emplace_back(U.cross(V).normalized());
}
// Throw out duplicates. They would cause trouble with summing. We will
// use std::unique which works on sorted ranges. We will sort by the
// coefficient-wise sum of the normals. It should force the same
// elements to be consecutive.
std::sort(neighnorms.begin(), neighnorms.end(),
[](const Vec3d& v1, const Vec3d& v2){
return v1.sum() < v2.sum();
});
auto lend = std::unique(neighnorms.begin(), neighnorms.end(),
[](const Vec3d& n1, const Vec3d& n2) {
// Compare normals for equivalence. This is controvers stuff.
auto deq = [](double a, double b) { return std::abs(a-b) < 1e-3; };
return deq(n1(X), n2(X)) && deq(n1(Y), n2(Y)) && deq(n1(Z), n2(Z));
});
if(!neighnorms.empty()) { // there were neighbors to count with
// sum up the normals and then normalize the result again.
// This unification seems to be enough.
Vec3d sumnorm(0, 0, 0);
sumnorm = std::accumulate(neighnorms.begin(), lend, sumnorm);
sumnorm.normalize();
ret.row(long(ridx)) = sumnorm;
}
else { // point lies safely within its triangle
Eigen::Vector3d U = p2 - p1;
Eigen::Vector3d V = p3 - p1;
ret.row(long(ridx)) = U.cross(V).normalized();
}
});
return ret;
}
namespace bgi = boost::geometry::index;
using Index3D = bgi::rtree< PointIndexEl, bgi::rstar<16, 4> /* ? */ >;
namespace {
bool cmp_ptidx_elements(const PointIndexEl& e1, const PointIndexEl& e2)
{
return e1.second < e2.second;
};
ClusteredPoints cluster(Index3D &sindex,
unsigned max_points,
std::function<std::vector<PointIndexEl>(
const Index3D &, const PointIndexEl &)> qfn)
{
using Elems = std::vector<PointIndexEl>;
// Recursive function for visiting all the points in a given distance to
// each other
std::function<void(Elems&, Elems&)> group =
[&sindex, &group, max_points, qfn](Elems& pts, Elems& cluster)
{
for(auto& p : pts) {
std::vector<PointIndexEl> tmp = qfn(sindex, p);
std::sort(tmp.begin(), tmp.end(), cmp_ptidx_elements);
Elems newpts;
std::set_difference(tmp.begin(), tmp.end(),
cluster.begin(), cluster.end(),
std::back_inserter(newpts), cmp_ptidx_elements);
int c = max_points && newpts.size() + cluster.size() > max_points?
int(max_points - cluster.size()) : int(newpts.size());
cluster.insert(cluster.end(), newpts.begin(), newpts.begin() + c);
std::sort(cluster.begin(), cluster.end(), cmp_ptidx_elements);
if(!newpts.empty() && (!max_points || cluster.size() < max_points))
group(newpts, cluster);
}
};
std::vector<Elems> clusters;
for(auto it = sindex.begin(); it != sindex.end();) {
Elems cluster = {};
Elems pts = {*it};
group(pts, cluster);
for(auto& c : cluster) sindex.remove(c);
it = sindex.begin();
clusters.emplace_back(cluster);
}
ClusteredPoints result;
for(auto& cluster : clusters) {
result.emplace_back();
for(auto c : cluster) result.back().emplace_back(c.second);
}
return result;
}
std::vector<PointIndexEl> distance_queryfn(const Index3D& sindex,
const PointIndexEl& p,
double dist,
unsigned max_points)
{
std::vector<PointIndexEl> tmp; tmp.reserve(max_points);
sindex.query(
bgi::nearest(p.first, max_points),
std::back_inserter(tmp)
);
for(auto it = tmp.begin(); it < tmp.end(); ++it)
if(distance(p.first, it->first) > dist) it = tmp.erase(it);
return tmp;
}
} // namespace
// Clustering a set of points by the given criteria
ClusteredPoints cluster(
const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
double dist,
unsigned max_points)
{
// A spatial index for querying the nearest points
Index3D sindex;
// Build the index
for(auto idx : indices) sindex.insert( std::make_pair(pointfn(idx), idx));
return cluster(sindex, max_points,
[dist, max_points](const Index3D& sidx, const PointIndexEl& p)
{
return distance_queryfn(sidx, p, dist, max_points);
});
}
// Clustering a set of points by the given criteria
ClusteredPoints cluster(
const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
std::function<bool(const PointIndexEl&, const PointIndexEl&)> predicate,
unsigned max_points)
{
// A spatial index for querying the nearest points
Index3D sindex;
// Build the index
for(auto idx : indices) sindex.insert( std::make_pair(pointfn(idx), idx));
return cluster(sindex, max_points,
[max_points, predicate](const Index3D& sidx, const PointIndexEl& p)
{
std::vector<PointIndexEl> tmp; tmp.reserve(max_points);
sidx.query(bgi::satisfies([p, predicate](const PointIndexEl& e){
return predicate(p, e);
}), std::back_inserter(tmp));
return tmp;
});
}
ClusteredPoints cluster(const PointSet& pts, double dist, unsigned max_points)
{
// A spatial index for querying the nearest points
Index3D sindex;
// Build the index
for(Eigen::Index i = 0; i < pts.rows(); i++)
sindex.insert(std::make_pair(Vec3d(pts.row(i)), unsigned(i)));
return cluster(sindex, max_points,
[dist, max_points](const Index3D& sidx, const PointIndexEl& p)
{
return distance_queryfn(sidx, p, dist, max_points);
});
}
} // namespace sla
} // namespace Slic3r

View File

@ -0,0 +1,32 @@
#ifndef SLA_COMMON_HPP
#define SLA_COMMON_HPP
#include <memory>
#include <vector>
#include <numeric>
#include <functional>
#include <Eigen/Geometry>
//#include "SLASpatIndex.hpp"
//#include <libslic3r/ExPolygon.hpp>
//#include <libslic3r/TriangleMesh.hpp>
// #define SLIC3R_SLA_NEEDS_WINDTREE
namespace Slic3r {
// Typedefs from Point.hpp
typedef Eigen::Matrix<float, 3, 1, Eigen::DontAlign> Vec3f;
typedef Eigen::Matrix<double, 3, 1, Eigen::DontAlign> Vec3d;
typedef Eigen::Matrix<int, 4, 1, Eigen::DontAlign> Vec4i;
namespace sla {
using PointSet = Eigen::MatrixXd;
} // namespace sla
} // namespace Slic3r
#endif // SLASUPPORTTREE_HPP

View File

@ -1,7 +1,9 @@
#include "ConcaveHull.hpp"
#include <libslic3r/SLA/ConcaveHull.hpp>
#include <libslic3r/SLA/SpatIndex.hpp>
#include <libslic3r/MTUtils.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include "SLASpatIndex.hpp"
#include <boost/log/trivial.hpp>
namespace Slic3r {
@ -40,9 +42,9 @@ Point ConcaveHull::centroid(const Points &pp)
// As it shows, the current offset_ex in ClipperUtils hangs if used in jtRound
// mode
ClipperLib::Paths fast_offset(const ClipperLib::Paths &paths,
coord_t delta,
ClipperLib::JoinType jointype)
static ClipperLib::Paths fast_offset(const ClipperLib::Paths &paths,
coord_t delta,
ClipperLib::JoinType jointype)
{
using ClipperLib::ClipperOffset;
using ClipperLib::etClosedPolygon;
@ -73,7 +75,7 @@ Points ConcaveHull::calculate_centroids() const
Points centroids = reserve_vector<Point>(m_polys.size());
std::transform(m_polys.begin(), m_polys.end(),
std::back_inserter(centroids),
[this](const Polygon &poly) { return centroid(poly); });
[](const Polygon &poly) { return centroid(poly); });
return centroids;
}

View File

@ -1,5 +1,5 @@
#ifndef CONCAVEHULL_HPP
#define CONCAVEHULL_HPP
#ifndef SLA_CONCAVEHULL_HPP
#define SLA_CONCAVEHULL_HPP
#include <libslic3r/ExPolygon.hpp>

View File

@ -1,5 +1,5 @@
#ifndef SLACONCURRENCY_H
#define SLACONCURRENCY_H
#ifndef SLA_CONCURRENCY_H
#define SLA_CONCURRENCY_H
#include <tbb/spin_mutex.h>
#include <tbb/mutex.h>

View File

@ -1,4 +1,6 @@
#include "SLACommon.hpp"
#include <libslic3r/SLA/Contour3D.hpp>
#include <libslic3r/SLA/EigenMesh3D.hpp>
#include <libslic3r/Format/objparser.hpp>
namespace Slic3r { namespace sla {

View File

@ -0,0 +1,45 @@
#ifndef SLA_CONTOUR3D_HPP
#define SLA_CONTOUR3D_HPP
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/TriangleMesh.hpp>
namespace Slic3r { namespace sla {
class EigenMesh3D;
/// Dumb vertex mesh consisting of triangles (or) quads. Capable of merging with
/// other meshes of this type and converting to and from other mesh formats.
struct Contour3D {
std::vector<Vec3d> points;
std::vector<Vec3i> faces3;
std::vector<Vec4i> faces4;
Contour3D() = default;
Contour3D(const TriangleMesh &trmesh);
Contour3D(TriangleMesh &&trmesh);
Contour3D(const EigenMesh3D &emesh);
Contour3D& merge(const Contour3D& ctr);
Contour3D& merge(const Pointf3s& triangles);
// Write the index triangle structure to OBJ file for debugging purposes.
void to_obj(std::ostream& stream);
void from_obj(std::istream &stream);
inline bool empty() const
{
return points.empty() || (faces4.empty() && faces3.empty());
}
};
/// Mesh from an existing contour.
TriangleMesh to_triangle_mesh(const Contour3D& ctour);
/// Mesh from an evaporating 3D contour
TriangleMesh to_triangle_mesh(Contour3D&& ctour);
}} // namespace Slic3r::sla
#endif // CONTOUR3D_HPP

View File

@ -0,0 +1,135 @@
#ifndef SLA_EIGENMESH3D_H
#define SLA_EIGENMESH3D_H
#include <libslic3r/SLA/Common.hpp>
namespace Slic3r {
class TriangleMesh;
namespace sla {
struct Contour3D;
/// An index-triangle structure for libIGL functions. Also serves as an
/// alternative (raw) input format for the SLASupportTree.
// Implemented in SLASupportTreeIGL.cpp
class EigenMesh3D {
class AABBImpl;
Eigen::MatrixXd m_V;
Eigen::MatrixXi m_F;
double m_ground_level = 0, m_gnd_offset = 0;
std::unique_ptr<AABBImpl> m_aabb;
public:
EigenMesh3D(const TriangleMesh&);
EigenMesh3D(const EigenMesh3D& other);
EigenMesh3D(const Contour3D &other);
EigenMesh3D& operator=(const EigenMesh3D&);
~EigenMesh3D();
inline double ground_level() const { return m_ground_level + m_gnd_offset; }
inline void ground_level_offset(double o) { m_gnd_offset = o; }
inline double ground_level_offset() const { return m_gnd_offset; }
inline const Eigen::MatrixXd& V() const { return m_V; }
inline const Eigen::MatrixXi& F() const { return m_F; }
// Result of a raycast
class hit_result {
double m_t = std::nan("");
int m_face_id = -1;
const EigenMesh3D *m_mesh = nullptr;
Vec3d m_dir;
Vec3d m_source;
friend class EigenMesh3D;
// A valid object of this class can only be obtained from
// EigenMesh3D::query_ray_hit method.
explicit inline hit_result(const EigenMesh3D& em): m_mesh(&em) {}
public:
// This can create a placeholder object which is invalid (not created
// by a query_ray_hit call) but the distance can be preset to
// a specific value for distinguishing the placeholder.
inline hit_result(double val = std::nan("")): m_t(val) {}
inline double distance() const { return m_t; }
inline const Vec3d& direction() const { return m_dir; }
inline Vec3d position() const { return m_source + m_dir * m_t; }
inline int face() const { return m_face_id; }
inline bool is_valid() const { return m_mesh != nullptr; }
// Hit_result can decay into a double as the hit distance.
inline operator double() const { return distance(); }
inline Vec3d normal() const {
if(m_face_id < 0 || !is_valid()) return {};
auto trindex = m_mesh->m_F.row(m_face_id);
const Vec3d& p1 = m_mesh->V().row(trindex(0));
const Vec3d& p2 = m_mesh->V().row(trindex(1));
const Vec3d& p3 = m_mesh->V().row(trindex(2));
Eigen::Vector3d U = p2 - p1;
Eigen::Vector3d V = p3 - p1;
return U.cross(V).normalized();
}
inline bool is_inside() {
return m_face_id >= 0 && normal().dot(m_dir) > 0;
}
};
// Casting a ray on the mesh, returns the distance where the hit occures.
hit_result query_ray_hit(const Vec3d &s, const Vec3d &dir) const;
// Casts a ray on the mesh and returns all hits
std::vector<hit_result> query_ray_hits(const Vec3d &s, const Vec3d &dir) const;
class si_result {
double m_value;
int m_fidx;
Vec3d m_p;
si_result(double val, int i, const Vec3d& c):
m_value(val), m_fidx(i), m_p(c) {}
friend class EigenMesh3D;
public:
si_result() = delete;
double value() const { return m_value; }
operator double() const { return m_value; }
const Vec3d& point_on_mesh() const { return m_p; }
int F_idx() const { return m_fidx; }
};
#ifdef SLIC3R_SLA_NEEDS_WINDTREE
// The signed distance from a point to the mesh. Outputs the distance,
// the index of the triangle and the closest point in mesh coordinate space.
si_result signed_distance(const Vec3d& p) const;
bool inside(const Vec3d& p) const;
#endif /* SLIC3R_SLA_NEEDS_WINDTREE */
double squared_distance(const Vec3d& p, int& i, Vec3d& c) const;
inline double squared_distance(const Vec3d &p) const
{
int i;
Vec3d c;
return squared_distance(p, i, c);
}
};
// Calculate the normals for the selected points (from 'points' set) on the
// mesh. This will call squared distance for each point.
PointSet normals(const PointSet& points,
const EigenMesh3D& convert_mesh,
double eps = 0.05, // min distance from edges
std::function<void()> throw_on_cancel = [](){},
const std::vector<unsigned>& selected_points = {});
}} // namespace Slic3r::sla
#endif // EIGENMESH3D_H

View File

@ -0,0 +1,119 @@
#include <functional>
#include <libslic3r/SLA/Hollowing.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
//#include <openvdb/tools/Filter.h>
#include <boost/log/trivial.hpp>
#include <libslic3r/MTUtils.hpp>
#include <libslic3r/I18N.hpp>
//! macro used to mark string used at localization,
//! return same string
#define L(s) Slic3r::I18N::translate(s)
namespace Slic3r {
namespace sla {
template<class S, class = FloatingOnly<S>>
inline void _scale(S s, TriangleMesh &m) { m.scale(float(s)); }
template<class S, class = FloatingOnly<S>>
inline void _scale(S s, Contour3D &m)
{
for (auto &p : m.points) p *= s;
}
template<class Mesh>
remove_cvref_t<Mesh> _grid_to_mesh(const openvdb::FloatGrid &grid,
double isosurf,
double adapt);
template<>
TriangleMesh _grid_to_mesh<TriangleMesh>(const openvdb::FloatGrid &grid,
double isosurf,
double adapt)
{
return grid_to_mesh(grid, isosurf, adapt);
}
template<>
Contour3D _grid_to_mesh<Contour3D>(const openvdb::FloatGrid &grid,
double isosurf,
double adapt)
{
return grid_to_contour3d(grid, isosurf, adapt);
}
template<class Mesh>
remove_cvref_t<Mesh> _generate_interior(Mesh &&mesh,
const JobController &ctl,
double min_thickness,
double voxel_scale,
double closing_dist)
{
using MMesh = remove_cvref_t<Mesh>;
MMesh imesh{std::forward<Mesh>(mesh)};
_scale(voxel_scale, imesh);
double offset = voxel_scale * min_thickness;
double D = voxel_scale * closing_dist;
float out_range = 0.1f * float(offset);
float in_range = 1.1f * float(offset + D);
if (ctl.stopcondition()) return {};
else ctl.statuscb(0, L("Hollowing"));
auto gridptr = mesh_to_grid(imesh, {}, out_range, in_range);
assert(gridptr);
if (!gridptr) {
BOOST_LOG_TRIVIAL(error) << "Returned OpenVDB grid is NULL";
return MMesh{};
}
if (ctl.stopcondition()) return {};
else ctl.statuscb(30, L("Hollowing"));
if (closing_dist > .0) {
gridptr = redistance_grid(*gridptr, -(offset + D), double(in_range));
} else {
D = -offset;
}
if (ctl.stopcondition()) return {};
else ctl.statuscb(70, L("Hollowing"));
// openvdb::tools::Filter<openvdb::FloatGrid> filt{*gridptr};
// filt.offset(float(offset + D));
double iso_surface = D;
double adaptivity = 0.;
auto omesh = _grid_to_mesh<MMesh>(*gridptr, iso_surface, adaptivity);
_scale(1. / voxel_scale, omesh);
if (ctl.stopcondition()) return {};
else ctl.statuscb(100, L("Hollowing"));
return omesh;
}
TriangleMesh generate_interior(const TriangleMesh &mesh, const HollowingConfig &hc, const JobController &ctl)
{
static const double MAX_OVERSAMPL = 7.;
// I can't figure out how to increase the grid resolution through openvdb API
// so the model will be scaled up before conversion and the result scaled
// down. Voxels have a unit size. If I set voxelSize smaller, it scales
// the whole geometry down, and doesn't increase the number of voxels.
//
// max 8x upscale, min is native voxel size
auto voxel_scale = (1.0 + MAX_OVERSAMPL * hc.quality);
return _generate_interior(mesh, ctl, hc.min_thickness, voxel_scale, hc.closing_distance);
}
}} // namespace Slic3r::sla

View File

@ -0,0 +1,58 @@
#ifndef SLA_HOLLOWING_HPP
#define SLA_HOLLOWING_HPP
#include <libslic3r/OpenVDBUtils.hpp>
#include <libslic3r/SLA/JobController.hpp>
namespace Slic3r {
namespace sla {
struct HollowingConfig
{
double min_thickness = 2.;
double quality = 0.5;
double closing_distance = 0.5;
};
struct DrainHole
{
Vec3f m_pos;
Vec3f m_normal;
float m_radius;
float m_height;
DrainHole()
: m_pos(Vec3f::Zero()), m_normal(Vec3f::UnitZ()), m_radius(5.f),
m_height(10.f)
{}
DrainHole(Vec3f position, Vec3f normal, float radius, float height)
: m_pos(position)
, m_normal(normal)
, m_radius(radius)
, m_height(height)
{}
bool operator==(const DrainHole &sp) const
{
return (m_pos == sp.m_pos) && (m_normal == sp.m_normal) &&
is_approx(m_radius, sp.m_radius) &&
is_approx(m_height, sp.m_height);
}
bool operator!=(const DrainHole &sp) const { return !(sp == (*this)); }
template<class Archive> void serialize(Archive &ar)
{
ar(m_pos, m_normal, m_radius, m_height);
}
};
TriangleMesh generate_interior(const TriangleMesh &mesh,
const HollowingConfig & = {},
const JobController &ctl = {});
}
}
#endif // HOLLOWINGFILTER_H

View File

@ -0,0 +1,31 @@
#ifndef SLA_JOBCONTROLLER_HPP
#define SLA_JOBCONTROLLER_HPP
#include <functional>
namespace Slic3r { namespace sla {
/// A Control structure for the support calculation. Consists of the status
/// indicator callback and the stop condition predicate.
struct JobController
{
using StatusFn = std::function<void(unsigned, const std::string&)>;
using StopCond = std::function<bool(void)>;
using CancelFn = std::function<void(void)>;
// This will signal the status of the calculation to the front-end
StatusFn statuscb = [](unsigned, const std::string&){};
// Returns true if the calculation should be aborted.
StopCond stopcondition = [](){ return false; };
// Similar to cancel callback. This should check the stop condition and
// if true, throw an appropriate exception. (TriangleMeshSlicer needs this)
// consider it a hard abort. stopcondition is permits the algorithm to
// terminate itself
CancelFn cancelfn = [](){};
};
}} // namespace Slic3r::sla
#endif // JOBCONTROLLER_HPP

View File

@ -1,10 +1,12 @@
#include "SLAPad.hpp"
#include "SLACommon.hpp"
#include "SLASpatIndex.hpp"
#include <libslic3r/SLA/Pad.hpp>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SpatIndex.hpp>
#include <libslic3r/SLA/BoostAdapter.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
#include "ConcaveHull.hpp"
#include "boost/log/trivial.hpp"
#include "SLABoostAdapter.hpp"
#include "ClipperUtils.hpp"
#include "Tesselate.hpp"
#include "MTUtils.hpp"

View File

@ -1,5 +1,5 @@
#ifndef SLABASEPOOL_HPP
#define SLABASEPOOL_HPP
#ifndef SLA_PAD_HPP
#define SLA_PAD_HPP
#include <vector>
#include <functional>

View File

@ -3,7 +3,7 @@
#include <functional>
#include "SLARaster.hpp"
#include <libslic3r/SLA/Raster.hpp>
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/MTUtils.hpp"
#include <libnest2d/backends/clipper/clipper_polygon.hpp>

View File

@ -1,5 +1,5 @@
#ifndef SLARASTER_HPP
#define SLARASTER_HPP
#ifndef SLA_RASTER_HPP
#define SLA_RASTER_HPP
#include <ostream>
#include <memory>

View File

@ -1,6 +1,6 @@
#include "SLARasterWriter.hpp"
#include "libslic3r/Zipper.hpp"
#include "libslic3r/Time.hpp"
#include <libslic3r/SLA/RasterWriter.hpp>
#include <libslic3r/Zipper.hpp>
#include <libslic3r/Time.hpp>
#include "ExPolygon.hpp"
#include <libnest2d/backends/clipper/clipper_polygon.hpp>

View File

@ -1,5 +1,5 @@
#ifndef SLARASTERWRITER_HPP
#define SLARASTERWRITER_HPP
#ifndef SLA_RASTERWRITER_HPP
#define SLA_RASTERWRITER_HPP
// For png export of the sliced model
#include <fstream>
@ -11,7 +11,7 @@
#include "libslic3r/PrintConfig.hpp"
#include "SLARaster.hpp"
#include <libslic3r/SLA/Raster.hpp>
namespace Slic3r { namespace sla {

View File

@ -2,9 +2,9 @@
#include <exception>
#include <libnest2d/optimizers/nlopt/genetic.hpp>
#include "SLACommon.hpp"
#include "SLARotfinder.hpp"
#include "SLASupportTree.hpp"
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/Rotfinder.hpp>
#include <libslic3r/SLA/SupportTree.hpp>
#include "Model.hpp"
namespace Slic3r {

View File

@ -1,5 +1,5 @@
#ifndef SLAROTFINDER_HPP
#define SLAROTFINDER_HPP
#ifndef SLA_ROTFINDER_HPP
#define SLA_ROTFINDER_HPP
#include <functional>
#include <array>

View File

@ -1,292 +0,0 @@
#ifndef SLACOMMON_HPP
#define SLACOMMON_HPP
#include <memory>
#include <vector>
#include <numeric>
#include <functional>
#include <Eigen/Geometry>
#include "SLASpatIndex.hpp"
#include <libslic3r/ExPolygon.hpp>
#include <libslic3r/TriangleMesh.hpp>
// #define SLIC3R_SLA_NEEDS_WINDTREE
namespace Slic3r {
// Typedefs from Point.hpp
typedef Eigen::Matrix<float, 3, 1, Eigen::DontAlign> Vec3f;
typedef Eigen::Matrix<double, 3, 1, Eigen::DontAlign> Vec3d;
typedef Eigen::Matrix<int, 4, 1, Eigen::DontAlign> Vec4i;
namespace sla {
// An enum to keep track of where the current points on the ModelObject came from.
enum class PointsStatus {
NoPoints, // No points were generated so far.
Generating, // The autogeneration algorithm triggered, but not yet finished.
AutoGenerated, // Points were autogenerated (i.e. copied from the backend).
UserModified // User has done some edits.
};
struct SupportPoint
{
Vec3f pos;
float head_front_radius;
bool is_new_island;
SupportPoint()
: pos(Vec3f::Zero()), head_front_radius(0.f), is_new_island(false)
{}
SupportPoint(float pos_x,
float pos_y,
float pos_z,
float head_radius,
bool new_island)
: pos(pos_x, pos_y, pos_z)
, head_front_radius(head_radius)
, is_new_island(new_island)
{}
SupportPoint(Vec3f position, float head_radius, bool new_island)
: pos(position)
, head_front_radius(head_radius)
, is_new_island(new_island)
{}
SupportPoint(Eigen::Matrix<float, 5, 1, Eigen::DontAlign> data)
: pos(data(0), data(1), data(2))
, head_front_radius(data(3))
, is_new_island(data(4) != 0.f)
{}
bool operator==(const SupportPoint &sp) const
{
float rdiff = std::abs(head_front_radius - sp.head_front_radius);
return (pos == sp.pos) && rdiff < float(EPSILON) &&
is_new_island == sp.is_new_island;
}
bool operator!=(const SupportPoint &sp) const { return !(sp == (*this)); }
template<class Archive> void serialize(Archive &ar)
{
ar(pos, head_front_radius, is_new_island);
}
};
using SupportPoints = std::vector<SupportPoint>;
struct DrainHole
{
Vec3f m_pos;
Vec3f m_normal;
float m_radius;
float m_height;
DrainHole()
: m_pos(Vec3f::Zero()), m_normal(Vec3f::UnitZ()), m_radius(5.f),
m_height(10.f)
{}
DrainHole(Vec3f position, Vec3f normal, float radius, float height)
: m_pos(position)
, m_normal(normal)
, m_radius(radius)
, m_height(height)
{}
bool operator==(const DrainHole &sp) const
{
return (m_pos == sp.m_pos) && (m_normal == sp.m_normal)
&& is_approx(m_radius, sp.m_radius) && is_approx(m_height, sp.m_height);
}
bool operator!=(const DrainHole &sp) const { return !(sp == (*this)); }
template<class Archive> void serialize(Archive &ar)
{
ar(m_pos, m_normal, m_radius, m_height);
}
};
struct Contour3D;
/// An index-triangle structure for libIGL functions. Also serves as an
/// alternative (raw) input format for the SLASupportTree.
// Implemented in SLASupportTreeIGL.cpp
class EigenMesh3D {
class AABBImpl;
Eigen::MatrixXd m_V;
Eigen::MatrixXi m_F;
double m_ground_level = 0, m_gnd_offset = 0;
std::unique_ptr<AABBImpl> m_aabb;
public:
EigenMesh3D(const TriangleMesh&);
EigenMesh3D(const EigenMesh3D& other);
EigenMesh3D(const Contour3D &other);
EigenMesh3D& operator=(const EigenMesh3D&);
~EigenMesh3D();
inline double ground_level() const { return m_ground_level + m_gnd_offset; }
inline void ground_level_offset(double o) { m_gnd_offset = o; }
inline double ground_level_offset() const { return m_gnd_offset; }
inline const Eigen::MatrixXd& V() const { return m_V; }
inline const Eigen::MatrixXi& F() const { return m_F; }
// Result of a raycast
class hit_result {
double m_t = std::nan("");
int m_face_id = -1;
const EigenMesh3D *m_mesh = nullptr;
Vec3d m_dir;
Vec3d m_source;
friend class EigenMesh3D;
// A valid object of this class can only be obtained from
// EigenMesh3D::query_ray_hit method.
explicit inline hit_result(const EigenMesh3D& em): m_mesh(&em) {}
public:
// This can create a placeholder object which is invalid (not created
// by a query_ray_hit call) but the distance can be preset to
// a specific value for distinguishing the placeholder.
inline hit_result(double val = std::nan("")): m_t(val) {}
inline double distance() const { return m_t; }
inline const Vec3d& direction() const { return m_dir; }
inline Vec3d position() const { return m_source + m_dir * m_t; }
inline int face() const { return m_face_id; }
inline bool is_valid() const { return m_mesh != nullptr; }
// Hit_result can decay into a double as the hit distance.
inline operator double() const { return distance(); }
inline Vec3d normal() const {
if(m_face_id < 0 || !is_valid()) return {};
auto trindex = m_mesh->m_F.row(m_face_id);
const Vec3d& p1 = m_mesh->V().row(trindex(0));
const Vec3d& p2 = m_mesh->V().row(trindex(1));
const Vec3d& p3 = m_mesh->V().row(trindex(2));
Eigen::Vector3d U = p2 - p1;
Eigen::Vector3d V = p3 - p1;
return U.cross(V).normalized();
}
inline bool is_inside() {
return m_face_id >= 0 && normal().dot(m_dir) > 0;
}
};
// Casting a ray on the mesh, returns the distance where the hit occures.
hit_result query_ray_hit(const Vec3d &s, const Vec3d &dir) const;
// Casts a ray on the mesh and returns all hits
std::vector<hit_result> query_ray_hits(const Vec3d &s, const Vec3d &dir) const;
class si_result {
double m_value;
int m_fidx;
Vec3d m_p;
si_result(double val, int i, const Vec3d& c):
m_value(val), m_fidx(i), m_p(c) {}
friend class EigenMesh3D;
public:
si_result() = delete;
double value() const { return m_value; }
operator double() const { return m_value; }
const Vec3d& point_on_mesh() const { return m_p; }
int F_idx() const { return m_fidx; }
};
#ifdef SLIC3R_SLA_NEEDS_WINDTREE
// The signed distance from a point to the mesh. Outputs the distance,
// the index of the triangle and the closest point in mesh coordinate space.
si_result signed_distance(const Vec3d& p) const;
bool inside(const Vec3d& p) const;
#endif /* SLIC3R_SLA_NEEDS_WINDTREE */
double squared_distance(const Vec3d& p, int& i, Vec3d& c) const;
inline double squared_distance(const Vec3d &p) const
{
int i;
Vec3d c;
return squared_distance(p, i, c);
}
};
using PointSet = Eigen::MatrixXd;
/// Dumb vertex mesh consisting of triangles (or) quads. Capable of merging with
/// other meshes of this type and converting to and from other mesh formats.
struct Contour3D {
Pointf3s points;
std::vector<Vec3i> faces3;
std::vector<Vec4i> faces4;
Contour3D() = default;
Contour3D(const TriangleMesh &trmesh);
Contour3D(TriangleMesh &&trmesh);
Contour3D(const EigenMesh3D &emesh);
Contour3D& merge(const Contour3D& ctr);
Contour3D& merge(const Pointf3s& triangles);
// Write the index triangle structure to OBJ file for debugging purposes.
void to_obj(std::ostream& stream);
void from_obj(std::istream &stream);
inline bool empty() const { return points.empty() || (faces4.empty() && faces3.empty()); }
};
using ClusterEl = std::vector<unsigned>;
using ClusteredPoints = std::vector<ClusterEl>;
// Clustering a set of points by the given distance.
ClusteredPoints cluster(const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
double dist,
unsigned max_points);
ClusteredPoints cluster(const PointSet& points,
double dist,
unsigned max_points);
ClusteredPoints cluster(
const std::vector<unsigned>& indices,
std::function<Vec3d(unsigned)> pointfn,
std::function<bool(const PointIndexEl&, const PointIndexEl&)> predicate,
unsigned max_points);
// Calculate the normals for the selected points (from 'points' set) on the
// mesh. This will call squared distance for each point.
PointSet normals(const PointSet& points,
const EigenMesh3D& convert_mesh,
double eps = 0.05, // min distance from edges
std::function<void()> throw_on_cancel = [](){},
const std::vector<unsigned>& selected_points = {});
/// Mesh from an existing contour.
TriangleMesh to_triangle_mesh(const Contour3D& ctour);
/// Mesh from an evaporating 3D contour
TriangleMesh to_triangle_mesh(Contour3D&& ctour);
} // namespace sla
} // namespace Slic3r
#endif // SLASUPPORTTREE_HPP

View File

@ -1,5 +1,5 @@
#ifndef SPATINDEX_HPP
#define SPATINDEX_HPP
#ifndef SLA_SPATINDEX_HPP
#define SLA_SPATINDEX_HPP
#include <memory>
#include <utility>

View File

@ -0,0 +1,69 @@
#ifndef SLA_SUPPORTPOINT_HPP
#define SLA_SUPPORTPOINT_HPP
#include <vector>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/ExPolygon.hpp>
namespace Slic3r { namespace sla {
// An enum to keep track of where the current points on the ModelObject came from.
enum class PointsStatus {
NoPoints, // No points were generated so far.
Generating, // The autogeneration algorithm triggered, but not yet finished.
AutoGenerated, // Points were autogenerated (i.e. copied from the backend).
UserModified // User has done some edits.
};
struct SupportPoint
{
Vec3f pos;
float head_front_radius;
bool is_new_island;
SupportPoint()
: pos(Vec3f::Zero()), head_front_radius(0.f), is_new_island(false)
{}
SupportPoint(float pos_x,
float pos_y,
float pos_z,
float head_radius,
bool new_island)
: pos(pos_x, pos_y, pos_z)
, head_front_radius(head_radius)
, is_new_island(new_island)
{}
SupportPoint(Vec3f position, float head_radius, bool new_island)
: pos(position)
, head_front_radius(head_radius)
, is_new_island(new_island)
{}
SupportPoint(Eigen::Matrix<float, 5, 1, Eigen::DontAlign> data)
: pos(data(0), data(1), data(2))
, head_front_radius(data(3))
, is_new_island(data(4) != 0.f)
{}
bool operator==(const SupportPoint &sp) const
{
float rdiff = std::abs(head_front_radius - sp.head_front_radius);
return (pos == sp.pos) && rdiff < float(EPSILON) &&
is_new_island == sp.is_new_island;
}
bool operator!=(const SupportPoint &sp) const { return !(sp == (*this)); }
template<class Archive> void serialize(Archive &ar)
{
ar(pos, head_front_radius, is_new_island);
}
};
using SupportPoints = std::vector<SupportPoint>;
}} // namespace Slic3r::sla
#endif // SUPPORTPOINT_HPP

View File

@ -3,7 +3,7 @@
#include <tbb/parallel_for.h>
#include "SLAAutoSupports.hpp"
#include "SupportPointGenerator.hpp"
#include "Model.hpp"
#include "ExPolygon.hpp"
#include "SVG.hpp"
@ -18,7 +18,7 @@
namespace Slic3r {
namespace sla {
/*float SLAAutoSupports::approximate_geodesic_distance(const Vec3d& p1, const Vec3d& p2, Vec3d& n1, Vec3d& n2)
/*float SupportPointGenerator::approximate_geodesic_distance(const Vec3d& p1, const Vec3d& p2, Vec3d& n1, Vec3d& n2)
{
n1.normalize();
n2.normalize();
@ -36,7 +36,7 @@ namespace sla {
}
float SLAAutoSupports::get_required_density(float angle) const
float SupportPointGenerator::get_required_density(float angle) const
{
// calculation would be density_0 * cos(angle). To provide one more degree of freedom, we will scale the angle
// to get the user-set density for 45 deg. So it ends up as density_0 * cos(K * angle).
@ -44,12 +44,12 @@ float SLAAutoSupports::get_required_density(float angle) const
return std::max(0.f, float(m_config.density_at_horizontal * cos(K*angle)));
}
float SLAAutoSupports::distance_limit(float angle) const
float SupportPointGenerator::distance_limit(float angle) const
{
return 1./(2.4*get_required_density(angle));
}*/
SLAAutoSupports::SLAAutoSupports(const sla::EigenMesh3D & emesh,
SupportPointGenerator::SupportPointGenerator(const sla::EigenMesh3D & emesh,
const std::vector<ExPolygons> &slices,
const std::vector<float> & heights,
const Config & config,
@ -64,7 +64,7 @@ SLAAutoSupports::SLAAutoSupports(const sla::EigenMesh3D & emesh,
project_onto_mesh(m_output);
}
void SLAAutoSupports::project_onto_mesh(std::vector<sla::SupportPoint>& points) const
void SupportPointGenerator::project_onto_mesh(std::vector<sla::SupportPoint>& points) const
{
// The function makes sure that all the points are really exactly placed on the mesh.
@ -99,14 +99,14 @@ void SLAAutoSupports::project_onto_mesh(std::vector<sla::SupportPoint>& points)
});
}
static std::vector<SLAAutoSupports::MyLayer> make_layers(
static std::vector<SupportPointGenerator::MyLayer> make_layers(
const std::vector<ExPolygons>& slices, const std::vector<float>& heights,
std::function<void(void)> throw_on_cancel)
{
assert(slices.size() == heights.size());
// Allocate empty layers.
std::vector<SLAAutoSupports::MyLayer> layers;
std::vector<SupportPointGenerator::MyLayer> layers;
layers.reserve(slices.size());
for (size_t i = 0; i < slices.size(); ++ i)
layers.emplace_back(i, heights[i]);
@ -122,7 +122,7 @@ static std::vector<SLAAutoSupports::MyLayer> make_layers(
if ((layer_id % 8) == 0)
// Don't call the following function too often as it flushes CPU write caches due to synchronization primitves.
throw_on_cancel();
SLAAutoSupports::MyLayer &layer = layers[layer_id];
SupportPointGenerator::MyLayer &layer = layers[layer_id];
const ExPolygons &islands = slices[layer_id];
//FIXME WTF?
const float height = (layer_id>2 ? heights[layer_id-3] : heights[0]-(heights[1]-heights[0]));
@ -143,8 +143,8 @@ static std::vector<SLAAutoSupports::MyLayer> make_layers(
if ((layer_id % 2) == 0)
// Don't call the following function too often as it flushes CPU write caches due to synchronization primitves.
throw_on_cancel();
SLAAutoSupports::MyLayer &layer_above = layers[layer_id];
SLAAutoSupports::MyLayer &layer_below = layers[layer_id - 1];
SupportPointGenerator::MyLayer &layer_above = layers[layer_id];
SupportPointGenerator::MyLayer &layer_below = layers[layer_id - 1];
//FIXME WTF?
const float layer_height = (layer_id!=0 ? heights[layer_id]-heights[layer_id-1] : heights[0]);
const float safe_angle = 5.f * (float(M_PI)/180.f); // smaller number - less supports
@ -152,8 +152,8 @@ static std::vector<SLAAutoSupports::MyLayer> make_layers(
const float slope_angle = 75.f * (float(M_PI)/180.f); // smaller number - less supports
const float slope_offset = float(scale_(layer_height / std::tan(slope_angle)));
//FIXME This has a quadratic time complexity, it will be excessively slow for many tiny islands.
for (SLAAutoSupports::Structure &top : layer_above.islands) {
for (SLAAutoSupports::Structure &bottom : layer_below.islands) {
for (SupportPointGenerator::Structure &top : layer_above.islands) {
for (SupportPointGenerator::Structure &bottom : layer_below.islands) {
float overlap_area = top.overlap_area(bottom);
if (overlap_area > 0) {
top.islands_below.emplace_back(&bottom, overlap_area);
@ -191,13 +191,13 @@ static std::vector<SLAAutoSupports::MyLayer> make_layers(
return layers;
}
void SLAAutoSupports::process(const std::vector<ExPolygons>& slices, const std::vector<float>& heights)
void SupportPointGenerator::process(const std::vector<ExPolygons>& slices, const std::vector<float>& heights)
{
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
std::vector<std::pair<ExPolygon, coord_t>> islands;
#endif /* SLA_AUTOSUPPORTS_DEBUG */
#endif /* SLA_SUPPORTPOINTGEN_DEBUG */
std::vector<SLAAutoSupports::MyLayer> layers = make_layers(slices, heights, m_throw_on_cancel);
std::vector<SupportPointGenerator::MyLayer> layers = make_layers(slices, heights, m_throw_on_cancel);
PointGrid3D point_grid;
point_grid.cell_size = Vec3f(10.f, 10.f, 10.f);
@ -206,8 +206,8 @@ void SLAAutoSupports::process(const std::vector<ExPolygons>& slices, const std::
double status = 0;
for (unsigned int layer_id = 0; layer_id < layers.size(); ++ layer_id) {
SLAAutoSupports::MyLayer *layer_top = &layers[layer_id];
SLAAutoSupports::MyLayer *layer_bottom = (layer_id > 0) ? &layers[layer_id - 1] : nullptr;
SupportPointGenerator::MyLayer *layer_top = &layers[layer_id];
SupportPointGenerator::MyLayer *layer_bottom = (layer_id > 0) ? &layers[layer_id - 1] : nullptr;
std::vector<float> support_force_bottom;
if (layer_bottom != nullptr) {
support_force_bottom.assign(layer_bottom->islands.size(), 0.f);
@ -263,13 +263,13 @@ void SLAAutoSupports::process(const std::vector<ExPolygons>& slices, const std::
status += increment;
m_statusfn(int(std::round(status)));
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
/*std::string layer_num_str = std::string((i<10 ? "0" : "")) + std::string((i<100 ? "0" : "")) + std::to_string(i);
output_expolygons(expolys_top, "top" + layer_num_str + ".svg");
output_expolygons(diff, "diff" + layer_num_str + ".svg");
if (!islands.empty())
output_expolygons(islands, "islands" + layer_num_str + ".svg");*/
#endif /* SLA_AUTOSUPPORTS_DEBUG */
#endif /* SLA_SUPPORTPOINTGEN_DEBUG */
}
}
@ -449,7 +449,7 @@ static inline std::vector<Vec2f> poisson_disk_from_samples(const std::vector<Vec
return out;
}
void SLAAutoSupports::uniformly_cover(const ExPolygons& islands, Structure& structure, PointGrid3D &grid3d, bool is_new_island, bool just_one)
void SupportPointGenerator::uniformly_cover(const ExPolygons& islands, Structure& structure, PointGrid3D &grid3d, bool is_new_island, bool just_one)
{
//int num_of_points = std::max(1, (int)((island.area()*pow(SCALING_FACTOR, 2) * m_config.tear_pressure)/m_config.support_force));
@ -488,7 +488,7 @@ void SLAAutoSupports::uniformly_cover(const ExPolygons& islands, Structure& stru
min_spacing = std::max(m_config.minimal_distance, min_spacing * coeff);
}
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
{
static int irun = 0;
Slic3r::SVG svg(debug_out_path("SLA_supports-uniformly_cover-%d.svg", irun ++), get_extents(islands));
@ -528,8 +528,8 @@ void remove_bottom_points(std::vector<SupportPoint> &pts, double gnd_lvl, double
pts.erase(endit, pts.end());
}
#ifdef SLA_AUTOSUPPORTS_DEBUG
void SLAAutoSupports::output_structures(const std::vector<Structure>& structures)
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
void SupportPointGenerator::output_structures(const std::vector<Structure>& structures)
{
for (unsigned int i=0 ; i<structures.size(); ++i) {
std::stringstream ss;
@ -538,7 +538,7 @@ void SLAAutoSupports::output_structures(const std::vector<Structure>& structures
}
}
void SLAAutoSupports::output_expolygons(const ExPolygons& expolys, const std::string &filename)
void SupportPointGenerator::output_expolygons(const ExPolygons& expolys, const std::string &filename)
{
BoundingBox bb(Point(-30000000, -30000000), Point(30000000, 30000000));
Slic3r::SVG svg_cummulative(filename, bb);

View File

@ -1,43 +1,45 @@
#ifndef SLAAUTOSUPPORTS_HPP_
#define SLAAUTOSUPPORTS_HPP_
#ifndef SLA_SUPPORTPOINTGENERATOR_HPP
#define SLA_SUPPORTPOINTGENERATOR_HPP
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SupportPoint.hpp>
#include <libslic3r/SLA/EigenMesh3D.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include <libslic3r/Point.hpp>
#include <libslic3r/TriangleMesh.hpp>
#include <libslic3r/SLA/SLACommon.hpp>
#include <boost/container/small_vector.hpp>
// #define SLA_AUTOSUPPORTS_DEBUG
// #define SLA_SUPPORTPOINTGEN_DEBUG
namespace Slic3r {
namespace sla {
namespace Slic3r { namespace sla {
class SLAAutoSupports {
class SupportPointGenerator {
public:
struct Config {
float density_relative {1.f};
float minimal_distance {1.f};
float head_diameter {0.4f};
///////////////
inline float support_force() const { return 7.7f / density_relative; } // a force one point can support (arbitrary force unit)
inline float tear_pressure() const { return 1.f; } // pressure that the display exerts (the force unit per mm2)
};
SLAAutoSupports(const sla::EigenMesh3D& emesh, const std::vector<ExPolygons>& slices,
const std::vector<float>& heights, const Config& config, std::function<void(void)> throw_on_cancel, std::function<void(int)> statusfn);
float density_relative {1.f};
float minimal_distance {1.f};
float head_diameter {0.4f};
///////////////
inline float support_force() const { return 7.7f / density_relative; } // a force one point can support (arbitrary force unit)
inline float tear_pressure() const { return 1.f; } // pressure that the display exerts (the force unit per mm2)
};
SupportPointGenerator(const EigenMesh3D& emesh, const std::vector<ExPolygons>& slices,
const std::vector<float>& heights, const Config& config, std::function<void(void)> throw_on_cancel, std::function<void(int)> statusfn);
const std::vector<SupportPoint>& output() { return m_output; }
struct MyLayer;
const std::vector<sla::SupportPoint>& output() { return m_output; }
struct MyLayer;
struct Structure {
Structure(MyLayer &layer, const ExPolygon& poly, const BoundingBox &bbox, const Vec2f &centroid, float area, float h) :
layer(&layer), polygon(&poly), bbox(bbox), centroid(centroid), area(area), height(h)
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
, unique_id(std::chrono::duration_cast<std::chrono::milliseconds>(std::chrono::system_clock::now().time_since_epoch()))
#endif /* SLA_AUTOSUPPORTS_DEBUG */
{}
#endif /* SLA_SUPPORTPOINTGEN_DEBUG */
{}
MyLayer *layer;
const ExPolygon* polygon = nullptr;
const BoundingBox bbox;
@ -49,24 +51,24 @@ public:
float supports_force_this_layer = 0.f;
float supports_force_inherited = 0.f;
float supports_force_total() const { return this->supports_force_this_layer + this->supports_force_inherited; }
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
std::chrono::milliseconds unique_id;
#endif /* SLA_AUTOSUPPORTS_DEBUG */
#endif /* SLA_SUPPORTPOINTGEN_DEBUG */
struct Link {
Link(Structure *island, float overlap_area) : island(island), overlap_area(overlap_area) {}
Link(Structure *island, float overlap_area) : island(island), overlap_area(overlap_area) {}
Structure *island;
float overlap_area;
};
#ifdef NDEBUG
// In release mode, use the optimized container.
// In release mode, use the optimized container.
boost::container::small_vector<Link, 4> islands_above;
boost::container::small_vector<Link, 4> islands_below;
#else
// In debug mode, use the standard vector, which is well handled by debugger visualizer.
std::vector<Link> islands_above;
std::vector<Link> islands_below;
// In debug mode, use the standard vector, which is well handled by debugger visualizer.
std::vector<Link> islands_above;
std::vector<Link> islands_below;
#endif
// Overhangs, that are dangling considerably.
ExPolygons dangling_areas;
@ -75,15 +77,15 @@ public:
// Overhangs, where the surface must slope.
ExPolygons overhangs_slopes;
float overhangs_area;
bool overlaps(const Structure &rhs) const {
return this->bbox.overlap(rhs.bbox) && (this->polygon->overlaps(*rhs.polygon) || rhs.polygon->overlaps(*this->polygon));
}
float overlap_area(const Structure &rhs) const {
double out = 0.;
if (this->bbox.overlap(rhs.bbox)) {
Polygons polys = intersection(to_polygons(*this->polygon), to_polygons(*rhs.polygon), false);
for (const Polygon &poly : polys)
Polygons polys = intersection(to_polygons(*this->polygon), to_polygons(*rhs.polygon), false);
for (const Polygon &poly : polys)
out += poly.area();
}
return float(out);
@ -96,13 +98,13 @@ public:
}
Polygons polygons_below() const {
size_t cnt = 0;
for (const Link &below : this->islands_below)
for (const Link &below : this->islands_below)
cnt += 1 + below.island->polygon->holes.size();
Polygons out;
out.reserve(cnt);
for (const Link &below : this->islands_below) {
for (const Link &below : this->islands_below) {
out.emplace_back(below.island->polygon->contour);
append(out, below.island->polygon->holes);
append(out, below.island->polygon->holes);
}
return out;
}
@ -116,19 +118,19 @@ public:
// Positive deficit of the supports. If negative, this area is well supported. If positive, more supports need to be added.
float support_force_deficit(const float tear_pressure) const { return this->area * tear_pressure - this->supports_force_total(); }
};
struct MyLayer {
MyLayer(const size_t layer_id, coordf_t print_z) : layer_id(layer_id), print_z(print_z) {}
MyLayer(const size_t layer_id, coordf_t print_z) : layer_id(layer_id), print_z(print_z) {}
size_t layer_id;
coordf_t print_z;
std::vector<Structure> islands;
};
struct RichSupportPoint {
Vec3f position;
Structure *island;
};
struct PointGrid3D {
struct GridHash {
std::size_t operator()(const Vec3i &cell_id) const {
@ -136,23 +138,23 @@ public:
}
};
typedef std::unordered_multimap<Vec3i, RichSupportPoint, GridHash> Grid;
Vec3f cell_size;
Grid grid;
Vec3i cell_id(const Vec3f &pos) {
return Vec3i(int(floor(pos.x() / cell_size.x())),
int(floor(pos.y() / cell_size.y())),
int(floor(pos.z() / cell_size.z())));
}
void insert(const Vec2f &pos, Structure *island) {
RichSupportPoint pt;
pt.position = Vec3f(pos.x(), pos.y(), float(island->layer->print_z));
pt.position = Vec3f(pos.x(), pos.y(), float(island->layer->print_z));
pt.island = island;
grid.emplace(cell_id(pt.position), pt);
}
bool collides_with(const Vec2f &pos, Structure *island, float radius) {
Vec3f pos3d(pos.x(), pos.y(), float(island->layer->print_z));
Vec3i cell = cell_id(pos3d);
@ -170,41 +172,39 @@ public:
}
return false;
}
private:
bool collides_with(const Vec3f &pos, float radius, Grid::const_iterator it_begin, Grid::const_iterator it_end) {
for (Grid::const_iterator it = it_begin; it != it_end; ++ it) {
float dist2 = (it->second.position - pos).squaredNorm();
float dist2 = (it->second.position - pos).squaredNorm();
if (dist2 < radius * radius)
return true;
}
return false;
}
};
private:
std::vector<sla::SupportPoint> m_output;
SLAAutoSupports::Config m_config;
std::vector<SupportPoint> m_output;
SupportPointGenerator::Config m_config;
void process(const std::vector<ExPolygons>& slices, const std::vector<float>& heights);
void uniformly_cover(const ExPolygons& islands, Structure& structure, PointGrid3D &grid3d, bool is_new_island = false, bool just_one = false);
void project_onto_mesh(std::vector<sla::SupportPoint>& points) const;
void project_onto_mesh(std::vector<SupportPoint>& points) const;
#ifdef SLA_AUTOSUPPORTS_DEBUG
#ifdef SLA_SUPPORTPOINTGEN_DEBUG
static void output_expolygons(const ExPolygons& expolys, const std::string &filename);
static void output_structures(const std::vector<Structure> &structures);
#endif // SLA_AUTOSUPPORTS_DEBUG
const sla::EigenMesh3D& m_emesh;
#endif // SLA_SUPPORTPOINTGEN_DEBUG
const EigenMesh3D& m_emesh;
std::function<void(void)> m_throw_on_cancel;
std::function<void(int)> m_statusfn;
};
void remove_bottom_points(std::vector<SupportPoint> &pts, double gnd_lvl, double tolerance);
} // namespace sla
} // namespace Slic3r
}} // namespace Slic3r::sla
#endif // SLAAUTOSUPPORTS_HPP_
#endif // SUPPORTPOINTGENERATOR_HPP

View File

@ -4,10 +4,10 @@
*/
#include <numeric>
#include "SLASupportTree.hpp"
#include "SLACommon.hpp"
#include "SLASpatIndex.hpp"
#include "SLASupportTreeBuilder.hpp"
#include <libslic3r/SLA/SupportTree.hpp>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SpatIndex.hpp>
#include <libslic3r/SLA/SupportTreeBuilder.hpp>
#include <libslic3r/MTUtils.hpp>
#include <libslic3r/ClipperUtils.hpp>

View File

@ -1,12 +1,15 @@
#ifndef SLASUPPORTTREE_HPP
#define SLASUPPORTTREE_HPP
#ifndef SLA_SUPPORTTREE_HPP
#define SLA_SUPPORTTREE_HPP
#include <vector>
#include <memory>
#include <Eigen/Geometry>
#include "SLACommon.hpp"
#include "SLAPad.hpp"
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/Pad.hpp>
#include <libslic3r/SLA/EigenMesh3D.hpp>
#include <libslic3r/SLA/SupportPoint.hpp>
#include <libslic3r/SLA/JobController.hpp>
namespace Slic3r {
@ -105,27 +108,6 @@ struct SupportConfig
enum class MeshType { Support, Pad };
/// A Control structure for the support calculation. Consists of the status
/// indicator callback and the stop condition predicate.
struct JobController
{
using StatusFn = std::function<void(unsigned, const std::string&)>;
using StopCond = std::function<bool(void)>;
using CancelFn = std::function<void(void)>;
// This will signal the status of the calculation to the front-end
StatusFn statuscb = [](unsigned, const std::string&){};
// Returns true if the calculation should be aborted.
StopCond stopcondition = [](){ return false; };
// Similar to cancel callback. This should check the stop condition and
// if true, throw an appropriate exception. (TriangleMeshSlicer needs this)
// consider it a hard abort. stopcondition is permits the algorithm to
// terminate itself
CancelFn cancelfn = [](){};
};
struct SupportableMesh
{
EigenMesh3D emesh;

View File

@ -1,5 +1,6 @@
#include "SLASupportTreeBuilder.hpp"
#include "SLASupportTreeBuildsteps.hpp"
#include <libslic3r/SLA/SupportTreeBuilder.hpp>
#include <libslic3r/SLA/SupportTreeBuildsteps.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
namespace Slic3r {
namespace sla {

View File

@ -1,10 +1,11 @@
#ifndef SUPPORTTREEBUILDER_HPP
#define SUPPORTTREEBUILDER_HPP
#ifndef SLA_SUPPORTTREEBUILDER_HPP
#define SLA_SUPPORTTREEBUILDER_HPP
#include "SLAConcurrency.hpp"
#include "SLACommon.hpp"
#include "SLASupportTree.hpp"
#include "SLAPad.hpp"
#include <libslic3r/SLA/Concurrency.hpp>
#include <libslic3r/SLA/Common.hpp>
#include <libslic3r/SLA/SupportTree.hpp>
#include <libslic3r/SLA/Contour3D.hpp>
#include <libslic3r/SLA/Pad.hpp>
#include <libslic3r/MTUtils.hpp>
namespace Slic3r {

View File

@ -1,4 +1,4 @@
#include "SLASupportTreeBuildsteps.hpp"
#include <libslic3r/SLA/SupportTreeBuildsteps.hpp>
#include <libnest2d/optimizers/nlopt/genetic.hpp>
#include <libnest2d/optimizers/nlopt/subplex.hpp>
@ -8,7 +8,7 @@ namespace Slic3r {
namespace sla {
SupportTreeBuildsteps::SupportTreeBuildsteps(SupportTreeBuilder & builder,
const SupportableMesh &sm)
const SupportableMesh &sm)
: m_cfg(sm.cfg)
, m_mesh(sm.emesh)
, m_support_pts(sm.pts)
@ -30,7 +30,7 @@ SupportTreeBuildsteps::SupportTreeBuildsteps(SupportTreeBuilder & builder,
}
bool SupportTreeBuildsteps::execute(SupportTreeBuilder & builder,
const SupportableMesh &sm)
const SupportableMesh &sm)
{
if(sm.pts.empty()) return false;

View File

@ -3,7 +3,8 @@
#include <cstdint>
#include "SLASupportTreeBuilder.hpp"
#include <libslic3r/SLA/SupportTreeBuilder.hpp>
#include <libslic3r/SLA/Clustering.hpp>
namespace Slic3r {
namespace sla {

View File

@ -1,7 +1,8 @@
#include "SLAPrint.hpp"
#include "SLA/SLASupportTree.hpp"
#include "SLA/SLAPad.hpp"
#include "SLA/SLAAutoSupports.hpp"
#include "SLA/SupportTree.hpp"
#include "SLA/Pad.hpp"
#include "SLA/SupportPointGenerator.hpp"
#include "SLA/Hollowing.hpp"
#include "ClipperUtils.hpp"
#include "Geometry.hpp"
#include "MTUtils.hpp"
@ -47,6 +48,14 @@ public:
}
};
class SLAPrintObject::HollowingData
{
public:
TriangleMesh interior;
// std::vector<drillpoints>
};
namespace {
// should add up to 100 (%)
@ -752,6 +761,29 @@ void SLAPrint::process()
// the coefficient that multiplies the per object status values which
// are set up for <0, 100>. They need to be scaled into the whole process
const double ostepd = (max_objstatus - min_objstatus) / (objcount * 100.0);
auto hollow_model = [](SLAPrintObject &po) {
if (!po.m_config.hollowing_enable.getBool()) {
BOOST_LOG_TRIVIAL(info) << "Skipping hollowing step!";
po.m_hollowing_data.reset();
return;
} else {
BOOST_LOG_TRIVIAL(info) << "Performing hollowing step!";
}
if (!po.m_hollowing_data)
po.m_hollowing_data.reset(new SLAPrintObject::HollowingData());
double thickness = po.m_config.hollowing_min_thickness.getFloat();
double quality = po.m_config.hollowing_quality.getFloat();
double closing_d = po.m_config.hollowing_closing_distance.getFloat();
po.m_hollowing_data->interior =
generate_interior(po.transformed_mesh(), {thickness, quality, closing_d});
if (po.m_hollowing_data->interior.empty())
BOOST_LOG_TRIVIAL(warning) << "Hollowed interior is empty!";
};
// The slicing will be performed on an imaginary 1D grid which starts from
// the bottom of the bounding box created around the supported model. So
@ -765,7 +797,20 @@ void SLAPrint::process()
// Slicing the model object. This method is oversimplified and needs to
// be compared with the fff slicing algorithm for verification
auto slice_model = [this, ilhs, ilh](SLAPrintObject& po) {
const TriangleMesh& mesh = po.transformed_mesh();
TriangleMesh hollowed_mesh;
bool is_hollowing = po.m_config.hollowing_enable.getBool() &&
po.m_hollowing_data;
if (is_hollowing) {
hollowed_mesh = po.transformed_mesh();
hollowed_mesh.merge(po.m_hollowing_data->interior);
hollowed_mesh.require_shared_vertices();
}
const TriangleMesh &mesh = is_hollowing ? hollowed_mesh :
po.transformed_mesh();
// We need to prepare the slice index...
@ -865,7 +910,7 @@ void SLAPrint::process()
const std::vector<float>& heights = po.m_model_height_levels;
this->throw_if_canceled();
SLAAutoSupports::Config config;
SupportPointGenerator::Config config;
const SLAPrintObjectConfig& cfg = po.config();
// the density config value is in percents:
@ -888,12 +933,9 @@ void SLAPrint::process()
// Construction of this object does the calculation.
this->throw_if_canceled();
SLAAutoSupports auto_supports(po.m_supportdata->emesh,
po.get_model_slices(),
heights,
config,
[this]() { throw_if_canceled(); },
statuscb);
SupportPointGenerator auto_supports(
po.m_supportdata->emesh, po.get_model_slices(), heights,
config, [this]() { throw_if_canceled(); }, statuscb);
// Now let's extract the result.
const std::vector<sla::SupportPoint>& points = auto_supports.output();
@ -1465,12 +1507,12 @@ void SLAPrint::process()
slaposFn pobj_program[] =
{
[](SLAPrintObject&){}, slice_model, [](SLAPrintObject&){}, support_points, support_tree, generate_pad, slice_supports
hollow_model, slice_model, [](SLAPrintObject&){}, support_points, support_tree, generate_pad, slice_supports
};
// We want to first process all objects...
std::vector<SLAPrintObjectStep> level1_obj_steps = {
slaposObjectSlice, slaposSupportPoints, slaposSupportTree, slaposPad
slaposHollowing, slaposObjectSlice, slaposSupportPoints, slaposSupportTree, slaposPad
};
// and then slice all supports to allow preview to be displayed ASAP
@ -1707,7 +1749,14 @@ bool SLAPrintObject::invalidate_state_by_config_options(const std::vector<t_conf
std::vector<SLAPrintObjectStep> steps;
bool invalidated = false;
for (const t_config_option_key &opt_key : opt_keys) {
if ( opt_key == "layer_height"
if ( opt_key == "hollowing_enable"
|| opt_key == "hollowing_min_thickness"
|| opt_key == "hollowing_quality"
|| opt_key == "hollowing_closing_distance"
) {
steps.emplace_back(slaposHollowing);
} else if (
opt_key == "layer_height"
|| opt_key == "faded_layers"
|| opt_key == "pad_enable"
|| opt_key == "pad_wall_thickness"
@ -1927,6 +1976,14 @@ const TriangleMesh& SLAPrintObject::pad_mesh() const
return EMPTY_MESH;
}
const TriangleMesh &SLAPrintObject::hollowed_interior_mesh() const
{
if (m_hollowing_data && m_config.hollowing_enable.getBool())
return m_hollowing_data->interior;
return EMPTY_MESH;
}
const TriangleMesh &SLAPrintObject::transformed_mesh() const {
// we need to transform the raw mesh...
// currently all the instances share the same x and y rotation and scaling

View File

@ -4,7 +4,7 @@
#include <mutex>
#include "PrintBase.hpp"
//#include "PrintExport.hpp"
#include "SLA/SLARasterWriter.hpp"
#include "SLA/RasterWriter.hpp"
#include "Point.hpp"
#include "MTUtils.hpp"
#include <libnest2d/backends/clipper/clipper_polygon.hpp>
@ -74,8 +74,11 @@ public:
// Support mesh is only valid if this->is_step_done(slaposSupportTree) is true.
const TriangleMesh& support_mesh() const;
// Get a pad mesh centered around origin in XY, and with zero rotation around Z applied.
// Support mesh is only valid if this->is_step_done(slaposBasePool) is true.
// Support mesh is only valid if this->is_step_done(slaposPad) is true.
const TriangleMesh& pad_mesh() const;
// Ready after this->is_step_done(slaposHollowing) is true
const TriangleMesh& hollowed_interior_mesh() const;
// This will return the transformed mesh which is cached
const TriangleMesh& transformed_mesh() const;
@ -288,9 +291,12 @@ private:
// Caching the transformed (m_trafo) raw mesh of the object
mutable CachedObject<TriangleMesh> m_transformed_rmesh;
class SupportData;
std::unique_ptr<SupportData> m_supportdata;
class HollowingData;
std::unique_ptr<HollowingData> m_hollowing_data;
};
using PrintObjects = std::vector<SLAPrintObject*>;

View File

@ -5362,6 +5362,8 @@ void GLCanvas3D::_load_sla_shells()
unsigned int initial_volumes_count = (unsigned int)m_volumes.volumes.size();
for (const SLAPrintObject::Instance& instance : obj->instances()) {
add_volume(*obj, 0, instance, obj->transformed_mesh(), GLVolume::MODEL_COLOR[0], true);
if (! obj->hollowed_interior_mesh().empty())
add_volume(*obj, -int(slaposHollowing), instance, obj->hollowed_interior_mesh(), GLVolume::MODEL_COLOR[0], false);
// Set the extruder_id and volume_id to achieve the same color as in the 3D scene when
// through the update_volumes_colors_by_extruder() call.
m_volumes.volumes.back()->extruder_id = obj->model_object()->volumes.front()->extruder_id();

View File

@ -98,6 +98,7 @@ ObjectList::ObjectList(wxWindow* parent) :
// ptSLA
CATEGORY_ICON[L("Supports")] = create_scaled_bitmap(nullptr, "support"/*"sla_supports"*/);
CATEGORY_ICON[L("Pad")] = create_scaled_bitmap(nullptr, "pad");
CATEGORY_ICON[L("Hollowing")] = create_scaled_bitmap(nullptr, "hollowing");
}
// create control

View File

@ -566,11 +566,9 @@ void GLGizmoHollow::on_update(const UpdateData& data)
}
}
void GLGizmoHollow::get_hollowing_parameters(TriangleMesh const** object_mesh, float& offset, float& adaptability) const
std::pair<const TriangleMesh *, sla::HollowingConfig> GLGizmoHollow::get_hollowing_parameters() const
{
offset = m_offset;
adaptability = m_adaptability;
*object_mesh = m_mesh;
return std::make_pair(m_mesh, sla::HollowingConfig{double(m_offset), double(m_accuracy), double(m_closing_d)});
}
void GLGizmoHollow::hollow_mesh()
@ -725,9 +723,12 @@ RENDER_AGAIN:
m_imgui->text("Offset: ");
ImGui::SameLine();
ImGui::SliderFloat(" ", &m_offset, 0.f, 5.f, "%.1f");
m_imgui->text("Adaptibility: ");
m_imgui->text("Quality: ");
ImGui::SameLine();
ImGui::SliderFloat(" ", &m_adaptability, 0.f, 1.f, "%.1f");
ImGui::SliderFloat(" ", &m_accuracy, 0.f, 1.f, "%.1f");
m_imgui->text("Closing distance: ");
ImGui::SameLine();
ImGui::SliderFloat(" ", &m_closing_d, 0.f, 10.f, "%.1f");
// Following is rendered in both editing and non-editing mode:
m_imgui->text("");

View File

@ -4,7 +4,7 @@
#include "GLGizmoBase.hpp"
#include "slic3r/GUI/GLSelectionRectangle.hpp"
#include "libslic3r/SLA/SLACommon.hpp"
#include <libslic3r/SLA/Hollowing.hpp>
#include <wx/dialog.h>
#include <cereal/types/vector.hpp>
@ -77,7 +77,7 @@ public:
void delete_selected_points(bool force = false);
ClippingPlane get_sla_clipping_plane() const;
void update_hollowed_mesh(std::unique_ptr<TriangleMesh> mesh);
void get_hollowing_parameters(TriangleMesh const** object_mesh, float& offset, float& adaptability) const;
std::pair<const TriangleMesh *, sla::HollowingConfig> get_hollowing_parameters() const;
bool is_selection_rectangle_dragging() const { return m_selection_rectangle.is_dragging(); }
@ -105,12 +105,13 @@ private:
float m_density_stash = 0.f; // and again
mutable std::vector<bool> m_selected; // which holes are currently selected
float m_offset = 2.f;
float m_adaptability = 1.f;
float m_offset = 2.0f;
float m_accuracy = 0.5f;
float m_closing_d = 2.f;
float m_clipping_plane_distance = 0.f;
std::unique_ptr<ClippingPlane> m_clipping_plane;
// This map holds all translated description texts, so they can be easily referenced during layout calculations
// etc. When language changes, GUI is recreated and this class constructed again, so the change takes effect.
std::map<std::string, wxString> m_desc;

View File

@ -4,7 +4,7 @@
#include "GLGizmoBase.hpp"
#include "slic3r/GUI/GLSelectionRectangle.hpp"
#include "libslic3r/SLA/SLACommon.hpp"
#include "libslic3r/SLA/Common.hpp"
#include <wx/dialog.h>
#include <cereal/types/vector.hpp>

View File

@ -3,7 +3,7 @@
#include "libslic3r/Point.hpp"
#include "libslic3r/Geometry.hpp"
#include "libslic3r/SLA/SLACommon.hpp"
#include "libslic3r/SLA/EigenMesh3D.hpp"
#include <cfloat>

View File

@ -33,12 +33,13 @@
#include "libslic3r/Format/3mf.hpp"
#include "libslic3r/GCode/PreviewData.hpp"
#include "libslic3r/Model.hpp"
#include "libslic3r/OpenVDBUtils.hpp"
#include "libslic3r/SLA/Hollowing.hpp"
#include "libslic3r/SLA/Rotfinder.hpp"
#include "libslic3r/SLA/SupportPoint.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Print.hpp"
#include "libslic3r/PrintConfig.hpp"
#include "libslic3r/SLAPrint.hpp"
#include "libslic3r/SLA/SLARotfinder.hpp"
#include "libslic3r/Utils.hpp"
//#include "libslic3r/ClipperUtils.hpp"
@ -1715,8 +1716,7 @@ struct Plater::priv
private:
std::unique_ptr<TriangleMesh> m_output;
const TriangleMesh* m_object_mesh = nullptr;
float m_offset = 0.f;
float m_adaptability = 0.f;
sla::HollowingConfig m_cfg;
};
// Jobs defined inside the group class will be managed so that only one can
@ -2864,22 +2864,22 @@ void Plater::priv::HollowJob::prepare()
const GLGizmosManager& gizmo_manager = plater().q->canvas3D()->get_gizmos_manager();
const GLGizmoHollow* gizmo_hollow = dynamic_cast<const GLGizmoHollow*>(gizmo_manager.get_current());
assert(gizmo_hollow);
gizmo_hollow->get_hollowing_parameters(&m_object_mesh, m_offset, m_adaptability);
auto hlw_data = gizmo_hollow->get_hollowing_parameters();
m_object_mesh = hlw_data.first;
m_cfg = hlw_data.second;
m_output.reset();
}
void Plater::priv::HollowJob::process()
{
Slic3r::sla::Contour3D imesh{*m_object_mesh};
auto ptr = meshToVolume(imesh, {});
sla::Contour3D omesh = volumeToMesh(*ptr, -m_offset, m_adaptability, true);
sla::JobController ctl;
TriangleMesh omesh = sla::generate_interior(*m_object_mesh, m_cfg, ctl);
if (omesh.empty()) return;
if (omesh.empty())
return;
imesh.merge(omesh);
m_output.reset(new TriangleMesh());
*m_output = sla::to_triangle_mesh(imesh);
m_output.reset(new TriangleMesh{*m_object_mesh});
m_output->merge(omesh);
m_output->require_shared_vertices();
}

View File

@ -496,6 +496,10 @@ const std::vector<std::string>& Preset::sla_print_options()
"pad_object_connector_stride",
"pad_object_connector_width",
"pad_object_connector_penetration",
"hollowing_enable",
"hollowing_min_thickness",
"hollowing_quality",
"hollowing_closing_distance",
"output_filename_format",
"default_sla_print_profile",
"compatible_printers",

View File

@ -3563,6 +3563,13 @@ void TabSLAPrint::build()
optgroup->append_single_option_line("pad_object_connector_stride");
optgroup->append_single_option_line("pad_object_connector_width");
optgroup->append_single_option_line("pad_object_connector_penetration");
page = add_options_page(_(L("Hollowing")), "hollowing");
optgroup = page->new_optgroup(_(L("Hollowing")));
optgroup->append_single_option_line("hollowing_enable");
optgroup->append_single_option_line("hollowing_min_thickness");
optgroup->append_single_option_line("hollowing_quality");
optgroup->append_single_option_line("hollowing_closing_distance");
page = add_options_page(_(L("Advanced")), "wrench");
optgroup = page->new_optgroup(_(L("Slicing")));

View File

@ -2,7 +2,7 @@
#include <fstream>
#include <catch2/catch.hpp>
#include "libslic3r/OpenVDBUtils.hpp"
#include "libslic3r/SLA/Hollowing.hpp"
#include <openvdb/tools/Filter.h>
#include "libslic3r/Format/OBJ.hpp"
@ -25,36 +25,16 @@ static Slic3r::TriangleMesh load_model(const std::string &obj_filename)
TEST_CASE("Negative 3D offset should produce smaller object.", "[Hollowing]")
{
Slic3r::TriangleMesh in_mesh = load_model("20mm_cube.obj");
in_mesh.scale(3.);
Slic3r::sla::Contour3D imesh = Slic3r::sla::Contour3D{in_mesh};
Benchmark bench;
bench.start();
openvdb::math::Transform tr;
auto ptr = Slic3r::meshToVolume(imesh, {}, 0.0f, 10.0f);
REQUIRE(ptr);
openvdb::tools::Filter<openvdb::FloatGrid>{*ptr}.gaussian(1, 3);
double iso_surface = -3.0;
double adaptivity = 0.5;
Slic3r::sla::Contour3D omesh = Slic3r::volumeToMesh(*ptr, iso_surface, adaptivity);
REQUIRE(!omesh.empty());
imesh.merge(omesh);
for (auto &p : imesh.points) p /= 3.;
Slic3r::TriangleMesh out_mesh = Slic3r::sla::generate_interior(in_mesh);
bench.stop();
std::cout << "Elapsed processing time: " << bench.getElapsedSec() << std::endl;
std::fstream merged_outfile("merged_out.obj", std::ios::out);
imesh.to_obj(merged_outfile);
std::fstream outfile("out.obj", std::ios::out);
omesh.to_obj(outfile);
in_mesh.merge(out_mesh);
in_mesh.require_shared_vertices();
in_mesh.WriteOBJFile("merged_out.obj");
}

View File

@ -11,11 +11,11 @@
#include "libslic3r/Format/OBJ.hpp"
#include "libslic3r/SLAPrint.hpp"
#include "libslic3r/TriangleMesh.hpp"
#include "libslic3r/SLA/SLAPad.hpp"
#include "libslic3r/SLA/SLASupportTreeBuilder.hpp"
#include "libslic3r/SLA/SLASupportTreeBuildsteps.hpp"
#include "libslic3r/SLA/SLAAutoSupports.hpp"
#include "libslic3r/SLA/SLARaster.hpp"
#include "libslic3r/SLA/Pad.hpp"
#include "libslic3r/SLA/SupportTreeBuilder.hpp"
#include "libslic3r/SLA/SupportTreeBuildsteps.hpp"
#include "libslic3r/SLA/SupportPointGenerator.hpp"
#include "libslic3r/SLA/Raster.hpp"
#include "libslic3r/SLA/ConcaveHull.hpp"
#include "libslic3r/MTUtils.hpp"
@ -231,11 +231,12 @@ void test_supports(const std::string & obj_filename,
sla::EigenMesh3D emesh{mesh};
// Create the support point generator
sla::SLAAutoSupports::Config autogencfg;
sla::SupportPointGenerator::Config autogencfg;
autogencfg.head_diameter = float(2 * supportcfg.head_front_radius_mm);
sla::SLAAutoSupports point_gen{emesh, out.model_slices, out.slicegrid,
autogencfg, [] {}, [](int) {}};
sla::SupportPointGenerator point_gen{emesh, out.model_slices,
out.slicegrid, autogencfg,
[] {}, [](int) {}};
// Get the calculated support points.
std::vector<sla::SupportPoint> support_points = point_gen.output();