Useful backend improvements from sla volumes branch

This commit is contained in:
tamasmeszaros 2022-10-18 13:18:02 +02:00
parent 9a682a10cb
commit 2144f81bf1
25 changed files with 1126 additions and 429 deletions

View File

@ -69,7 +69,6 @@ public:
template<class M> void AABBMesh::init(const M &mesh, bool calculate_epsilon)
{
BoundingBoxf3 bb = bounding_box(mesh);
m_ground_level += bb.min(Z);
// Build the AABB accelaration tree
m_aabb->init(*m_tm, calculate_epsilon);
@ -97,7 +96,6 @@ AABBMesh::~AABBMesh() {}
AABBMesh::AABBMesh(const AABBMesh &other)
: m_tm(other.m_tm)
, m_ground_level(other.m_ground_level)
, m_aabb(new AABBImpl(*other.m_aabb))
, m_vfidx{other.m_vfidx}
, m_fnidx{other.m_fnidx}
@ -106,7 +104,6 @@ AABBMesh::AABBMesh(const AABBMesh &other)
AABBMesh &AABBMesh::operator=(const AABBMesh &other)
{
m_tm = other.m_tm;
m_ground_level = other.m_ground_level;
m_aabb.reset(new AABBImpl(*other.m_aabb));
m_vfidx = other.m_vfidx;
m_fnidx = other.m_fnidx;

View File

@ -28,7 +28,7 @@ class AABBMesh {
class AABBImpl;
const indexed_triangle_set* m_tm;
double m_ground_level = 0/*, m_gnd_offset = 0*/;
// double m_ground_level = 0/*, m_gnd_offset = 0*/;
std::unique_ptr<AABBImpl> m_aabb;
VertexFaceIndex m_vfidx; // vertex-face index
@ -57,7 +57,7 @@ public:
~AABBMesh();
inline double ground_level() const { return m_ground_level /*+ m_gnd_offset*/; }
// 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; }

View File

@ -11,7 +11,7 @@ endif ()
set(OpenVDBUtils_SOURCES "")
if (TARGET OpenVDB::openvdb)
set(OpenVDBUtils_SOURCES OpenVDBUtils.cpp OpenVDBUtils.hpp)
set(OpenVDBUtils_SOURCES OpenVDBUtils.cpp OpenVDBUtils.hpp OpenVDBUtilsLegacy.hpp)
endif()
set(SLIC3R_SOURCES
@ -39,6 +39,11 @@ set(SLIC3R_SOURCES
Color.hpp
Config.cpp
Config.hpp
CSGMesh/CSGMesh.hpp
CSGMesh/SliceCSGMesh.hpp
CSGMesh/ModelToCSGMesh.hpp
CSGMesh/PerformCSGMeshBooleans.hpp
CSGMesh/VoxelizeCSGMesh.hpp
EdgeGrid.cpp
EdgeGrid.hpp
ElephantFootCompensation.cpp

View File

@ -0,0 +1,76 @@
#ifndef CSGMESH_HPP
#define CSGMESH_HPP
#include <libslic3r/MTUtils.hpp> // for AnyPtr
#include <admesh/stl.h>
namespace Slic3r { namespace csg {
// A CSGPartT should be an object that can provide at least a mesh + trafo and an
// associated csg operation. A collection of CSGPartT objects can then
// be interpreted as one model and used in various contexts. It can be assembled
// with CGAL or OpenVDB, rendered with OpenCSG or provided to a ray-tracer to
// deal with various parts of it according to the supported CSG types...
//
// A few simple templated interface functions are provided here and a default
// CSGPart class that implements the necessary means to be usable as a
// CSGPartT object.
// Supported CSG operation types
enum class CSGType { Union, Difference, Intersection };
// Get the CSG operation of the part. Can be overriden for any type
template<class CSGPartT> CSGType get_operation(const CSGPartT &part)
{
return part.operation;
}
// Get the mesh for the part. Can be overriden for any type
template<class CSGPartT>
const indexed_triangle_set *get_mesh(const CSGPartT &part)
{
return part.its_ptr.get();
}
// Get the transformation associated with the mesh inside a CSGPartT object.
// Can be overriden for any type.
template<class CSGPartT>
Transform3f get_transform(const CSGPartT &part)
{
return part.trafo;
}
// Provide default overloads for indexed_triangle_set to be usable as a plain
// CSGPart with an implicit union operation
inline CSGType get_operation(const indexed_triangle_set &part)
{
return CSGType::Union;
}
inline const indexed_triangle_set * get_mesh(const indexed_triangle_set &part)
{
return &part;
}
inline Transform3f get_transform(const indexed_triangle_set &part)
{
return Transform3f::Identity();
}
// Default implementation
struct CSGPart {
AnyPtr<const indexed_triangle_set> its_ptr;
Transform3f trafo;
CSGType operation;
CSGPart(AnyPtr<const indexed_triangle_set> ptr = {},
CSGType op = CSGType::Union,
const Transform3f &tr = Transform3f::Identity())
: its_ptr{std::move(ptr)}, operation{op}, trafo{tr}
{}
};
}} // namespace Slic3r::csg
#endif // CSGMESH_HPP

View File

@ -0,0 +1,58 @@
#ifndef MODELTOCSGMESH_HPP
#define MODELTOCSGMESH_HPP
#include "CSGMesh.hpp"
#include "libslic3r/Model.hpp"
#include "libslic3r/SLA/Hollowing.hpp"
namespace Slic3r { namespace csg {
enum ModelParts {
mpartsPositive = 1,
mpartsNegative = 2,
mpartsDrillHoles = 4
};
template<class OutIt>
void model_to_csgmesh(const ModelObject &mo,
const Transform3d &trafo,
OutIt out,
// values of ModelParts ORed
int parts_to_include = mpartsPositive
)
{
bool do_positives = parts_to_include & mpartsPositive;
bool do_negatives = parts_to_include & mpartsNegative;
bool do_drillholes = parts_to_include & mpartsDrillHoles;
for (const ModelVolume *vol : mo.volumes) {
if (vol && vol->mesh_ptr() &&
((do_positives && vol->is_model_part()) ||
(do_negatives && vol->is_negative_volume()))) {
CSGPart part{&(vol->mesh().its),
vol->is_model_part() ? CSGType::Union : CSGType::Difference,
(trafo * vol->get_matrix()).cast<float>()};
*out = std::move(part);
++out;
}
}
if (do_drillholes) {
sla::DrainHoles drainholes = sla::transformed_drainhole_points(mo, trafo);
for (const sla::DrainHole &dhole : drainholes) {
CSGPart part{std::make_unique<const indexed_triangle_set>(
dhole.to_mesh()),
CSGType::Difference};
*out = std::move(part);
++out;
}
}
}
}} // namespace Slic3r::csg
#endif // MODELTOCSGMESH_HPP

View File

@ -0,0 +1,19 @@
#ifndef PERFORMCSGMESHBOOLEANS_HPP
#define PERFORMCSGMESHBOOLEANS_HPP
#include "CSGMesh.hpp"
#include "libslic3r/MeshBoolean.hpp"
namespace Slic3r {
template<class It>
void perform_csgmesh_booleans(MeshBoolean::cgal::CGALMesh &cgalm,
const Range<It> &csg)
{
}
} // namespace Slic3r
#endif // PERFORMCSGMESHBOOLEANS_HPP

View File

@ -0,0 +1,56 @@
#ifndef SLICECSGMESH_HPP
#define SLICECSGMESH_HPP
#include "CSGMesh.hpp"
#include "libslic3r/TriangleMeshSlicer.hpp"
#include "libslic3r/ClipperUtils.hpp"
namespace Slic3r { namespace csg {
template<class ItCSG>
std::vector<ExPolygons> slice_csgmesh_ex(
const Range<ItCSG> &csg,
const std::vector<float> &slicegrid,
const MeshSlicingParamsEx &params,
const std::function<void()> &throw_on_cancel = [] {})
{
std::vector<ExPolygons> ret(slicegrid.size());
MeshSlicingParamsEx params_cpy = params;
auto trafo = params.trafo;
for (const auto &m : csg) {
const indexed_triangle_set *its = csg::get_mesh(m);
if (!its)
continue;
params_cpy.trafo = trafo * csg::get_transform(m).template cast<double>();
std::vector<ExPolygons> slices = slice_mesh_ex(*its,
slicegrid, params_cpy,
throw_on_cancel);
assert(slices.size() == slicegrid.size());
for (size_t i = 0; i < slicegrid.size(); ++i) {
switch(get_operation(m)) {
case CSGType::Union:
for (ExPolygon &expoly : slices[i])
ret[i].emplace_back(std::move(expoly));
ret[i] = union_ex(ret[i]);
break;
case CSGType::Difference:
ret[i] = diff_ex(ret[i], slices[i]);
break;
case CSGType::Intersection:
ret[i] = intersection_ex(ret[i], slices[i]);
break;
}
}
}
return ret;
}
}} // namespace Slic3r::csg
#endif // SLICECSGMESH_HPP

View File

@ -0,0 +1,85 @@
#ifndef VOXELIZECSGMESH_HPP
#define VOXELIZECSGMESH_HPP
#include "CSGMesh.hpp"
#include "libslic3r/OpenVDBUtils.hpp"
namespace Slic3r { namespace csg {
class VoxelizeParams {
float m_voxel_scale = 1.f;
float m_exterior_bandwidth = 3.0f;
float m_interior_bandwidth = 3.0f;
public:
float voxel_scale() const noexcept { return m_voxel_scale; }
float exterior_bandwidth() const noexcept { return m_exterior_bandwidth; }
float interior_bandwidth() const noexcept { return m_interior_bandwidth; }
VoxelizeParams &voxel_scale(float val) noexcept
{
m_voxel_scale = val;
return *this;
}
VoxelizeParams &exterior_bandwidth(float val) noexcept
{
m_exterior_bandwidth = val;
return *this;
}
VoxelizeParams &interior_bandwidth(float val) noexcept
{
m_interior_bandwidth = val;
return *this;
}
};
// This method can be overriden when a specific CSGPart type supports caching
// of the voxel grid
template<class CSGPartT>
VoxelGridPtr get_voxelgrid(const CSGPartT &csgpart, const VoxelizeParams &params)
{
const indexed_triangle_set *its = csg::get_mesh(csgpart);
VoxelGridPtr ret;
if (its)
ret = mesh_to_grid(*csg::get_mesh(csgpart),
csg::get_transform(csgpart),
params.voxel_scale(),
params.exterior_bandwidth(),
params.interior_bandwidth());
return ret;
}
template<class It>
VoxelGridPtr voxelize_csgmesh(const Range<It> &csgrange,
const VoxelizeParams &params = {})
{
VoxelGridPtr ret;
for (auto &csgpart : csgrange) {
VoxelGridPtr partgrid = get_voxelgrid(csgpart, params);
if (!ret && get_operation(csgpart) == CSGType::Union) {
ret = std::move(partgrid);
} else if (ret) {
switch (get_operation(csgpart)) {
case CSGType::Union:
grid_union(*ret, *partgrid);
break;
case CSGType::Difference:
grid_difference(*ret, *partgrid);
break;
case CSGType::Intersection:
grid_intersection(*ret, *partgrid);
break;
}
}
}
return ret;
}
}} // namespace Slic3r::csg
#endif // VOXELIZECSGMESH_HPP

View File

@ -8,6 +8,7 @@
#include <vector>
#include <algorithm>
#include <cmath>
#include <boost/variant.hpp>
#include "libslic3r.h"
@ -136,6 +137,88 @@ inline std::vector<ArithmeticOnly<T>> grid(const T &start,
return vals;
}
// A general purpose pointer holder that can hold any type of smart pointer
// or raw pointer which can own or not own any object they point to.
// In case a raw pointer is stored, it is not destructed so ownership is
// assumed to be foreign.
//
// The stored pointer is not checked for being null when dereferenced.
//
// This is a movable only object due to the fact that it can possibly hold
// a unique_ptr which a non-copy.
template<class T>
class AnyPtr {
enum { RawPtr, UPtr, ShPtr, WkPtr };
boost::variant<T*, std::unique_ptr<T>, std::shared_ptr<T>, std::weak_ptr<T>> ptr;
template<class Self> static T *get_ptr(Self &&s)
{
switch (s.ptr.which()) {
case RawPtr: return boost::get<T *>(s.ptr);
case UPtr: return boost::get<std::unique_ptr<T>>(s.ptr).get();
case ShPtr: return boost::get<std::shared_ptr<T>>(s.ptr).get();
case WkPtr: {
auto shptr = boost::get<std::weak_ptr<T>>(s.ptr).lock();
return shptr.get();
}
}
return nullptr;
}
public:
template<class TT = T, class = std::enable_if_t<std::is_convertible_v<TT, T>>>
AnyPtr(TT *p = nullptr) : ptr{p}
{}
template<class TT, class = std::enable_if_t<std::is_convertible_v<TT, T>>>
AnyPtr(std::unique_ptr<TT> p) : ptr{std::unique_ptr<T>(std::move(p))}
{}
template<class TT, class = std::enable_if_t<std::is_convertible_v<TT, T>>>
AnyPtr(std::shared_ptr<TT> p) : ptr{std::shared_ptr<T>(std::move(p))}
{}
template<class TT, class = std::enable_if_t<std::is_convertible_v<TT, T>>>
AnyPtr(std::weak_ptr<TT> p) : ptr{std::weak_ptr<T>(std::move(p))}
{}
~AnyPtr() = default;
AnyPtr(AnyPtr &&other) noexcept : ptr{std::move(other.ptr)} {}
AnyPtr(const AnyPtr &other) = delete;
AnyPtr &operator=(AnyPtr &&other) noexcept { ptr = std::move(other.ptr); return *this; }
AnyPtr &operator=(const AnyPtr &other) = delete;
AnyPtr &operator=(T *p) { ptr = p; return *this; }
AnyPtr &operator=(std::unique_ptr<T> p) { ptr = std::move(p); return *this; }
AnyPtr &operator=(std::shared_ptr<T> p) { ptr = p; return *this; }
AnyPtr &operator=(std::weak_ptr<T> p) { ptr = std::move(p); return *this; }
const T &operator*() const { return *get_ptr(*this); }
T &operator*() { return *get_ptr(*this); }
T *operator->() { return get_ptr(*this); }
const T *operator->() const { return get_ptr(*this); }
T *get() { return get_ptr(*this); }
const T *get() const { return get_ptr(*this); }
operator bool() const
{
switch (ptr.which()) {
case RawPtr: return bool(boost::get<T *>(ptr));
case UPtr: return bool(boost::get<std::unique_ptr<T>>(ptr));
case ShPtr: return bool(boost::get<std::shared_ptr<T>>(ptr));
case WkPtr: {
auto shptr = boost::get<std::weak_ptr<T>>(ptr).lock();
return bool(shptr);
}
}
return false;
}
};
} // namespace Slic3r
#endif // MTUTILS_HPP

View File

@ -108,6 +108,21 @@ template<class IndexT> struct ItsNeighborsWrapper
const auto& get_index() const noexcept { return index_ref; }
};
// Can be used as the second argument to its_split to apply a functor on each
// part, instead of collecting them into a container.
template<class Fn>
struct SplitOutputFn {
Fn fn;
SplitOutputFn(Fn f): fn{std::move(f)} {}
SplitOutputFn &operator *() { return *this; }
void operator=(indexed_triangle_set &&its) { fn(std::move(its)); }
void operator=(indexed_triangle_set &its) { fn(its); }
SplitOutputFn& operator++() { return *this; };
};
// Splits a mesh into multiple meshes when possible.
template<class Its, class OutputIt>
void its_split(const Its &m, OutputIt out_it)
@ -155,7 +170,8 @@ void its_split(const Its &m, OutputIt out_it)
mesh.indices.emplace_back(new_face);
}
out_it = std::move(mesh);
*out_it = std::move(mesh);
++out_it;
}
}

View File

@ -6,6 +6,7 @@
#pragma warning(push)
#pragma warning(disable : 4146)
#endif // _MSC_VER
#include <openvdb/openvdb.h>
#include <openvdb/tools/MeshToVolume.h>
#ifdef _MSC_VER
#pragma warning(pop)
@ -16,14 +17,44 @@
#include <openvdb/tools/LevelSetRebuild.h>
#include <openvdb/tools/FastSweeping.h>
//#include "MTUtils.hpp"
namespace Slic3r {
struct VoxelGrid
{
openvdb::FloatGrid grid;
mutable std::optional<openvdb::FloatGrid::ConstAccessor> accessor;
template<class...Args>
VoxelGrid(Args &&...args): grid{std::forward<Args>(args)...} {}
};
void VoxelGridDeleter::operator()(VoxelGrid *ptr) { delete ptr; }
// Similarly to std::make_unique()
template<class...Args>
VoxelGridPtr make_voxelgrid(Args &&...args)
{
VoxelGrid *ptr = nullptr;
try {
ptr = new VoxelGrid(std::forward<Args>(args)...);
} catch(...) {
delete ptr;
}
return VoxelGridPtr{ptr};
}
template VoxelGridPtr make_voxelgrid<>();
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])}; }
class TriangleMeshDataAdapter {
public:
const indexed_triangle_set &its;
float voxel_scale;
Transform3d trafo;
size_t polygonCount() const { return its.indices.size(); }
size_t pointCount() const { return its.vertices.size(); }
@ -35,19 +66,19 @@ public:
void getIndexSpacePoint(size_t n, size_t v, openvdb::Vec3d& pos) const
{
auto vidx = size_t(its.indices[n](Eigen::Index(v)));
Slic3r::Vec3d p = its.vertices[vidx].cast<double>() * voxel_scale;
Slic3r::Vec3d p = trafo * its.vertices[vidx].cast<double>();
pos = {p.x(), p.y(), p.z()};
}
TriangleMeshDataAdapter(const indexed_triangle_set &m, float voxel_sc = 1.f)
: its{m}, voxel_scale{voxel_sc} {};
TriangleMeshDataAdapter(const indexed_triangle_set &m, const Transform3d tr = Transform3d::Identity())
: its{m}, trafo{tr} {}
};
openvdb::FloatGrid::Ptr mesh_to_grid(const indexed_triangle_set & mesh,
const openvdb::math::Transform &tr,
float voxel_scale,
float exteriorBandWidth,
float interiorBandWidth)
VoxelGridPtr mesh_to_grid(const indexed_triangle_set &mesh,
const Transform3f &tr,
float voxel_scale,
float exteriorBandWidth,
float interiorBandWidth)
{
// Might not be needed but this is now proven to be working
openvdb::initialize();
@ -55,51 +86,47 @@ openvdb::FloatGrid::Ptr mesh_to_grid(const indexed_triangle_set & mesh,
std::vector<indexed_triangle_set> meshparts = its_split(mesh);
auto it = std::remove_if(meshparts.begin(), meshparts.end(),
[](auto &m) { return its_volume(m) < EPSILON; });
[](auto &m) {
return its_volume(m) < EPSILON;
});
meshparts.erase(it, meshparts.end());
Transform3d trafo = tr.cast<double>();
trafo.prescale(voxel_scale);
openvdb::FloatGrid::Ptr grid;
for (auto &m : meshparts) {
auto subgrid = openvdb::tools::meshToVolume<openvdb::FloatGrid>(
TriangleMeshDataAdapter{m, voxel_scale}, tr, 1.f, 1.f);
TriangleMeshDataAdapter{m, trafo}, {},
exteriorBandWidth, interiorBandWidth);
if (grid && subgrid) openvdb::tools::csgUnion(*grid, *subgrid);
else if (subgrid) grid = std::move(subgrid);
if (grid && subgrid)
openvdb::tools::csgUnion(*grid, *subgrid);
else if (subgrid)
grid = std::move(subgrid);
}
if (meshparts.size() > 1) {
// This is needed to avoid various artefacts on multipart meshes.
// TODO: replace with something faster
grid = openvdb::tools::levelSetRebuild(*grid, 0., 1.f, 1.f);
}
if(meshparts.empty()) {
if (meshparts.empty()) {
// Splitting failed, fall back to hollow the original mesh
grid = openvdb::tools::meshToVolume<openvdb::FloatGrid>(
TriangleMeshDataAdapter{mesh}, tr, 1.f, 1.f);
TriangleMeshDataAdapter{mesh, trafo}, {}, exteriorBandWidth,
interiorBandWidth);
}
constexpr int DilateIterations = 1;
grid = openvdb::tools::dilateSdf(
*grid, interiorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_LESS_THAN_ISOVALUE);
grid = openvdb::tools::dilateSdf(
*grid, exteriorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_GREATER_THAN_ISOVALUE);
grid->transform().preScale(1./voxel_scale);
grid->insertMeta("voxel_scale", openvdb::FloatMetadata(voxel_scale));
return grid;
VoxelGridPtr ret = make_voxelgrid(std::move(*grid));
return ret;
}
indexed_triangle_set grid_to_mesh(const openvdb::FloatGrid &grid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
indexed_triangle_set grid_to_mesh(const VoxelGrid &vgrid,
double isovalue,
double adaptivity,
bool relaxDisorientedTriangles)
{
openvdb::initialize();
@ -107,51 +134,147 @@ indexed_triangle_set grid_to_mesh(const openvdb::FloatGrid &grid,
std::vector<openvdb::Vec3I> triangles;
std::vector<openvdb::Vec4I> quads;
auto &grid = vgrid.grid;
openvdb::tools::volumeToMesh(grid, points, triangles, quads, isovalue,
adaptivity, relaxDisorientedTriangles);
float scale = 1.;
try {
scale = grid.template metaValue<float>("voxel_scale");
} catch (...) { }
indexed_triangle_set ret;
ret.vertices.reserve(points.size());
ret.indices.reserve(triangles.size() + quads.size() * 2);
for (auto &v : points) ret.vertices.emplace_back(to_vec3f(v) / scale);
for (auto &v : points) ret.vertices.emplace_back(to_vec3f(v) /*/ scale*/);
for (auto &v : triangles) ret.indices.emplace_back(to_vec3i(v));
for (auto &quad : quads) {
ret.indices.emplace_back(quad(0), quad(1), quad(2));
ret.indices.emplace_back(quad(2), quad(3), quad(0));
ret.indices.emplace_back(quad(2), quad(1), quad(0));
ret.indices.emplace_back(quad(0), quad(3), quad(2));
}
return ret;
}
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid,
double iso,
double er,
double ir)
VoxelGridPtr dilate_grid(const VoxelGrid &vgrid,
float exteriorBandWidth,
float interiorBandWidth)
{
auto new_grid = openvdb::tools::levelSetRebuild(grid, float(iso),
float(er), float(ir));
constexpr int DilateIterations = 1;
openvdb::FloatGrid::Ptr new_grid;
float scale = get_voxel_scale(vgrid);
if (interiorBandWidth > 0.f)
new_grid = openvdb::tools::dilateSdf(
vgrid.grid, scale * interiorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_LESS_THAN_ISOVALUE);
auto &arg = new_grid? *new_grid : vgrid.grid;
if (exteriorBandWidth > 0.f)
new_grid = openvdb::tools::dilateSdf(
arg, scale * exteriorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_GREATER_THAN_ISOVALUE);
VoxelGridPtr ret;
if (new_grid)
ret = make_voxelgrid(std::move(*new_grid));
else
ret = make_voxelgrid(vgrid.grid);
// Copies voxel_scale metadata, if it exists.
new_grid->insertMeta(*grid.deepCopyMeta());
ret->grid.insertMeta(*vgrid.grid.deepCopyMeta());
return new_grid;
return ret;
}
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid,
double iso)
VoxelGridPtr redistance_grid(const VoxelGrid &vgrid,
float iso,
float er,
float ir)
{
auto new_grid = openvdb::tools::levelSetRebuild(grid, float(iso));
auto new_grid = openvdb::tools::levelSetRebuild(vgrid.grid, iso, er, ir);
// Copies voxel_scale metadata, if it exists.
new_grid->insertMeta(*grid.deepCopyMeta());
auto ret = make_voxelgrid(std::move(*new_grid));
return new_grid;
// Copies voxel_scale metadata, if it exists.
ret->grid.insertMeta(*vgrid.grid.deepCopyMeta());
return ret;
}
VoxelGridPtr redistance_grid(const VoxelGrid &vgrid, float iso)
{
auto new_grid = openvdb::tools::levelSetRebuild(vgrid.grid, iso);
auto ret = make_voxelgrid(std::move(*new_grid));
// Copies voxel_scale metadata, if it exists.
ret->grid.insertMeta(*vgrid.grid.deepCopyMeta());
return ret;
}
void grid_union(VoxelGrid &grid, VoxelGrid &arg)
{
openvdb::tools::csgUnion(grid.grid, arg.grid);
}
void grid_difference(VoxelGrid &grid, VoxelGrid &arg)
{
openvdb::tools::csgDifference(grid.grid, arg.grid);
}
void grid_intersection(VoxelGrid &grid, VoxelGrid &arg)
{
openvdb::tools::csgIntersection(grid.grid, arg.grid);
}
void reset_accessor(const VoxelGrid &vgrid)
{
vgrid.accessor = vgrid.grid.getConstAccessor();
}
double get_distance_raw(const Vec3f &p, const VoxelGrid &vgrid)
{
if (!vgrid.accessor)
reset_accessor(vgrid);
auto v = (p).cast<double>();
auto grididx = vgrid.grid.transform().worldToIndexCellCentered(
{v.x(), v.y(), v.z()});
return vgrid.accessor->getValue(grididx) ;
}
float get_voxel_scale(const VoxelGrid &vgrid)
{
float scale = 1.;
try {
scale = vgrid.grid.template metaValue<float>("voxel_scale");
} catch (...) { }
return scale;
}
VoxelGridPtr clone(const VoxelGrid &grid)
{
return make_voxelgrid(grid);
}
void rescale_grid(VoxelGrid &grid, float scale)
{/*
float old_scale = get_voxel_scale(grid);
float nscale = scale / old_scale;*/
// auto tr = openvdb::math::Transform::createLinearTransform(scale);
grid.grid.transform().preScale(scale);
// grid.grid.insertMeta("voxel_scale", openvdb::FloatMetadata(nscale));
// grid.grid.setTransform(tr);
}
} // namespace Slic3r

View File

@ -3,21 +3,25 @@
#include <libslic3r/TriangleMesh.hpp>
#ifdef _MSC_VER
// Suppress warning C4146 in include/gmp.h(2177,31): unary minus operator applied to unsigned type, result still unsigned
#pragma warning(push)
#pragma warning(disable : 4146)
#endif // _MSC_VER
#include <openvdb/openvdb.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif // _MSC_VER
namespace Slic3r {
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])}; }
struct VoxelGrid;
struct VoxelGridDeleter { void operator()(VoxelGrid *ptr); };
using VoxelGridPtr = std::unique_ptr<VoxelGrid, VoxelGridDeleter>;
// This is like std::make_unique for a voxelgrid
template<class... Args> VoxelGridPtr make_voxelgrid(Args &&...args);
// Default constructed voxelgrid can be obtained this way.
extern template VoxelGridPtr make_voxelgrid<>();
void reset_accessor(const VoxelGrid &vgrid);
double get_distance_raw(const Vec3f &p, const VoxelGrid &interior);
float get_voxel_scale(const VoxelGrid &grid);
VoxelGridPtr clone(const VoxelGrid &grid);
// Here voxel_scale defines the scaling of voxels which affects the voxel count.
// 1.0 value means a voxel for every unit cube. 2 means the model is scaled to
@ -26,24 +30,33 @@ inline Vec3i to_vec3i(const openvdb::Vec3I &v) { return Vec3i{int(v[0]), int(v[1
// achievable through the Transform parameter. (TODO: or is it?)
// The resulting grid will contain the voxel_scale in its metadata under the
// "voxel_scale" key to be used in grid_to_mesh function.
openvdb::FloatGrid::Ptr mesh_to_grid(const indexed_triangle_set & mesh,
const openvdb::math::Transform &tr = {},
float voxel_scale = 1.f,
float exteriorBandWidth = 3.0f,
float interiorBandWidth = 3.0f);
VoxelGridPtr mesh_to_grid(const indexed_triangle_set &mesh,
const Transform3f &tr = Transform3f::Identity(),
float voxel_scale = 1.f,
float exteriorBandWidth = 3.0f,
float interiorBandWidth = 3.0f);
indexed_triangle_set grid_to_mesh(const openvdb::FloatGrid &grid,
double isovalue = 0.0,
double adaptivity = 0.0,
indexed_triangle_set grid_to_mesh(const VoxelGrid &grid,
double isovalue = 0.0,
double adaptivity = 0.0,
bool relaxDisorientedTriangles = true);
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid,
double iso);
VoxelGridPtr dilate_grid(const VoxelGrid &grid,
float exteriorBandWidth = 3.0f,
float interiorBandWidth = 3.0f);
openvdb::FloatGrid::Ptr redistance_grid(const openvdb::FloatGrid &grid,
double iso,
double ext_range,
double int_range);
VoxelGridPtr redistance_grid(const VoxelGrid &grid, float iso);
VoxelGridPtr redistance_grid(const VoxelGrid &grid,
float iso,
float ext_range,
float int_range);
void rescale_grid(VoxelGrid &grid, float scale);
void grid_union(VoxelGrid &grid, VoxelGrid &arg);
void grid_difference(VoxelGrid &grid, VoxelGrid &arg);
void grid_intersection(VoxelGrid &grid, VoxelGrid &arg);
} // namespace Slic3r

View File

@ -0,0 +1,100 @@
#ifndef OPENVDBUTILSLEGACY_HPP
#define OPENVDBUTILSLEGACY_HPP
#include "libslic3r/TriangleMesh.hpp"
#ifdef _MSC_VER
// Suppress warning C4146 in OpenVDB: unary minus operator applied to unsigned type, result still unsigned
#pragma warning(push)
#pragma warning(disable : 4146)
#endif // _MSC_VER
#include <openvdb/openvdb.h>
#include <openvdb/tools/MeshToVolume.h>
#include <openvdb/tools/FastSweeping.h>
#include <openvdb/tools/Composite.h>
#include <openvdb/tools/LevelSetRebuild.h>
#ifdef _MSC_VER
#pragma warning(pop)
#endif // _MSC_VER
namespace Slic3r {
openvdb::FloatGrid::Ptr mesh_to_grid(const indexed_triangle_set & mesh,
const openvdb::math::Transform &tr,
float voxel_scale,
float exteriorBandWidth,
float interiorBandWidth)
{
class TriangleMeshDataAdapter {
public:
const indexed_triangle_set &its;
float voxel_scale;
size_t polygonCount() const { return its.indices.size(); }
size_t pointCount() const { return its.vertices.size(); }
size_t vertexCount(size_t) const { return 3; }
// Return position pos in local grid index space for polygon n and vertex v
// The actual mesh will appear to openvdb as scaled uniformly by voxel_size
// And the voxel count per unit volume can be affected this way.
void getIndexSpacePoint(size_t n, size_t v, openvdb::Vec3d& pos) const
{
auto vidx = size_t(its.indices[n](Eigen::Index(v)));
Slic3r::Vec3d p = its.vertices[vidx].cast<double>() * voxel_scale;
pos = {p.x(), p.y(), p.z()};
}
TriangleMeshDataAdapter(const indexed_triangle_set &m, float voxel_sc = 1.f)
: its{m}, voxel_scale{voxel_sc} {};
};
// Might not be needed but this is now proven to be working
openvdb::initialize();
std::vector<indexed_triangle_set> meshparts = its_split(mesh);
auto it = std::remove_if(meshparts.begin(), meshparts.end(),
[](auto &m) { return its_volume(m) < EPSILON; });
meshparts.erase(it, meshparts.end());
openvdb::FloatGrid::Ptr grid;
for (auto &m : meshparts) {
auto subgrid = openvdb::tools::meshToVolume<openvdb::FloatGrid>(
TriangleMeshDataAdapter{m, voxel_scale}, tr, 1.f, 1.f);
if (grid && subgrid) openvdb::tools::csgUnion(*grid, *subgrid);
else if (subgrid) grid = std::move(subgrid);
}
if (meshparts.size() > 1) {
// This is needed to avoid various artefacts on multipart meshes.
// TODO: replace with something faster
grid = openvdb::tools::levelSetRebuild(*grid, 0., 1.f, 1.f);
}
if(meshparts.empty()) {
// Splitting failed, fall back to hollow the original mesh
grid = openvdb::tools::meshToVolume<openvdb::FloatGrid>(
TriangleMeshDataAdapter{mesh}, tr, 1.f, 1.f);
}
constexpr int DilateIterations = 1;
grid = openvdb::tools::dilateSdf(
*grid, interiorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_LESS_THAN_ISOVALUE);
grid = openvdb::tools::dilateSdf(
*grid, exteriorBandWidth, openvdb::tools::NN_FACE_EDGE,
DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_GREATER_THAN_ISOVALUE);
grid->insertMeta("voxel_scale", openvdb::FloatMetadata(voxel_scale));
return grid;
}
} // namespace Slic3r
#endif // OPENVDBUTILSLEGACY_HPP

View File

@ -10,11 +10,10 @@
#include <libslic3r/QuadricEdgeCollapse.hpp>
#include <libslic3r/SLA/SupportTreeMesher.hpp>
#include <libslic3r/Execution/ExecutionSeq.hpp>
#include <libslic3r/Model.hpp>
#include <boost/log/trivial.hpp>
#include <openvdb/tools/FastSweeping.h>
#include <libslic3r/MTUtils.hpp>
#include <libslic3r/I18N.hpp>
@ -27,19 +26,17 @@ namespace sla {
struct Interior {
indexed_triangle_set mesh;
openvdb::FloatGrid::Ptr gridptr;
mutable std::optional<openvdb::FloatGrid::ConstAccessor> accessor;
VoxelGridPtr gridptr;
double iso_surface = 0.;
double thickness = 0.;
double voxel_scale = 1.;
double full_narrowb = 2.;
void reset_accessor() const // This resets the accessor and its cache
// Not a thread safe call!
{
if (gridptr)
accessor = gridptr->getConstAccessor();
Slic3r::reset_accessor(*gridptr);
}
};
@ -58,29 +55,30 @@ const indexed_triangle_set &get_mesh(const Interior &interior)
return interior.mesh;
}
static InteriorPtr generate_interior_verbose(const TriangleMesh & mesh,
const JobController &ctl,
double min_thickness,
double voxel_scale,
double closing_dist)
const VoxelGrid &get_grid(const Interior &interior)
{
double offset = voxel_scale * min_thickness;
double D = voxel_scale * closing_dist;
return *interior.gridptr;
}
VoxelGrid &get_grid(Interior &interior)
{
return *interior.gridptr;
}
InteriorPtr generate_interior(const VoxelGrid &vgrid,
const HollowingConfig &hc,
const JobController &ctl)
{
double offset = hc.min_thickness;
double D = hc.closing_distance;
float in_range = 1.1f * float(offset + D);
auto narrowb = 1.;
auto narrowb = 3.f / get_voxel_scale(vgrid);
float out_range = narrowb;
if (ctl.stopcondition()) return {};
else ctl.statuscb(0, L("Hollowing"));
auto gridptr = mesh_to_grid(mesh.its, {}, voxel_scale, out_range, in_range);
assert(gridptr);
if (!gridptr) {
BOOST_LOG_TRIVIAL(error) << "Returned OpenVDB grid is NULL";
return {};
}
auto gridptr = dilate_grid(vgrid, out_range, in_range);
if (ctl.stopcondition()) return {};
else ctl.statuscb(30, L("Hollowing"));
@ -90,12 +88,7 @@ static InteriorPtr generate_interior_verbose(const TriangleMesh & mesh,
in_range = narrowb;
gridptr = redistance_grid(*gridptr, -(offset + D), narrowb, in_range);
constexpr int DilateIterations = 1;
gridptr = openvdb::tools::dilateSdf(
*gridptr, std::ceil(iso_surface),
openvdb::tools::NN_FACE_EDGE_VERTEX, DilateIterations,
openvdb::tools::FastSweepingDomain::SWEEP_GREATER_THAN_ISOVALUE);
gridptr = dilate_grid(*gridptr, std::ceil(iso_surface), 0.f);
out_range = iso_surface;
} else {
@ -109,68 +102,14 @@ static InteriorPtr generate_interior_verbose(const TriangleMesh & mesh,
InteriorPtr interior = InteriorPtr{new Interior{}};
interior->mesh = grid_to_mesh(*gridptr, iso_surface, adaptivity);
interior->gridptr = gridptr;
interior->gridptr = std::move(gridptr);
if (ctl.stopcondition()) return {};
else ctl.statuscb(100, L("Hollowing"));
interior->iso_surface = iso_surface;
interior->thickness = offset;
interior->voxel_scale = voxel_scale;
interior->full_narrowb = out_range + in_range;
return interior;
}
InteriorPtr generate_interior(const TriangleMesh & mesh,
const HollowingConfig &hc,
const JobController & ctl)
{
static constexpr double MIN_SAMPLES_IN_WALL = 3.5;
static constexpr double MAX_OVERSAMPL = 8.;
static constexpr double UNIT_VOLUME = 500000; // empiric
// 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.
//
// First an allowed range for voxel scale is determined from an initial
// range of <MIN_SAMPLES_IN_WALL, MAX_OVERSAMPL>. The final voxel scale is
// then chosen from this range using the 'quality:<0, 1>' parameter.
// The minimum can be lowered if the wall thickness is great enough and
// the maximum is lowered if the model volume very big.
double mesh_vol = its_volume(mesh.its);
double sc_divider = std::max(1.0, (mesh_vol / UNIT_VOLUME));
double min_oversampl = std::max(MIN_SAMPLES_IN_WALL / hc.min_thickness, 1.);
double max_oversampl_scaled = std::max(min_oversampl, MAX_OVERSAMPL / sc_divider);
auto voxel_scale = min_oversampl + (max_oversampl_scaled - min_oversampl) * hc.quality;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: max oversampl will be: " << max_oversampl_scaled;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: voxel scale will be: " << voxel_scale;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: mesh volume is: " << mesh_vol;
InteriorPtr interior = generate_interior_verbose(mesh, ctl,
hc.min_thickness,
voxel_scale,
hc.closing_distance);
if (interior && !interior->mesh.empty()) {
// flip normals back...
swap_normals(interior->mesh);
// simplify mesh lossless
float loss_less_max_error = 2*std::numeric_limits<float>::epsilon();
its_quadric_edge_collapse(interior->mesh, 0U, &loss_less_max_error);
its_compactify_vertices(interior->mesh);
its_merge_vertices(interior->mesh);
// flip normals back...
swap_normals(interior->mesh);
}
interior->full_narrowb = (out_range + in_range) / 2.;
return interior;
}
@ -208,7 +147,6 @@ bool DrainHole::is_inside(const Vec3f& pt) const
return false;
}
// Given a line s+dir*t, find parameter t of intersections with the hole
// and the normal (points inside the hole). Outputs through out reference,
// returns true if two intersections were found.
@ -331,7 +269,7 @@ void cut_drainholes(std::vector<ExPolygons> & obj_slices,
void hollow_mesh(TriangleMesh &mesh, const HollowingConfig &cfg, int flags)
{
InteriorPtr interior = generate_interior(mesh, cfg, JobController{});
InteriorPtr interior = generate_interior(mesh.its, cfg, JobController{});
if (!interior) return;
hollow_mesh(mesh, *interior, flags);
@ -354,13 +292,7 @@ static double get_distance_raw(const Vec3f &p, const Interior &interior)
{
assert(interior.gridptr);
if (!interior.accessor) interior.reset_accessor();
auto v = (p * interior.voxel_scale).cast<double>();
auto grididx = interior.gridptr->transform().worldToIndexCellCentered(
{v.x(), v.y(), v.z()});
return interior.accessor->getValue(grididx) ;
return Slic3r::get_distance_raw(p, *interior.gridptr);
}
struct TriangleBubble { Vec3f center; double R; };
@ -369,7 +301,7 @@ struct TriangleBubble { Vec3f center; double R; };
// triangle is too big to be measured.
static double get_distance(const TriangleBubble &b, const Interior &interior)
{
double R = b.R * interior.voxel_scale;
double R = b.R;
double D = 2. * R;
double Dst = get_distance_raw(b.center, interior);
@ -379,10 +311,16 @@ static double get_distance(const TriangleBubble &b, const Interior &interior)
Dst - interior.iso_surface;
}
double get_distance(const Vec3f &p, const Interior &interior)
inline double get_distance(const Vec3f &p, const Interior &interior)
{
double d = get_distance_raw(p, interior) - interior.iso_surface;
return d / interior.voxel_scale;
return d;
}
template<class T>
FloatingOnly<T> get_distance(const Vec<3, T> &p, const Interior &interior)
{
return get_distance(Vec3f(p.template cast<float>()), interior);
}
// A face that can be divided. Stores the indices into the original mesh if its
@ -500,7 +438,7 @@ void remove_inside_triangles(TriangleMesh &mesh, const Interior &interior,
TriangleBubble bubble{facebb.center().cast<float>(), facebb.radius()};
double D = get_distance(bubble, interior);
double R = bubble.R * interior.voxel_scale;
double R = bubble.R;
if (std::isnan(D)) // The distance cannot be measured, triangle too big
return true;
@ -585,4 +523,223 @@ void remove_inside_triangles(TriangleMesh &mesh, const Interior &interior,
//FIXME do we want to repair the mesh? Are there duplicate vertices or flipped triangles?
}
struct FaceHash {
// A 64 bit number's max hex digits
static constexpr size_t MAX_NUM_CHARS = 16;
// A hash is created for each triangle to be identifiable. The hash uses
// only the triangle's geometric traits, not the index in a particular mesh.
std::unordered_set<std::string> facehash;
// Returns the string in reverse, but that is ok for hashing
static std::array<char, MAX_NUM_CHARS + 1> to_chars(int64_t val)
{
std::array<char, MAX_NUM_CHARS + 1> ret;
static const constexpr char * Conv = "0123456789abcdef";
auto ptr = ret.begin();
auto uval = static_cast<uint64_t>(std::abs(val));
while (uval) {
*ptr = Conv[uval & 0xf];
++ptr;
uval = uval >> 4;
}
if (val < 0) { *ptr = '-'; ++ptr; }
*ptr = '\0'; // C style string ending
return ret;
}
static std::string hash(const Vec<3, int64_t> &v)
{
std::string ret;
ret.reserve(3 * MAX_NUM_CHARS);
for (auto val : v)
ret += to_chars(val).data();
return ret;
}
static std::string facekey(const Vec3i &face, const std::vector<Vec3f> &vertices)
{
// Scale to integer to avoid floating points
std::array<Vec<3, int64_t>, 3> pts = {
scaled<int64_t>(vertices[face(0)]),
scaled<int64_t>(vertices[face(1)]),
scaled<int64_t>(vertices[face(2)])
};
// Get the first two sides of the triangle, do a cross product and move
// that vector to the center of the triangle. This encodes all
// information to identify an identical triangle at the same position.
Vec<3, int64_t> a = pts[0] - pts[2], b = pts[1] - pts[2];
Vec<3, int64_t> c = a.cross(b) + (pts[0] + pts[1] + pts[2]) / 3;
// Return a concatenated string representation of the coordinates
return hash(c);
}
FaceHash (const indexed_triangle_set &its): facehash(its.indices.size())
{
for (const Vec3i &face : its.indices)
facehash.insert(facekey(face, its.vertices));
}
bool find(const std::string &key)
{
auto it = facehash.find(key);
return it != facehash.end();
}
};
static void exclude_neighbors(const Vec3i &face,
std::vector<bool> &mask,
const indexed_triangle_set &its,
const VertexFaceIndex &index,
size_t recursions)
{
for (int i = 0; i < 3; ++i) {
const auto &neighbors_range = index[face(i)];
for (size_t fi_n : neighbors_range) {
mask[fi_n] = true;
if (recursions > 0)
exclude_neighbors(its.indices[fi_n], mask, its, index, recursions - 1);
}
}
}
std::vector<bool> create_exclude_mask(const indexed_triangle_set &its,
const Interior &interior,
const std::vector<DrainHole> &holes)
{
FaceHash interior_hash{sla::get_mesh(interior)};
std::vector<bool> exclude_mask(its.indices.size(), false);
VertexFaceIndex neighbor_index{its};
for (size_t fi = 0; fi < its.indices.size(); ++fi) {
auto &face = its.indices[fi];
if (interior_hash.find(FaceHash::facekey(face, its.vertices))) {
exclude_mask[fi] = true;
continue;
}
if (exclude_mask[fi]) {
exclude_neighbors(face, exclude_mask, its, neighbor_index, 1);
continue;
}
// Lets deal with the holes. All the triangles of a hole and all the
// neighbors of these triangles need to be kept. The neigbors were
// created by CGAL mesh boolean operation that modified the original
// interior inside the input mesh to contain the holes.
Vec3d tr_center = (
its.vertices[face(0)] +
its.vertices[face(1)] +
its.vertices[face(2)]
).cast<double>() / 3.;
// If the center is more than half a mm inside the interior,
// it cannot possibly be part of a hole wall.
if (sla::get_distance(tr_center, interior) < -0.5)
continue;
Vec3f U = its.vertices[face(1)] - its.vertices[face(0)];
Vec3f V = its.vertices[face(2)] - its.vertices[face(0)];
Vec3f C = U.cross(V);
Vec3f face_normal = C.normalized();
for (const sla::DrainHole &dh : holes) {
if (dh.failed) continue;
Vec3d dhpos = dh.pos.cast<double>();
Vec3d dhend = dhpos + dh.normal.cast<double>() * dh.height;
Linef3 holeaxis{dhpos, dhend};
double D_hole_center = line_alg::distance_to(holeaxis, tr_center);
double D_hole = std::abs(D_hole_center - dh.radius);
float dot = dh.normal.dot(face_normal);
// Empiric tolerances for center distance and normals angle.
// For triangles that are part of a hole wall the angle of
// triangle normal and the hole axis is around 90 degrees,
// so the dot product is around zero.
double D_tol = dh.radius / sla::DrainHole::steps;
float normal_angle_tol = 1.f / sla::DrainHole::steps;
if (D_hole < D_tol && std::abs(dot) < normal_angle_tol) {
exclude_mask[fi] = true;
exclude_neighbors(face, exclude_mask, its, neighbor_index, 1);
}
}
}
return exclude_mask;
}
DrainHoles transformed_drainhole_points(const ModelObject &mo,
const Transform3d &trafo)
{
auto pts = mo.sla_drain_holes;
const Transform3d& vol_trafo = mo.volumes.front()->get_transformation().get_matrix();
const Geometry::Transformation trans(trafo * vol_trafo);
const Transform3f& tr = trans.get_matrix().cast<float>();
const Vec3f sc = trans.get_scaling_factor().cast<float>();
for (sla::DrainHole &hl : pts) {
hl.pos = tr * hl.pos;
hl.normal = tr * hl.normal - tr.translation();
// The normal scales as a covector (and we must also
// undo the damage already done).
hl.normal = Vec3f(hl.normal(0)/(sc(0)*sc(0)),
hl.normal(1)/(sc(1)*sc(1)),
hl.normal(2)/(sc(2)*sc(2)));
// Now shift the hole a bit above the object and make it deeper to
// compensate for it. This is to avoid problems when the hole is placed
// on (nearly) flat surface.
hl.pos -= hl.normal.normalized() * sla::HoleStickOutLength;
hl.height += sla::HoleStickOutLength;
}
return pts;
}
double get_voxel_scale(double mesh_volume, const HollowingConfig &hc)
{
static constexpr double MIN_SAMPLES_IN_WALL = 3.5;
static constexpr double MAX_OVERSAMPL = 8.;
static constexpr double UNIT_VOLUME = 500000; // empiric
// 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.
//
// First an allowed range for voxel scale is determined from an initial
// range of <MIN_SAMPLES_IN_WALL, MAX_OVERSAMPL>. The final voxel scale is
// then chosen from this range using the 'quality:<0, 1>' parameter.
// The minimum can be lowered if the wall thickness is great enough and
// the maximum is lowered if the model volume very big.
double sc_divider = std::max(1.0, (mesh_volume / UNIT_VOLUME));
double min_oversampl = std::max(MIN_SAMPLES_IN_WALL / hc.min_thickness, 1.);
double max_oversampl_scaled = std::max(min_oversampl, MAX_OVERSAMPL / sc_divider);
auto voxel_scale = min_oversampl + (max_oversampl_scaled - min_oversampl) * hc.quality;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: max oversampl will be: " << max_oversampl_scaled;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: voxel scale will be: " << voxel_scale;
BOOST_LOG_TRIVIAL(debug) << "Hollowing: mesh volume is: " << mesh_volume;
return voxel_scale;
}
}} // namespace Slic3r::sla

View File

@ -3,10 +3,14 @@
#include <memory>
#include <libslic3r/TriangleMesh.hpp>
#include <libslic3r/OpenVDBUtils.hpp>
#include <libslic3r/SLA/JobController.hpp>
#include <libslic3r/CSGMesh/VoxelizeCSGMesh.hpp>
namespace Slic3r {
class ModelObject;
namespace sla {
struct HollowingConfig
@ -28,6 +32,9 @@ using InteriorPtr = std::unique_ptr<Interior, InteriorDeleter>;
indexed_triangle_set & get_mesh(Interior &interior);
const indexed_triangle_set &get_mesh(const Interior &interior);
const VoxelGrid & get_grid(const Interior &interior);
VoxelGrid &get_grid(Interior &interior);
struct DrainHole
{
Vec3f pos;
@ -46,18 +53,18 @@ struct DrainHole
DrainHole(const DrainHole& rhs) :
DrainHole(rhs.pos, rhs.normal, rhs.radius, rhs.height, rhs.failed) {}
bool operator==(const DrainHole &sp) const;
bool operator!=(const DrainHole &sp) const { return !(sp == (*this)); }
bool is_inside(const Vec3f& pt) const;
bool get_intersections(const Vec3f& s, const Vec3f& dir,
std::array<std::pair<float, Vec3d>, 2>& out) const;
indexed_triangle_set to_mesh() const;
template<class Archive> inline void serialize(Archive &ar)
{
ar(pos, normal, radius, height, failed);
@ -70,10 +77,51 @@ using DrainHoles = std::vector<DrainHole>;
constexpr float HoleStickOutLength = 1.f;
InteriorPtr generate_interior(const TriangleMesh &mesh,
double get_voxel_scale(double mesh_volume, const HollowingConfig &hc);
InteriorPtr generate_interior(const VoxelGrid &mesh,
const HollowingConfig & = {},
const JobController &ctl = {});
inline InteriorPtr generate_interior(const indexed_triangle_set &mesh,
const HollowingConfig &hc = {},
const JobController &ctl = {})
{
auto voxel_scale = get_voxel_scale(its_volume(mesh), hc);
auto grid = mesh_to_grid(mesh, Transform3f::Identity(), voxel_scale, 1.f, 1.f);
if (its_is_splittable(mesh))
grid = redistance_grid(*grid, 0.0f, 6.f / voxel_scale, 6.f / voxel_scale);
return generate_interior(*grid, hc, ctl);
}
template<class It>
InteriorPtr generate_interior(const Range<It> &csgparts,
const HollowingConfig &hc = {},
const JobController &ctl = {})
{
double mesh_vol = 0;
for (auto &part : csgparts)
mesh_vol = std::max(mesh_vol,
double(its_volume(*(csg::get_mesh(part)))));
auto params = csg::VoxelizeParams{}
.voxel_scale(get_voxel_scale(mesh_vol, hc))
.exterior_bandwidth(1.f)
.interior_bandwidth(1.f);
auto ptr = csg::voxelize_csgmesh(csgparts, params);
if (csgparts.size() > 1 || its_is_splittable(*csg::get_mesh(*csgparts.begin())))
ptr = redistance_grid(*ptr,
0.0f,
6.f / params.voxel_scale(),
6.f / params.voxel_scale());
return generate_interior(*ptr, hc, ctl);
}
// Will do the hollowing
void hollow_mesh(TriangleMesh &mesh, const HollowingConfig &cfg, int flags = 0);
@ -83,13 +131,8 @@ void hollow_mesh(TriangleMesh &mesh, const Interior &interior, int flags = 0);
void remove_inside_triangles(TriangleMesh &mesh, const Interior &interior,
const std::vector<bool> &exclude_mask = {});
double get_distance(const Vec3f &p, const Interior &interior);
template<class T>
FloatingOnly<T> get_distance(const Vec<3, T> &p, const Interior &interior)
{
return get_distance(Vec3f(p.template cast<float>()), interior);
}
sla::DrainHoles transformed_drainhole_points(const ModelObject &mo,
const Transform3d &trafo);
void cut_drainholes(std::vector<ExPolygons> & obj_slices,
const std::vector<float> &slicegrid,
@ -103,6 +146,16 @@ inline void swap_normals(indexed_triangle_set &its)
std::swap(face(0), face(2));
}
// Create exclude mask for triangle removal inside hollowed interiors.
// This is necessary when the interior is already part of the mesh which was
// drilled using CGAL mesh boolean operation. Excluded will be the triangles
// originally part of the interior mesh and triangles that make up the drilled
// hole walls.
std::vector<bool> create_exclude_mask(
const indexed_triangle_set &its,
const sla::Interior &interior,
const std::vector<sla::DrainHole> &holes);
} // namespace sla
} // namespace Slic3r

View File

@ -108,6 +108,7 @@ struct SupportableMesh
SupportPoints pts;
SupportTreeConfig cfg;
PadConfig pad_cfg;
double zoffset = 0.;
explicit SupportableMesh(const indexed_triangle_set &trmsh,
const SupportPoints &sp,
@ -124,7 +125,7 @@ struct SupportableMesh
inline double ground_level(const SupportableMesh &sm)
{
double lvl = sm.emesh.ground_level() -
double lvl = sm.zoffset -
!bool(sm.pad_cfg.embed_object) * sm.cfg.enabled * sm.cfg.object_elevation_mm +
bool(sm.pad_cfg.embed_object) * sm.pad_cfg.wall_thickness_mm;

View File

@ -1081,30 +1081,7 @@ sla::SupportPoints SLAPrintObject::transformed_support_points() const
sla::DrainHoles SLAPrintObject::transformed_drainhole_points() const
{
assert(m_model_object != nullptr);
auto pts = m_model_object->sla_drain_holes;
const Transform3d& vol_trafo = m_model_object->volumes.front()->get_transformation().get_matrix();
const Geometry::Transformation trans(trafo() * vol_trafo);
const Transform3f& tr = trans.get_matrix().cast<float>();
const Vec3f sc = trans.get_scaling_factor().cast<float>();
for (sla::DrainHole &hl : pts) {
hl.pos = tr * hl.pos;
hl.normal = tr * hl.normal - tr.translation();
// The normal scales as a covector (and we must also
// undo the damage already done).
hl.normal = Vec3f(hl.normal(0)/(sc(0)*sc(0)),
hl.normal(1)/(sc(1)*sc(1)),
hl.normal(2)/(sc(2)*sc(2)));
// Now shift the hole a bit above the object and make it deeper to
// compensate for it. This is to avoid problems when the hole is placed
// on (nearly) flat surface.
hl.pos -= hl.normal.normalized() * sla::HoleStickOutLength;
hl.height += sla::HoleStickOutLength;
}
return pts;
return sla::transformed_drainhole_points(*this->model_object(), trafo());
}
DynamicConfig SLAPrintStatistics::config() const

View File

@ -318,6 +318,10 @@ private:
inline SupportData(const TriangleMesh &t)
: input{t.its, {}, {}}
{}
inline SupportData(const indexed_triangle_set &t)
: input{t, {}, {}}
{}
void create_support_tree(const sla::JobController &ctl)
{

View File

@ -16,6 +16,7 @@
#include <libslic3r/AABBTreeIndirect.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include <libslic3r/QuadricEdgeCollapse.hpp>
#include <boost/log/trivial.hpp>
@ -134,209 +135,41 @@ void SLAPrint::Steps::hollow_model(SLAPrintObject &po)
double quality = po.m_config.hollowing_quality.getFloat();
double closing_d = po.m_config.hollowing_closing_distance.getFloat();
sla::HollowingConfig hlwcfg{thickness, quality, closing_d};
sla::JobController ctl;
ctl.stopcondition = [this]() { return canceled(); };
ctl.cancelfn = [this]() { throw_if_canceled(); };
sla::InteriorPtr interior = generate_interior(po.transformed_mesh(), hlwcfg);
sla::InteriorPtr interior = generate_interior(po.transformed_mesh().its, hlwcfg, ctl);
if (!interior || sla::get_mesh(*interior).empty())
BOOST_LOG_TRIVIAL(warning) << "Hollowed interior is empty!";
else {
po.m_hollowing_data.reset(new SLAPrintObject::HollowingData());
po.m_hollowing_data->interior = std::move(interior);
}
}
struct FaceHash {
indexed_triangle_set &m = sla::get_mesh(*po.m_hollowing_data->interior);
// A 64 bit number's max hex digits
static constexpr size_t MAX_NUM_CHARS = 16;
if (!m.empty()) {
// simplify mesh lossless
float loss_less_max_error = 2*std::numeric_limits<float>::epsilon();
its_quadric_edge_collapse(m, 0U, &loss_less_max_error);
// A hash is created for each triangle to be identifiable. The hash uses
// only the triangle's geometric traits, not the index in a particular mesh.
std::unordered_set<std::string> facehash;
its_compactify_vertices(m);
its_merge_vertices(m);
// Returns the string in reverse, but that is ok for hashing
static std::array<char, MAX_NUM_CHARS + 1> to_chars(int64_t val)
{
std::array<char, MAX_NUM_CHARS + 1> ret;
static const constexpr char * Conv = "0123456789abcdef";
auto ptr = ret.begin();
auto uval = static_cast<uint64_t>(std::abs(val));
while (uval) {
*ptr = Conv[uval & 0xf];
++ptr;
uval = uval >> 4;
}
if (val < 0) { *ptr = '-'; ++ptr; }
*ptr = '\0'; // C style string ending
return ret;
}
static std::string hash(const Vec<3, int64_t> &v)
{
std::string ret;
ret.reserve(3 * MAX_NUM_CHARS);
for (auto val : v)
ret += to_chars(val).data();
return ret;
}
static std::string facekey(const Vec3i &face, const std::vector<Vec3f> &vertices)
{
// Scale to integer to avoid floating points
std::array<Vec<3, int64_t>, 3> pts = {
scaled<int64_t>(vertices[face(0)]),
scaled<int64_t>(vertices[face(1)]),
scaled<int64_t>(vertices[face(2)])
};
// Get the first two sides of the triangle, do a cross product and move
// that vector to the center of the triangle. This encodes all
// information to identify an identical triangle at the same position.
Vec<3, int64_t> a = pts[0] - pts[2], b = pts[1] - pts[2];
Vec<3, int64_t> c = a.cross(b) + (pts[0] + pts[1] + pts[2]) / 3;
// Return a concatenated string representation of the coordinates
return hash(c);
}
FaceHash (const indexed_triangle_set &its): facehash(its.indices.size())
{
for (const Vec3i &face : its.indices)
facehash.insert(facekey(face, its.vertices));
}
bool find(const std::string &key)
{
auto it = facehash.find(key);
return it != facehash.end();
}
};
static void exclude_neighbors(const Vec3i &face,
std::vector<bool> &mask,
const indexed_triangle_set &its,
const VertexFaceIndex &index,
size_t recursions)
{
for (int i = 0; i < 3; ++i) {
const auto &neighbors_range = index[face(i)];
for (size_t fi_n : neighbors_range) {
mask[fi_n] = true;
if (recursions > 0)
exclude_neighbors(its.indices[fi_n], mask, its, index, recursions - 1);
// flip normals back...
sla::swap_normals(m);
}
}
}
// Create exclude mask for triangle removal inside hollowed interiors.
// This is necessary when the interior is already part of the mesh which was
// drilled using CGAL mesh boolean operation. Excluded will be the triangles
// originally part of the interior mesh and triangles that make up the drilled
// hole walls.
static std::vector<bool> create_exclude_mask(
const indexed_triangle_set &its,
const sla::Interior &interior,
const std::vector<sla::DrainHole> &holes)
{
FaceHash interior_hash{sla::get_mesh(interior)};
std::vector<bool> exclude_mask(its.indices.size(), false);
VertexFaceIndex neighbor_index{its};
for (size_t fi = 0; fi < its.indices.size(); ++fi) {
auto &face = its.indices[fi];
if (interior_hash.find(FaceHash::facekey(face, its.vertices))) {
exclude_mask[fi] = true;
continue;
}
if (exclude_mask[fi]) {
exclude_neighbors(face, exclude_mask, its, neighbor_index, 1);
continue;
}
// Lets deal with the holes. All the triangles of a hole and all the
// neighbors of these triangles need to be kept. The neigbors were
// created by CGAL mesh boolean operation that modified the original
// interior inside the input mesh to contain the holes.
Vec3d tr_center = (
its.vertices[face(0)] +
its.vertices[face(1)] +
its.vertices[face(2)]
).cast<double>() / 3.;
// If the center is more than half a mm inside the interior,
// it cannot possibly be part of a hole wall.
if (sla::get_distance(tr_center, interior) < -0.5)
continue;
Vec3f U = its.vertices[face(1)] - its.vertices[face(0)];
Vec3f V = its.vertices[face(2)] - its.vertices[face(0)];
Vec3f C = U.cross(V);
Vec3f face_normal = C.normalized();
for (const sla::DrainHole &dh : holes) {
if (dh.failed) continue;
Vec3d dhpos = dh.pos.cast<double>();
Vec3d dhend = dhpos + dh.normal.cast<double>() * dh.height;
Linef3 holeaxis{dhpos, dhend};
double D_hole_center = line_alg::distance_to(holeaxis, tr_center);
double D_hole = std::abs(D_hole_center - dh.radius);
float dot = dh.normal.dot(face_normal);
// Empiric tolerances for center distance and normals angle.
// For triangles that are part of a hole wall the angle of
// triangle normal and the hole axis is around 90 degrees,
// so the dot product is around zero.
double D_tol = dh.radius / sla::DrainHole::steps;
float normal_angle_tol = 1.f / sla::DrainHole::steps;
if (D_hole < D_tol && std::abs(dot) < normal_angle_tol) {
exclude_mask[fi] = true;
exclude_neighbors(face, exclude_mask, its, neighbor_index, 1);
}
}
}
return exclude_mask;
}
static indexed_triangle_set
remove_unconnected_vertices(const indexed_triangle_set &its)
{
if (its.indices.empty()) {};
indexed_triangle_set M;
std::vector<int> vtransl(its.vertices.size(), -1);
int vcnt = 0;
for (auto &f : its.indices) {
for (int i = 0; i < 3; ++i)
if (vtransl[size_t(f(i))] < 0) {
M.vertices.emplace_back(its.vertices[size_t(f(i))]);
vtransl[size_t(f(i))] = vcnt++;
}
std::array<int, 3> new_f = {
vtransl[size_t(f(0))],
vtransl[size_t(f(1))],
vtransl[size_t(f(2))]
};
M.indices.emplace_back(new_f[0], new_f[1], new_f[2]);
}
its_compactify_vertices(M);
return M;
}
@ -583,6 +416,9 @@ void SLAPrint::Steps::support_points(SLAPrintObject &po)
if (!po.m_supportdata)
po.m_supportdata.reset(new SLAPrintObject::SupportData(po.get_mesh_to_print()));
po.m_supportdata->input.zoffset = bounding_box(po.get_mesh_to_print())
.min.z();
const ModelObject& mo = *po.m_model_object;
BOOST_LOG_TRIVIAL(debug) << "Support point count "
@ -661,7 +497,7 @@ void SLAPrint::Steps::support_tree(SLAPrintObject &po)
if (is_zero_elevation(po.config())) {
remove_bottom_points(po.m_supportdata->input.pts,
float(
po.m_supportdata->input.emesh.ground_level() +
po.m_supportdata->input.zoffset +
EPSILON));
}

View File

@ -52,7 +52,8 @@ indexed_triangle_set slices_to_mesh(
Layers layers(slices.size());
size_t len = slices.size() - 1;
tbb::parallel_for(size_t(0), len, [&slices, &layers, &grid](size_t i) {
auto threads_cnt = execution::max_concurrency(ex_tbb);
execution::for_each(ex_tbb, size_t(0), len, [&slices, &layers, &grid](size_t i) {
const ExPolygons &upper = slices[i + 1];
const ExPolygons &lower = slices[i];
@ -64,14 +65,15 @@ indexed_triangle_set slices_to_mesh(
its_merge(layers[i], triangulate_expolygons_3d(free_top, grid[i], NORMALS_UP));
its_merge(layers[i], triangulate_expolygons_3d(overhang, grid[i], NORMALS_DOWN));
its_merge(layers[i], straight_walls(upper, grid[i], grid[i + 1]));
});
}, threads_cnt);
auto merge_fn = []( const indexed_triangle_set &a, const indexed_triangle_set &b ) {
indexed_triangle_set res{a}; its_merge(res, b); return res;
};
auto ret = execution::reduce(ex_tbb, layers.begin(), layers.end(),
indexed_triangle_set{}, merge_fn);
indexed_triangle_set{}, merge_fn,
threads_cnt);
its_merge(ret, triangulate_expolygons_3d(slices.front(), zmin, NORMALS_DOWN));
its_merge(ret, straight_walls(slices.front(), zmin, grid.front()));
@ -80,9 +82,14 @@ indexed_triangle_set slices_to_mesh(
// FIXME: these repairs do not fix the mesh entirely. There will be cracks
// in the output. It is very hard to do the meshing in a way that does not
// leave errors.
its_merge_vertices(ret);
its_remove_degenerate_faces(ret);
its_compactify_vertices(ret);
int num_mergedv = its_merge_vertices(ret);
BOOST_LOG_TRIVIAL(debug) << "Merged vertices count: " << num_mergedv;
int remcnt = its_remove_degenerate_faces(ret);
BOOST_LOG_TRIVIAL(debug) << "Removed degenerate faces count: " << remcnt;
int num_erasedv = its_compactify_vertices(ret);
BOOST_LOG_TRIVIAL(debug) << "Erased vertices count: " << num_erasedv;
return ret;
}

View File

@ -20,7 +20,7 @@
#include "MutablePolygon.hpp"
#include "SupportMaterial.hpp"
#include "TriangleMeshSlicer.hpp"
#include "OpenVDBUtils.hpp"
#include "OpenVDBUtilsLegacy.hpp"
#include <openvdb/tools/VolumeToSpheres.h>
#include <cassert>
@ -3441,7 +3441,7 @@ static void draw_branches(
TriangleMesh mesh = print_object.model_object()->raw_mesh();
mesh.transform(print_object.trafo_centered());
double scale = 10.;
openvdb::FloatGrid::Ptr grid = mesh_to_grid(mesh.its, {}, scale, 0., 0.);
openvdb::FloatGrid::Ptr grid = mesh_to_grid(mesh.its, openvdb::math::Transform{}, scale, 0., 0.);
closest_surface_point = openvdb::tools::ClosestSurfacePoint<openvdb::FloatGrid>::create(*grid);
std::vector<openvdb::Vec3R> pts, prev, projections;
std::vector<float> distances;

View File

@ -267,12 +267,18 @@ inline int its_triangle_edge_index(const stl_triangle_vertex_indices &triangle_i
using its_triangle = std::array<stl_vertex, 3>;
inline its_triangle its_triangle_vertices(const indexed_triangle_set &its,
const Vec3i &face)
{
return {its.vertices[face(0)],
its.vertices[face(1)],
its.vertices[face(2)]};
}
inline its_triangle its_triangle_vertices(const indexed_triangle_set &its,
size_t face_id)
{
return {its.vertices[its.indices[face_id](0)],
its.vertices[its.indices[face_id](1)],
its.vertices[its.indices[face_id](2)]};
return its_triangle_vertices(its, its.indices[face_id]);
}
inline stl_normal its_unnormalized_normal(const indexed_triangle_set &its,
@ -344,6 +350,22 @@ inline BoundingBoxf3 bounding_box(const indexed_triangle_set& its)
return {bmin.cast<double>(), bmax.cast<double>()};
}
inline BoundingBoxf3 bounding_box(const indexed_triangle_set& its, const Transform3f &tr)
{
if (its.vertices.empty())
return {};
Vec3f bmin = tr * its.vertices.front(), bmax = tr * its.vertices.front();
for (const Vec3f &p : its.vertices) {
Vec3f pp = tr * p;
bmin = pp.cwiseMin(bmin);
bmax = pp.cwiseMax(bmax);
}
return {bmin.cast<double>(), bmax.cast<double>()};
}
}
// Serialization through the Cereal library

View File

@ -352,10 +352,15 @@ public:
Range(It b, It e) : from(std::move(b)), to(std::move(e)) {}
// Some useful container-like methods...
inline size_t size() const { return end() - begin(); }
inline bool empty() const { return size() == 0; }
inline size_t size() const { return std::distance(from, to); }
inline bool empty() const { return from == to; }
};
template<class Cont> auto range(Cont &&cont)
{
return Range{std::begin(cont), std::end(cont)};
}
template<class T, class = FloatingOnly<T>>
constexpr T NaN = std::numeric_limits<T>::quiet_NaN();

View File

@ -157,13 +157,17 @@ class MeshRaycaster {
public:
#if ENABLE_RAYCAST_PICKING
explicit MeshRaycaster(std::shared_ptr<const TriangleMesh> mesh)
: m_mesh(mesh)
, m_emesh(*mesh, true) // calculate epsilon for triangle-ray intersection from an average edge length
, m_normals(its_face_normals(mesh->its))
: m_mesh(std::move(mesh))
, m_emesh(*m_mesh, true) // calculate epsilon for triangle-ray intersection from an average edge length
, m_normals(its_face_normals(m_mesh->its))
{
assert(m_mesh != nullptr);
assert(m_mesh);
}
explicit MeshRaycaster(const TriangleMesh &mesh)
: MeshRaycaster(std::make_unique<TriangleMesh>(mesh))
{}
static void line_from_mouse_pos(const Vec2d& mouse_pos, const Transform3d& trafo, const Camera& camera,
Vec3d& point, Vec3d& direction);
#else

View File

@ -101,7 +101,7 @@ void test_supports(const std::string &obj_filename,
REQUIRE_FALSE(mesh.empty());
if (hollowingcfg.enabled) {
sla::InteriorPtr interior = sla::generate_interior(mesh, hollowingcfg);
sla::InteriorPtr interior = sla::generate_interior(mesh.its, hollowingcfg);
REQUIRE(interior);
mesh.merge(TriangleMesh{sla::get_mesh(*interior)});
}