New BuildVolume class was created, which detects build volume type (rectangular,

circular, convex, concave) and performs efficient collision detection agains these build
volumes. As of now, collision detection is performed against a convex
hull of a concave build volume for efficency.

GCodeProcessor::Result renamed out of GCodeProcessor to GCodeProcessorResult,
so it could be forward declared.

Plater newly exports BuildVolume, not Bed3D. Bed3D is a rendering class,
while BuildVolume is a purely geometric class.

Reduced usage of global wxGetApp, the Bed3D is passed as a parameter
to View3D/Preview/GLCanvas.

Convex hull code was extracted from Geometry.cpp/hpp to Geometry/ConvexHulll.cpp,hpp.
New test inside_convex_polygon().
New efficent point inside polygon test: Decompose convex hull
to bottom / top parts and use the decomposition to detect point inside
a convex polygon in O(log n). decompose_convex_polygon_top_bottom(),
inside_convex_polygon().

New Circle constructing functions: circle_ransac() and circle_taubin_newton().

New polygon_is_convex() test with unit tests.
This commit is contained in:
Vojtech Bubnik 2021-11-16 10:15:51 +01:00
parent b431fd1f7e
commit cc44089440
51 changed files with 1544 additions and 1594 deletions

View file

@ -111,7 +111,7 @@ public:
void translate(coordf_t x, coordf_t y, coordf_t z) { assert(this->defined); PointClass v(x, y, z); this->min += v; this->max += v; }
void translate(const Vec3d &v) { this->min += v; this->max += v; }
void offset(coordf_t delta);
BoundingBoxBase<PointClass> inflated(coordf_t delta) const throw() { BoundingBoxBase<PointClass> out(*this); out.offset(delta); return out; }
BoundingBox3Base<PointClass> inflated(coordf_t delta) const throw() { BoundingBox3Base<PointClass> out(*this); out.offset(delta); return out; }
PointClass center() const;
coordf_t max_size() const;

View file

@ -0,0 +1,405 @@
#include "BuildVolume.hpp"
#include "ClipperUtils.hpp"
#include "Geometry/ConvexHull.hpp"
#include "GCode/GCodeProcessor.hpp"
#include "Point.hpp"
namespace Slic3r {
BuildVolume::BuildVolume(const std::vector<Vec2d> &bed_shape, const double max_print_height) : m_bed_shape(bed_shape), m_max_print_height(max_print_height)
{
assert(max_print_height >= 0);
m_polygon = Polygon::new_scale(bed_shape);
// Calcuate various metrics of the input polygon.
m_convex_hull = Geometry::convex_hull(m_polygon.points);
m_bbox = get_extents(m_convex_hull);
m_area = m_polygon.area();
BoundingBoxf bboxf = get_extents(bed_shape);
m_bboxf = BoundingBoxf3{ to_3d(bboxf.min, 0.), to_3d(bboxf.max, max_print_height) };
if (bed_shape.size() >= 4 && std::abs((m_area - double(m_bbox.size().x()) * double(m_bbox.size().y()))) < sqr(SCALED_EPSILON)) {
// Square print bed, use the bounding box for collision detection.
m_type = Type::Rectangle;
m_circle.center = 0.5 * (m_bbox.min.cast<double>() + m_bbox.max.cast<double>());
m_circle.radius = 0.5 * m_bbox.size().cast<double>().norm();
} else if (bed_shape.size() > 3) {
// Circle was discretized, formatted into text with limited accuracy, thus the circle was deformed.
// RANSAC is slightly more accurate than the iterative Taubin / Newton method with such an input.
// m_circle = Geometry::circle_taubin_newton(bed_shape);
m_circle = Geometry::circle_ransac(bed_shape);
bool is_circle = true;
#ifndef NDEBUG
// Measuring maximum absolute error of interpolating an input polygon with circle.
double max_error = 0;
#endif // NDEBUG
Vec2d prev = bed_shape.back();
for (const Vec2d &p : bed_shape) {
#ifndef NDEBUG
max_error = std::max(max_error, std::abs((p - m_circle.center).norm() - m_circle.radius));
#endif // NDEBUG
if (// Polygon vertices must lie very close the circle.
std::abs((p - m_circle.center).norm() - m_circle.radius) > 0.005 ||
// Midpoints of polygon edges must not undercat more than 3mm. This corresponds to 72 edges per circle generated by BedShapePanel::update_shape().
m_circle.radius - (0.5 * (prev + p) - m_circle.center).norm() > 3.) {
is_circle = false;
break;
}
prev = p;
}
if (is_circle) {
m_type = Type::Circle;
m_circle.center = scaled<double>(m_circle.center);
m_circle.radius = scaled<double>(m_circle.radius);
}
}
if (bed_shape.size() >= 3 && m_type == Type::Invalid) {
// Circle check is not used for Convex / Custom shapes, fill it with something reasonable.
m_circle = Geometry::smallest_enclosing_circle_welzl(m_convex_hull.points);
m_type = (m_convex_hull.area() - m_area) < sqr(SCALED_EPSILON) ? Type::Convex : Type::Custom;
// Initialize the top / bottom decomposition for inside convex polygon check. Do it with two different epsilons applied.
auto convex_decomposition = [](const Polygon &in, double epsilon) {
Polygon src = expand(in, float(epsilon)).front();
std::vector<Vec2d> pts;
pts.reserve(src.size());
for (const Point &pt : src.points)
pts.emplace_back(unscaled<double>(pt.cast<double>().eval()));
return Geometry::decompose_convex_polygon_top_bottom(pts);
};
m_top_bottom_convex_hull_decomposition_scene = convex_decomposition(m_convex_hull, SceneEpsilon);
m_top_bottom_convex_hull_decomposition_bed = convex_decomposition(m_convex_hull, BedEpsilon);
}
BOOST_LOG_TRIVIAL(debug) << "BuildVolume bed_shape clasified as: " << this->type_name();
}
#if 0
// Tests intersections of projected triangles, not just their vertices against a bounding box.
// This test also correctly evaluates collision of a non-convex object with the bounding box.
// Not used, slower than simple bounding box collision check and nobody complained about the inaccuracy of the simple test.
static inline BuildVolume::ObjectState rectangle_test(const indexed_triangle_set &its, const Transform3f &trafo, const Vec2f min, const Vec2f max, const float max_z)
{
bool inside = false;
bool outside = false;
auto sign = [](const Vec3f& pt) -> char { return pt.z() > 0 ? 1 : pt.z() < 0 ? -1 : 0; };
// Returns true if both inside and outside are set, thus early exit.
auto test_intersection = [&inside, &outside, min, max, max_z](const Vec3f& p1, const Vec3f& p2, const Vec3f& p3) -> bool {
// First test whether the triangle is completely inside or outside the bounding box.
Vec3f pmin = p1.cwiseMin(p2).cwiseMin(p3);
Vec3f pmax = p1.cwiseMax(p2).cwiseMax(p3);
bool tri_inside = false;
bool tri_outside = false;
if (pmax.x() < min.x() || pmin.x() > max.x() || pmax.y() < min.y() || pmin.y() > max.y()) {
// Separated by one of the rectangle sides.
tri_outside = true;
} else if (pmin.x() >= min.x() && pmax.x() <= max.x() && pmin.y() >= min.y() && pmax.y() <= max.y()) {
// Fully inside the rectangle.
tri_inside = true;
} else {
// Bounding boxes overlap. Test triangle sides against the bbox corners.
Vec2f v1(- p2.y() + p1.y(), p2.x() - p1.x());
Vec2f v2(- p2.y() + p2.y(), p3.x() - p2.x());
Vec2f v3(- p1.y() + p3.y(), p1.x() - p3.x());
bool ccw = cross2(v1, v2) > 0;
for (const Vec2f &p : { Vec2f{ min.x(), min.y() }, Vec2f{ min.x(), max.y() }, Vec2f{ max.x(), min.y() }, Vec2f{ max.x(), max.y() } }) {
auto dot = v1.dot(p);
if (ccw ? dot >= 0 : dot <= 0)
tri_inside = true;
else
tri_outside = true;
}
}
inside |= tri_inside;
outside |= tri_outside;
return inside && outside;
};
// Edge crosses the z plane. Calculate intersection point with the plane.
auto clip_edge = [](const Vec3f &p1, const Vec3f &p2) -> Vec3f {
const float t = (world_min_z - p1.z()) / (p2.z() - p1.z());
return { p1.x() + (p2.x() - p1.x()) * t, p1.y() + (p2.y() - p1.y()) * t, world_min_z };
};
// Clip at (p1, p2), p3 must be on the clipping plane.
// Returns true if both inside and outside are set, thus early exit.
auto clip_and_test1 = [&test_intersection, &clip_edge](const Vec3f &p1, const Vec3f &p2, const Vec3f &p3, bool p1above) -> bool {
Vec3f pa = clip_edge(p1, p2);
return p1above ? test_intersection(p1, pa, p3) : test_intersection(pa, p2, p3);
};
// Clip at (p1, p2) and (p2, p3).
// Returns true if both inside and outside are set, thus early exit.
auto clip_and_test2 = [&test_intersection, &clip_edge](const Vec3f &p1, const Vec3f &p2, const Vec3f &p3, bool p2above) -> bool {
Vec3f pa = clip_edge(p1, p2);
Vec3f pb = clip_edge(p2, p3);
return p2above ? test_intersection(pa, p2, pb) : test_intersection(p1, pa, p3) || test_intersection(p3, pa, pb);
};
for (const stl_triangle_vertex_indices &tri : its.indices) {
const Vec3f pts[3] = { trafo * its.vertices[tri(0)], trafo * its.vertices[tri(1)], trafo * its.vertices[tri(2)] };
char signs[3] = { sign(pts[0]), sign(pts[1]), sign(pts[2]) };
bool clips[3] = { signs[0] * signs[1] == -1, signs[1] * signs[2] == -1, signs[2] * signs[0] == -1 };
if (clips[0]) {
if (clips[1]) {
// Clipping at (pt0, pt1) and (pt1, pt2).
if (clip_and_test2(pts[0], pts[1], pts[2], signs[1] > 0))
break;
} else if (clips[2]) {
// Clipping at (pt0, pt1) and (pt0, pt2).
if (clip_and_test2(pts[2], pts[0], pts[1], signs[0] > 0))
break;
} else {
// Clipping at (pt0, pt1), pt2 must be on the clipping plane.
if (clip_and_test1(pts[0], pts[1], pts[2], signs[0] > 0))
break;
}
} else if (clips[1]) {
if (clips[2]) {
// Clipping at (pt1, pt2) and (pt0, pt2).
if (clip_and_test2(pts[0], pts[1], pts[2], signs[1] > 0))
break;
} else {
// Clipping at (pt1, pt2), pt0 must be on the clipping plane.
if (clip_and_test1(pts[1], pts[2], pts[0], signs[1] > 0))
break;
}
} else if (clips[2]) {
// Clipping at (pt0, pt2), pt1 must be on the clipping plane.
if (clip_and_test1(pts[2], pts[0], pts[1], signs[2] > 0))
break;
} else if (signs[0] >= 0 && signs[1] >= 0 && signs[2] >= 0) {
// The triangle is above or on the clipping plane.
if (test_intersection(pts[0], pts[1], pts[2]))
break;
}
}
return inside ? (outside ? BuildVolume::ObjectState::Colliding : BuildVolume::ObjectState::Inside) : BuildVolume::ObjectState::Outside;
}
#endif
// Trim the input transformed triangle mesh with print bed and test the remaining vertices with is_inside callback.
// Return inside / colliding / outside state.
template<typename InsideFn>
BuildVolume::ObjectState object_state_templ(const indexed_triangle_set &its, const Transform3f &trafo, bool may_be_below_bed, InsideFn is_inside)
{
size_t num_inside = 0;
size_t num_above = 0;
bool inside = false;
bool outside = false;
static constexpr const auto world_min_z = float(-BuildVolume::SceneEpsilon);
if (may_be_below_bed)
{
// Slower test, needs to clip the object edges with the print bed plane.
// 1) Allocate transformed vertices with their position with respect to print bed surface.
std::vector<char> sides;
sides.reserve(its.vertices.size());
const auto sign = [](const stl_vertex& pt) { return pt.z() > world_min_z ? 1 : pt.z() < world_min_z ? -1 : 0; };
for (const stl_vertex &v : its.vertices) {
const stl_vertex pt = trafo * v;
const int s = sign(pt);
sides.emplace_back(s);
if (s >= 0) {
// Vertex above or on print bed surface. Test whether it is inside the build volume.
++ num_above;
if (is_inside(pt))
++ num_inside;
}
}
// 2) Calculate intersections of triangle edges with the build surface.
inside = num_inside > 0;
outside = num_inside < num_above;
if (num_above < its.vertices.size() && ! (inside && outside)) {
// Not completely above the build surface and status may still change by testing edges intersecting the build platform.
for (const stl_triangle_vertex_indices &tri : its.indices) {
const int s[3] = { sides[tri(0)], sides[tri(1)], sides[tri(2)] };
if (std::min(s[0], std::min(s[1], s[2])) < 0 && std::max(s[0], std::max(s[1], s[2])) > 0) {
// Some edge of this triangle intersects the build platform. Calculate the intersection.
int iprev = 2;
for (int iedge = 0; iedge < 3; ++ iedge) {
if (s[iprev] * s[iedge] == -1) {
// edge intersects the build surface. Calculate intersection point.
const stl_vertex p1 = trafo * its.vertices[tri(iprev)];
const stl_vertex p2 = trafo * its.vertices[tri(iedge)];
assert(sign(p1) == s[iprev]);
assert(sign(p2) == s[iedge]);
assert(p1.z() * p2.z() < 0);
// Edge crosses the z plane. Calculate intersection point with the plane.
const float t = (world_min_z - p1.z()) / (p2.z() - p1.z());
(is_inside(Vec3f(p1.x() + (p2.x() - p1.x()) * t, p1.y() + (p2.y() - p1.y()) * t, world_min_z)) ? inside : outside) = true;
}
iprev = iedge;
}
if (inside && outside)
break;
}
}
}
}
else
{
// Much simpler and faster code, not clipping the object with the print bed.
assert(! may_be_below_bed);
num_above = its.vertices.size();
for (const stl_vertex &v : its.vertices) {
const stl_vertex pt = trafo * v;
assert(pt.z() >= world_min_z);
if (is_inside(pt))
++ num_inside;
}
inside = num_inside > 0;
outside = num_inside < num_above;
}
return inside ? (outside ? BuildVolume::ObjectState::Colliding : BuildVolume::ObjectState::Inside) : BuildVolume::ObjectState::Outside;
}
BuildVolume::ObjectState BuildVolume::object_state(const indexed_triangle_set &its, const Transform3f &trafo, bool may_be_below_bed) const
{
switch (m_type) {
case Type::Rectangle:
{
BoundingBox3Base<Vec3d> build_volume = this->bounding_volume().inflated(SceneEpsilon);
BoundingBox3Base<Vec3f> build_volumef(build_volume.min.cast<float>(), build_volume.max.cast<float>());
if (m_max_print_height == 0)
build_volume.max.z() = std::numeric_limits<double>::max();
// The following test correctly interprets intersection of a non-convex object with a rectangular build volume.
//return rectangle_test(its, trafo, to_2d(build_volume.min), to_2d(build_volume.max), build_volume.max.z());
//FIXME This test does NOT correctly interprets intersection of a non-convex object with a rectangular build volume.
return object_state_templ(its, trafo, may_be_below_bed, [build_volumef](const Vec3f &pt) { return build_volumef.contains(pt); });
}
case Type::Circle:
{
Geometry::Circlef circle { unscaled<float>(m_circle.center), unscaled<float>(m_circle.radius + SceneEpsilon) };
return m_max_print_height == 0 ?
object_state_templ(its, trafo, may_be_below_bed, [circle](const Vec3f &pt) { return circle.contains(to_2d(pt)); }) :
object_state_templ(its, trafo, may_be_below_bed, [circle, z = m_max_print_height + SceneEpsilon](const Vec3f &pt) { return pt.z() < z && circle.contains(to_2d(pt)); });
}
case Type::Convex:
//FIXME doing test on convex hull until we learn to do test on non-convex polygons efficiently.
case Type::Custom:
return m_max_print_height == 0 ?
object_state_templ(its, trafo, may_be_below_bed, [this](const Vec3f &pt) { return Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_scene, to_2d(pt).cast<double>()); }) :
object_state_templ(its, trafo, may_be_below_bed, [this, z = m_max_print_height + SceneEpsilon](const Vec3f &pt) { return pt.z() < z && Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_scene, to_2d(pt).cast<double>()); });
case Type::Invalid:
default:
return ObjectState::Inside;
}
}
BuildVolume::ObjectState BuildVolume::volume_state_bbox(const BoundingBoxf3 &volume_bbox) const
{
assert(m_type == Type::Rectangle);
BoundingBox3Base<Vec3d> build_volume = this->bounding_volume().inflated(SceneEpsilon);
if (m_max_print_height == 0)
build_volume.max.z() = std::numeric_limits<double>::max();
return build_volume.contains(volume_bbox) ? ObjectState::Inside : build_volume.intersects(volume_bbox) ? ObjectState::Colliding : ObjectState::Outside;
}
bool BuildVolume::all_paths_inside(const GCodeProcessorResult &paths, const BoundingBoxf3 &paths_bbox) const
{
auto move_valid = [](const GCodeProcessorResult::MoveVertex &move) {
return move.type == EMoveType::Extrude && move.extrusion_role != erCustom && move.width != 0.f && move.height != 0.f;
};
static constexpr const double epsilon = BedEpsilon;
switch (m_type) {
case Type::Rectangle:
{
BoundingBox3Base<Vec3d> build_volume = this->bounding_volume().inflated(epsilon);
if (m_max_print_height == 0)
build_volume.max.z() = std::numeric_limits<double>::max();
return build_volume.contains(paths_bbox);
}
case Type::Circle:
{
const Vec2f c = unscaled<float>(m_circle.center);
const float r = unscaled<double>(m_circle.radius) + epsilon;
const float r2 = sqr(r);
return m_max_print_height == 0 ?
std::all_of(paths.moves.begin(), paths.moves.end(), [move_valid, c, r2](const GCodeProcessorResult::MoveVertex &move)
{ return ! move_valid(move) || (to_2d(move.position) - c).squaredNorm() <= r2; }) :
std::all_of(paths.moves.begin(), paths.moves.end(), [move_valid, c, r2, z = m_max_print_height + epsilon](const GCodeProcessorResult::MoveVertex& move)
{ return ! move_valid(move) || ((to_2d(move.position) - c).squaredNorm() <= r2 && move.position.z() <= z); });
}
case Type::Convex:
//FIXME doing test on convex hull until we learn to do test on non-convex polygons efficiently.
case Type::Custom:
return m_max_print_height == 0 ?
std::all_of(paths.moves.begin(), paths.moves.end(), [move_valid, this](const GCodeProcessorResult::MoveVertex &move)
{ return ! move_valid(move) || Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_bed, to_2d(move.position).cast<double>()); }) :
std::all_of(paths.moves.begin(), paths.moves.end(), [move_valid, this, z = m_max_print_height + epsilon](const GCodeProcessorResult::MoveVertex &move)
{ return ! move_valid(move) || (Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_bed, to_2d(move.position).cast<double>()) && move.position.z() <= z); });
default:
return true;
}
}
template<typename Fn>
inline bool all_inside_vertices_normals_interleaved(const std::vector<float> &paths, Fn fn)
{
for (auto it = paths.begin(); it != paths.end(); ) {
it += 3;
if (! fn({ *it, *(it + 1), *(it + 2) }))
return false;
it += 3;
}
return true;
}
bool BuildVolume::all_paths_inside_vertices_and_normals_interleaved(const std::vector<float> &paths, const Eigen::AlignedBox<float, 3> &paths_bbox) const
{
assert(paths.size() % 6 == 0);
static constexpr const double epsilon = BedEpsilon;
switch (m_type) {
case Type::Rectangle:
{
BoundingBox3Base<Vec3d> build_volume = this->bounding_volume().inflated(epsilon);
if (m_max_print_height == 0)
build_volume.max.z() = std::numeric_limits<double>::max();
return build_volume.contains(paths_bbox.min().cast<double>()) && build_volume.contains(paths_bbox.max().cast<double>());
}
case Type::Circle:
{
const Vec2f c = unscaled<float>(m_circle.center);
const float r = unscaled<double>(m_circle.radius) + float(epsilon);
const float r2 = sqr(r);
return m_max_print_height == 0 ?
all_inside_vertices_normals_interleaved(paths, [c, r2](Vec3f p) { return (to_2d(p) - c).squaredNorm() <= r2; }) :
all_inside_vertices_normals_interleaved(paths, [c, r2, z = m_max_print_height + epsilon](Vec3f p) { return (to_2d(p) - c).squaredNorm() <= r2 && p.z() <= z; });
}
case Type::Convex:
//FIXME doing test on convex hull until we learn to do test on non-convex polygons efficiently.
case Type::Custom:
return m_max_print_height == 0 ?
all_inside_vertices_normals_interleaved(paths, [this](Vec3f p) { return Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_bed, to_2d(p).cast<double>()); }) :
all_inside_vertices_normals_interleaved(paths, [this, z = m_max_print_height + epsilon](Vec3f p) { return Geometry::inside_convex_polygon(m_top_bottom_convex_hull_decomposition_bed, to_2d(p).cast<double>()) && p.z() <= z; });
default:
return true;
}
}
std::string_view BuildVolume::type_name(Type type)
{
using namespace std::literals;
switch (type) {
case Type::Invalid: return "Invalid"sv;
case Type::Rectangle: return "Rectangle"sv;
case Type::Circle: return "Circle"sv;
case Type::Convex: return "Convex"sv;
case Type::Custom: return "Custom"sv;
}
// make visual studio happy
assert(false);
return {};
}
} // namespace Slic3r

View file

@ -0,0 +1,120 @@
#ifndef slic3r_BuildVolume_hpp_
#define slic3r_BuildVolume_hpp_
#include "Point.hpp"
#include "Geometry/Circle.hpp"
#include <string_view>
namespace Slic3r {
struct GCodeProcessorResult;
// For collision detection of objects and G-code (extrusion paths) against the build volume.
class BuildVolume
{
public:
enum class Type : unsigned char
{
// Not set yet or undefined.
Invalid,
// Rectangular print bed. Most common, cheap to work with.
Rectangle,
// Circular print bed. Common on detals, cheap to work with.
Circle,
// Convex print bed. Complex to process.
Convex,
// Some non convex shape.
Custom
};
// Initialized to empty, all zeros, Invalid.
BuildVolume() {}
// Initialize from PrintConfig::bed_shape and PrintConfig::max_print_height
BuildVolume(const std::vector<Vec2d> &bed_shape, const double max_print_height);
// Source data, unscaled coordinates.
const std::vector<Vec2d>& bed_shape() const { return m_bed_shape; }
double max_print_height() const { return m_max_print_height; }
// Derived data
Type type() const { return m_type; }
// Format the type for console output.
static std::string_view type_name(Type type);
std::string_view type_name() const { return type_name(m_type); }
bool valid() const { return m_type != Type::Invalid; }
// Same as bed_shape(), but scaled coordinates.
const Polygon& polygon() const { return m_polygon; }
// Bounding box of polygon(), scaled.
const BoundingBox& bounding_box() const { return m_bbox; }
// Bounding volume of bed_shape(), max_print_height(), unscaled.
const BoundingBoxf3& bounding_volume() const { return m_bboxf; }
BoundingBoxf bounding_volume2d() const { return { to_2d(m_bboxf.min), to_2d(m_bboxf.max) }; };
// Center of the print bed, unscaled.
Vec2d bed_center() const { return to_2d(m_bboxf.center()); }
// Convex hull of polygon(), scaled.
const Polygon& convex_hull() const { return m_convex_hull; }
// Smallest enclosing circle of polygon(), scaled.
const Geometry::Circled& circle() const { return m_circle; }
enum class ObjectState : unsigned char
{
// Inside the build volume, thus printable.
Inside,
// Colliding with the build volume boundary, thus not printable and error is shown.
Colliding,
// Outside of the build volume means the object is ignored: Not printed and no error is shown.
Outside
};
// 1) Tests called on the plater.
// Using SceneEpsilon for all tests.
static constexpr const double SceneEpsilon = EPSILON;
// Called by Plater to update Inside / Colliding / Outside state of ModelObjects before slicing.
// Called from Model::update_print_volume_state() -> ModelObject::update_instances_print_volume_state()
// Using SceneEpsilon
ObjectState object_state(const indexed_triangle_set &its, const Transform3f &trafo, bool may_be_below_bed) const;
// Called by GLVolumeCollection::check_outside_state() after an object is manipulated with gizmos for example.
// Called for a rectangular bed:
ObjectState volume_state_bbox(const BoundingBoxf3 &volume_bbox) const;
// 2) Test called on G-code paths.
// Using BedEpsilon for all tests.
static constexpr const double BedEpsilon = 3. * EPSILON;
// Called on final G-code paths.
//FIXME The test does not take the thickness of the extrudates into account!
bool all_paths_inside(const GCodeProcessorResult &paths, const BoundingBoxf3 &paths_bbox) const;
// Called on initial G-code preview on OpenGL vertex buffer interleaved normals and vertices.
bool all_paths_inside_vertices_and_normals_interleaved(const std::vector<float> &paths, const Eigen::AlignedBox<float, 3> &bbox) const;
private:
// Source definition of the print bed geometry (PrintConfig::bed_shape)
std::vector<Vec2d> m_bed_shape;
// Source definition of the print volume height (PrintConfig::max_print_height)
double m_max_print_height;
// Derived values.
Type m_type { Type::Invalid };
// Geometry of the print bed, scaled copy of m_bed_shape.
Polygon m_polygon;
// Scaled snug bounding box around m_polygon.
BoundingBox m_bbox;
// 3D bounding box around m_shape, m_max_print_height.
BoundingBoxf3 m_bboxf;
// Area of m_polygon, scaled.
double m_area { 0. };
// Convex hull of m_polygon, scaled.
Polygon m_convex_hull;
// For collision detection against a convex build volume. Only filled in for m_type == Convex or Custom.
// Variant with SceneEpsilon applied.
std::pair<std::vector<Vec2d>, std::vector<Vec2d>> m_top_bottom_convex_hull_decomposition_scene;
// Variant with BedEpsilon applied.
std::pair<std::vector<Vec2d>, std::vector<Vec2d>> m_top_bottom_convex_hull_decomposition_bed;
// Smallest enclosing circle of m_polygon, scaled.
Geometry::Circled m_circle { Vec2d::Zero(), 0 };
};
} // namespace Slic3r
#endif // slic3r_BuildVolume_hpp_

View file

@ -23,6 +23,8 @@ add_library(libslic3r STATIC
BridgeDetector.hpp
Brim.cpp
Brim.hpp
BuildVolume.cpp
BuildVolume.hpp
clipper.cpp
clipper.hpp
ClipperUtils.cpp
@ -116,6 +118,8 @@ add_library(libslic3r STATIC
Geometry.hpp
Geometry/Circle.cpp
Geometry/Circle.hpp
Geometry/ConvexHull.cpp
Geometry/ConvexHull.hpp
Geometry/MedialAxis.cpp
Geometry/MedialAxis.hpp
Geometry/Voronoi.hpp

View file

@ -542,6 +542,8 @@ static inline Polygons _clipper(ClipperLib::ClipType clipType, TSubj &&subject,
return to_polygons(clipper_do<ClipperLib::Paths>(clipType, std::forward<TSubj>(subject), std::forward<TClip>(clip), ClipperLib::pftNonZero, do_safety_offset));
}
Slic3r::Polygons diff(const Slic3r::Polygon &subject, const Slic3r::Polygon &clip, ApplySafetyOffset do_safety_offset)
{ return _clipper(ClipperLib::ctDifference, ClipperUtils::SinglePathProvider(subject.points), ClipperUtils::SinglePathProvider(clip.points), do_safety_offset); }
Slic3r::Polygons diff(const Slic3r::Polygons &subject, const Slic3r::Polygons &clip, ApplySafetyOffset do_safety_offset)
{ return _clipper(ClipperLib::ctDifference, ClipperUtils::PolygonsProvider(subject), ClipperUtils::PolygonsProvider(clip), do_safety_offset); }
Slic3r::Polygons diff(const Slic3r::Polygons &subject, const Slic3r::ExPolygons &clip, ApplySafetyOffset do_safety_offset)

View file

@ -331,6 +331,8 @@ Slic3r::ExPolygons union_safety_offset_ex(const Slic3r::Polygons &polygons);
Slic3r::ExPolygons union_safety_offset_ex(const Slic3r::ExPolygons &expolygons);
// Aliases for the various offset(...) functions, conveying the purpose of the offset.
inline Slic3r::Polygons expand(const Slic3r::Polygon &polygon, const float delta, ClipperLib::JoinType joinType = DefaultJoinType, double miterLimit = DefaultMiterLimit)
{ assert(delta > 0); return offset(polygon, delta, joinType, miterLimit); }
inline Slic3r::Polygons expand(const Slic3r::Polygons &polygons, const float delta, ClipperLib::JoinType joinType = DefaultJoinType, double miterLimit = DefaultMiterLimit)
{ assert(delta > 0); return offset(polygons, delta, joinType, miterLimit); }
inline Slic3r::ExPolygons expand_ex(const Slic3r::Polygons &polygons, const float delta, ClipperLib::JoinType joinType = DefaultJoinType, double miterLimit = DefaultMiterLimit)
@ -378,6 +380,7 @@ inline Slic3r::ExPolygons opening_ex(const Slic3r::Surfaces &surfaces, const flo
Slic3r::Lines _clipper_ln(ClipperLib::ClipType clipType, const Slic3r::Lines &subject, const Slic3r::Polygons &clip);
// Safety offset is applied to the clipping polygons only.
Slic3r::Polygons diff(const Slic3r::Polygon &subject, const Slic3r::Polygon &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::Polygons diff(const Slic3r::Polygons &subject, const Slic3r::Polygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::Polygons diff(const Slic3r::Polygons &subject, const Slic3r::ExPolygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::Polygons diff(const Slic3r::ExPolygons &subject, const Slic3r::Polygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);

View file

@ -1,5 +1,5 @@
#include "ExPolygonCollection.hpp"
#include "Geometry.hpp"
#include "Geometry/ConvexHull.hpp"
namespace Slic3r {

View file

@ -4,7 +4,7 @@
#include "Exception.hpp"
#include "ExtrusionEntity.hpp"
#include "EdgeGrid.hpp"
#include "Geometry.hpp"
#include "Geometry/ConvexHull.hpp"
#include "GCode/PrintExtents.hpp"
#include "GCode/WipeTower.hpp"
#include "ShortestPath.hpp"
@ -622,7 +622,7 @@ std::vector<std::pair<coordf_t, std::vector<GCode::LayerToPrint>>> GCode::collec
namespace DoExport {
// static void update_print_estimated_times_stats(const GCodeProcessor& processor, PrintStatistics& print_statistics)
// {
// const GCodeProcessor::Result& result = processor.get_result();
// const GCodeProcessorResult& result = processor.get_result();
// print_statistics.estimated_normal_print_time = get_time_dhms(result.print_statistics.modes[static_cast<size_t>(PrintEstimatedStatistics::ETimeMode::Normal)].time);
// print_statistics.estimated_silent_print_time = processor.is_stealth_time_estimator_enabled() ?
// get_time_dhms(result.print_statistics.modes[static_cast<size_t>(PrintEstimatedStatistics::ETimeMode::Stealth)].time) : "N/A";
@ -630,7 +630,7 @@ namespace DoExport {
static void update_print_estimated_stats(const GCodeProcessor& processor, const std::vector<Extruder>& extruders, PrintStatistics& print_statistics)
{
const GCodeProcessor::Result& result = processor.get_result();
const GCodeProcessorResult& result = processor.get_result();
print_statistics.estimated_normal_print_time = get_time_dhms(result.print_statistics.modes[static_cast<size_t>(PrintEstimatedStatistics::ETimeMode::Normal)].time);
print_statistics.estimated_silent_print_time = processor.is_stealth_time_estimator_enabled() ?
get_time_dhms(result.print_statistics.modes[static_cast<size_t>(PrintEstimatedStatistics::ETimeMode::Stealth)].time) : "N/A";
@ -723,7 +723,7 @@ namespace DoExport {
}
} // namespace DoExport
void GCode::do_export(Print* print, const char* path, GCodeProcessor::Result* result, ThumbnailsGeneratorCallback thumbnail_cb)
void GCode::do_export(Print* print, const char* path, GCodeProcessorResult* result, ThumbnailsGeneratorCallback thumbnail_cb)
{
PROFILE_CLEAR();

View file

@ -143,7 +143,7 @@ public:
// throws std::runtime_exception on error,
// throws CanceledException through print->throw_if_canceled().
void do_export(Print* print, const char* path, GCodeProcessor::Result* result = nullptr, ThumbnailsGeneratorCallback thumbnail_cb = nullptr);
void do_export(Print* print, const char* path, GCodeProcessorResult* result = nullptr, ThumbnailsGeneratorCallback thumbnail_cb = nullptr);
// Exported for the helper classes (OozePrevention, Wipe) and for the Perl binding for unit tests.
const Vec2d& origin() const { return m_origin; }

View file

@ -343,7 +343,7 @@ void GCodeProcessor::TimeProcessor::reset()
machines[static_cast<size_t>(PrintEstimatedStatistics::ETimeMode::Normal)].enabled = true;
}
void GCodeProcessor::TimeProcessor::post_process(const std::string& filename, std::vector<MoveVertex>& moves, std::vector<size_t>& lines_ends)
void GCodeProcessor::TimeProcessor::post_process(const std::string& filename, std::vector<GCodeProcessorResult::MoveVertex>& moves, std::vector<size_t>& lines_ends)
{
FilePtr in{ boost::nowide::fopen(filename.c_str(), "rb") };
if (in.f == nullptr)
@ -636,7 +636,7 @@ void GCodeProcessor::TimeProcessor::post_process(const std::string& filename, st
// updates moves' gcode ids which have been modified by the insertion of the M73 lines
unsigned int curr_offset_id = 0;
unsigned int total_offset = 0;
for (MoveVertex& move : moves) {
for (GCodeProcessorResult::MoveVertex& move : moves) {
while (curr_offset_id < static_cast<unsigned int>(offsets.size()) && offsets[curr_offset_id].first <= move.gcode_id) {
total_offset += offsets[curr_offset_id].second;
++curr_offset_id;
@ -716,8 +716,8 @@ void GCodeProcessor::UsedFilaments::process_caches(GCodeProcessor* processor)
}
#if ENABLE_GCODE_VIEWER_STATISTICS
void GCodeProcessor::Result::reset() {
moves = std::vector<GCodeProcessor::MoveVertex>();
void GCodeProcessorResult::reset() {
moves = std::vector<GCodeProcessorResult::MoveVertex>();
bed_shape = Pointfs();
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
max_print_height = 0.0f;
@ -731,7 +731,7 @@ void GCodeProcessor::Result::reset() {
time = 0;
}
#else
void GCodeProcessor::Result::reset() {
void GCodeProcessorResult::reset() {
moves.clear();
lines_ends.clear();
@ -1256,7 +1256,7 @@ void GCodeProcessor::process_file(const std::string& filename, std::function<voi
m_result.filename = filename;
m_result.id = ++s_result_id;
// 1st move must be a dummy move
m_result.moves.emplace_back(MoveVertex());
m_result.moves.emplace_back(GCodeProcessorResult::MoveVertex());
size_t parse_line_callback_cntr = 10000;
m_parser.parse_file(filename, [this, cancel_callback, &parse_line_callback_cntr](GCodeReader& reader, const GCodeReader::GCodeLine& line) {
if (-- parse_line_callback_cntr == 0) {
@ -1284,7 +1284,7 @@ void GCodeProcessor::initialize(const std::string& filename)
m_result.filename = filename;
m_result.id = ++s_result_id;
// 1st move must be a dummy move
m_result.moves.emplace_back(MoveVertex());
m_result.moves.emplace_back(GCodeProcessorResult::MoveVertex());
}
void GCodeProcessor::process_buffer(const std::string &buffer)
@ -1298,7 +1298,7 @@ void GCodeProcessor::process_buffer(const std::string &buffer)
void GCodeProcessor::finalize(bool post_process)
{
// update width/height of wipe moves
for (MoveVertex& move : m_result.moves) {
for (GCodeProcessorResult::MoveVertex& move : m_result.moves) {
if (move.type == EMoveType::Wipe) {
move.width = Wipe_Width;
move.height = Wipe_Height;

View file

@ -76,6 +76,65 @@ namespace Slic3r {
}
};
struct GCodeProcessorResult
{
struct SettingsIds
{
std::string print;
std::vector<std::string> filament;
std::string printer;
void reset() {
print.clear();
filament.clear();
printer.clear();
}
};
struct MoveVertex
{
unsigned int gcode_id{ 0 };
EMoveType type{ EMoveType::Noop };
ExtrusionRole extrusion_role{ erNone };
unsigned char extruder_id{ 0 };
unsigned char cp_color_id{ 0 };
Vec3f position{ Vec3f::Zero() }; // mm
float delta_extruder{ 0.0f }; // mm
float feedrate{ 0.0f }; // mm/s
float width{ 0.0f }; // mm
float height{ 0.0f }; // mm
float mm3_per_mm{ 0.0f };
float fan_speed{ 0.0f }; // percentage
float temperature{ 0.0f }; // Celsius degrees
float time{ 0.0f }; // s
float volumetric_rate() const { return feedrate * mm3_per_mm; }
};
std::string filename;
unsigned int id;
std::vector<MoveVertex> moves;
// Positions of ends of lines of the final G-code this->filename after TimeProcessor::post_process() finalizes the G-code.
std::vector<size_t> lines_ends;
Pointfs bed_shape;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
float max_print_height;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
SettingsIds settings_ids;
size_t extruders_count;
std::vector<std::string> extruder_colors;
std::vector<float> filament_diameters;
std::vector<float> filament_densities;
PrintEstimatedStatistics print_statistics;
std::vector<CustomGCode::Item> custom_gcode_per_print_z;
#if ENABLE_GCODE_VIEWER_STATISTICS
int64_t time{ 0 };
#endif // ENABLE_GCODE_VIEWER_STATISTICS
void reset();
};
class GCodeProcessor
{
static const std::vector<std::string> Reserved_Tags;
@ -190,26 +249,6 @@ namespace Slic3r {
float time() const;
};
struct MoveVertex
{
unsigned int gcode_id{ 0 };
EMoveType type{ EMoveType::Noop };
ExtrusionRole extrusion_role{ erNone };
unsigned char extruder_id{ 0 };
unsigned char cp_color_id{ 0 };
Vec3f position{ Vec3f::Zero() }; // mm
float delta_extruder{ 0.0f }; // mm
float feedrate{ 0.0f }; // mm/s
float width{ 0.0f }; // mm
float height{ 0.0f }; // mm
float mm3_per_mm{ 0.0f };
float fan_speed{ 0.0f }; // percentage
float temperature{ 0.0f }; // Celsius degrees
float time{ 0.0f }; // s
float volumetric_rate() const { return feedrate * mm3_per_mm; }
};
private:
struct TimeMachine
{
@ -304,7 +343,7 @@ namespace Slic3r {
// post process the file with the given filename to add remaining time lines M73
// and updates moves' gcode ids accordingly
void post_process(const std::string& filename, std::vector<MoveVertex>& moves, std::vector<size_t>& lines_ends);
void post_process(const std::string& filename, std::vector<GCodeProcessorResult::MoveVertex>& moves, std::vector<size_t>& lines_ends);
};
struct UsedFilaments // filaments per ColorChange
@ -331,43 +370,6 @@ namespace Slic3r {
};
public:
struct Result
{
struct SettingsIds
{
std::string print;
std::vector<std::string> filament;
std::string printer;
void reset() {
print.clear();
filament.clear();
printer.clear();
}
};
std::string filename;
unsigned int id;
std::vector<MoveVertex> moves;
// Positions of ends of lines of the final G-code this->filename after TimeProcessor::post_process() finalizes the G-code.
std::vector<size_t> lines_ends;
Pointfs bed_shape;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
float max_print_height;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
SettingsIds settings_ids;
size_t extruders_count;
std::vector<std::string> extruder_colors;
std::vector<float> filament_diameters;
std::vector<float> filament_densities;
PrintEstimatedStatistics print_statistics;
std::vector<CustomGCode::Item> custom_gcode_per_print_z;
#if ENABLE_GCODE_VIEWER_STATISTICS
int64_t time{ 0 };
#endif // ENABLE_GCODE_VIEWER_STATISTICS
void reset();
};
class SeamsDetector
{
bool m_active{ false };
@ -394,12 +396,12 @@ namespace Slic3r {
// custom gcode markes
class OptionsZCorrector
{
Result& m_result;
GCodeProcessorResult& m_result;
std::optional<size_t> m_move_id;
std::optional<size_t> m_custom_gcode_per_print_z_id;
public:
explicit OptionsZCorrector(Result& result) : m_result(result) {
explicit OptionsZCorrector(GCodeProcessorResult& result) : m_result(result) {
}
void set() {
@ -413,7 +415,7 @@ namespace Slic3r {
const Vec3f position = m_result.moves.back().position;
MoveVertex& move = m_result.moves.emplace_back(m_result.moves[*m_move_id]);
GCodeProcessorResult::MoveVertex& move = m_result.moves.emplace_back(m_result.moves[*m_move_id]);
move.position = position;
move.height = height;
m_result.moves.erase(m_result.moves.begin() + *m_move_id);
@ -562,7 +564,7 @@ namespace Slic3r {
TimeProcessor m_time_processor;
UsedFilaments m_used_filaments;
Result m_result;
GCodeProcessorResult m_result;
static unsigned int s_result_id;
#if ENABLE_GCODE_VIEWER_DATA_CHECKING
@ -582,8 +584,8 @@ namespace Slic3r {
void enable_machine_envelope_processing(bool enabled) { m_time_processor.machine_envelope_processing_enabled = enabled; }
void reset();
const Result& get_result() const { return m_result; }
Result&& extract_result() { return std::move(m_result); }
const GCodeProcessorResult& get_result() const { return m_result; }
GCodeProcessorResult&& extract_result() { return std::move(m_result); }
// Load a G-code into a stand-alone G-code viewer.
// throws CanceledException through print->throw_if_canceled() (sent by the caller as callback).

View file

@ -24,107 +24,8 @@
#define BOOST_NO_CXX17_HDR_STRING_VIEW
#endif
#include <boost/multiprecision/integer.hpp>
namespace Slic3r { namespace Geometry {
// This implementation is based on Andrew's monotone chain 2D convex hull algorithm
Polygon convex_hull(Points pts)
{
std::sort(pts.begin(), pts.end(), [](const Point& a, const Point& b) { return a.x() < b.x() || (a.x() == b.x() && a.y() < b.y()); });
pts.erase(std::unique(pts.begin(), pts.end(), [](const Point& a, const Point& b) { return a.x() == b.x() && a.y() == b.y(); }), pts.end());
Polygon hull;
int n = (int)pts.size();
if (n >= 3) {
int k = 0;
hull.points.resize(2 * n);
// Build lower hull
for (int i = 0; i < n; ++ i) {
while (k >= 2 && pts[i].ccw(hull[k-2], hull[k-1]) <= 0)
-- k;
hull[k ++] = pts[i];
}
// Build upper hull
for (int i = n-2, t = k+1; i >= 0; i--) {
while (k >= t && pts[i].ccw(hull[k-2], hull[k-1]) <= 0)
-- k;
hull[k ++] = pts[i];
}
hull.points.resize(k);
assert(hull.points.front() == hull.points.back());
hull.points.pop_back();
}
return hull;
}
Pointf3s convex_hull(Pointf3s points)
{
assert(points.size() >= 3);
// sort input points
std::sort(points.begin(), points.end(), [](const Vec3d &a, const Vec3d &b){ return a.x() < b.x() || (a.x() == b.x() && a.y() < b.y()); });
int n = points.size(), k = 0;
Pointf3s hull;
if (n >= 3)
{
hull.resize(2 * n);
// Build lower hull
for (int i = 0; i < n; ++i)
{
Point p = Point::new_scale(points[i](0), points[i](1));
while (k >= 2)
{
Point k1 = Point::new_scale(hull[k - 1](0), hull[k - 1](1));
Point k2 = Point::new_scale(hull[k - 2](0), hull[k - 2](1));
if (p.ccw(k2, k1) <= 0)
--k;
else
break;
}
hull[k++] = points[i];
}
// Build upper hull
for (int i = n - 2, t = k + 1; i >= 0; --i)
{
Point p = Point::new_scale(points[i](0), points[i](1));
while (k >= t)
{
Point k1 = Point::new_scale(hull[k - 1](0), hull[k - 1](1));
Point k2 = Point::new_scale(hull[k - 2](0), hull[k - 2](1));
if (p.ccw(k2, k1) <= 0)
--k;
else
break;
}
hull[k++] = points[i];
}
hull.resize(k);
assert(hull.front() == hull.back());
hull.pop_back();
}
return hull;
}
Polygon convex_hull(const Polygons &polygons)
{
Points pp;
for (Polygons::const_iterator p = polygons.begin(); p != polygons.end(); ++p) {
pp.insert(pp.end(), p->points.begin(), p->points.end());
}
return convex_hull(std::move(pp));
}
bool directions_parallel(double angle1, double angle2, double max_diff)
{
double diff = fabs(angle1 - angle2);
@ -761,205 +662,4 @@ double rotation_diff_z(const Vec3d &rot_xyz_from, const Vec3d &rot_xyz_to)
return (axis.z() < 0) ? -angle : angle;
}
namespace rotcalip {
using int256_t = boost::multiprecision::int256_t;
using int128_t = boost::multiprecision::int128_t;
template<class Scalar = int64_t>
inline Scalar magnsq(const Point &p)
{
return Scalar(p.x()) * p.x() + Scalar(p.y()) * p.y();
}
template<class Scalar = int64_t>
inline Scalar dot(const Point &a, const Point &b)
{
return Scalar(a.x()) * b.x() + Scalar(a.y()) * b.y();
}
template<class Scalar = int64_t>
inline Scalar dotperp(const Point &a, const Point &b)
{
return Scalar(a.x()) * b.y() - Scalar(a.y()) * b.x();
}
using boost::multiprecision::abs;
// Compares the angle enclosed by vectors dir and dirA (alpha) with the angle
// enclosed by -dir and dirB (beta). Returns -1 if alpha is less than beta, 0
// if they are equal and 1 if alpha is greater than beta. Note that dir is
// reversed for beta, because it represents the opposite side of a caliper.
int cmp_angles(const Point &dir, const Point &dirA, const Point &dirB) {
int128_t dotA = dot(dir, dirA);
int128_t dotB = dot(-dir, dirB);
int256_t dcosa = int256_t(magnsq(dirB)) * int256_t(abs(dotA)) * dotA;
int256_t dcosb = int256_t(magnsq(dirA)) * int256_t(abs(dotB)) * dotB;
int256_t diff = dcosa - dcosb;
return diff > 0? -1 : (diff < 0 ? 1 : 0);
}
// A helper class to navigate on a polygon. Given a vertex index, one can
// get the edge belonging to that vertex, the coordinates of the vertex, the
// next and previous edges. Stuff that is needed in the rotating calipers algo.
class Idx
{
size_t m_idx;
const Polygon *m_poly;
public:
explicit Idx(const Polygon &p): m_idx{0}, m_poly{&p} {}
explicit Idx(size_t idx, const Polygon &p): m_idx{idx}, m_poly{&p} {}
size_t idx() const { return m_idx; }
void set_idx(size_t i) { m_idx = i; }
size_t next() const { return (m_idx + 1) % m_poly->size(); }
size_t inc() { return m_idx = (m_idx + 1) % m_poly->size(); }
Point prev_dir() const {
return pt() - (*m_poly)[(m_idx + m_poly->size() - 1) % m_poly->size()];
}
const Point &pt() const { return (*m_poly)[m_idx]; }
const Point dir() const { return (*m_poly)[next()] - pt(); }
const Point next_dir() const
{
return (*m_poly)[(m_idx + 2) % m_poly->size()] - (*m_poly)[next()];
}
const Polygon &poly() const { return *m_poly; }
};
enum class AntipodalVisitMode { Full, EdgesOnly };
// Visit all antipodal pairs starting from the initial ia, ib pair which
// has to be a valid antipodal pair (not checked). fn is called for every
// antipodal pair encountered including the initial one.
// The callback Fn has a signiture of bool(size_t i, size_t j, const Point &dir)
// where i,j are the vertex indices of the antipodal pair and dir is the
// direction of the calipers touching the i vertex.
template<AntipodalVisitMode mode = AntipodalVisitMode::Full, class Fn>
void visit_antipodals (Idx& ia, Idx &ib, Fn &&fn)
{
// Set current caliper direction to be the lower edge angle from X axis
int cmp = cmp_angles(ia.prev_dir(), ia.dir(), ib.dir());
Idx *current = cmp <= 0 ? &ia : &ib, *other = cmp <= 0 ? &ib : &ia;
Idx *initial = current;
bool visitor_continue = true;
size_t start = initial->idx();
bool finished = false;
while (visitor_continue && !finished) {
Point current_dir_a = current == &ia ? current->dir() : -current->dir();
visitor_continue = fn(ia.idx(), ib.idx(), current_dir_a);
// Parallel edges encountered. An additional pair of antipodals
// can be yielded.
if constexpr (mode == AntipodalVisitMode::Full)
if (cmp == 0 && visitor_continue) {
visitor_continue = fn(current == &ia ? ia.idx() : ia.next(),
current == &ib ? ib.idx() : ib.next(),
current_dir_a);
}
cmp = cmp_angles(current->dir(), current->next_dir(), other->dir());
current->inc();
if (cmp > 0) {
std::swap(current, other);
}
if (initial->idx() == start) finished = true;
}
}
} // namespace rotcalip
bool convex_polygons_intersect(const Polygon &A, const Polygon &B)
{
using namespace rotcalip;
// Establish starting antipodals as extremes in XY plane. Use the
// easily obtainable bounding boxes to check if A and B is disjoint
// and return false if the are.
struct BB
{
size_t xmin = 0, xmax = 0, ymin = 0, ymax = 0;
const Polygon &P;
static bool cmpy(const Point &l, const Point &u)
{
return l.y() < u.y() || (l.y() == u.y() && l.x() < u.x());
}
BB(const Polygon &poly): P{poly}
{
for (size_t i = 0; i < P.size(); ++i) {
if (P[i] < P[xmin]) xmin = i;
if (P[xmax] < P[i]) xmax = i;
if (cmpy(P[i], P[ymin])) ymin = i;
if (cmpy(P[ymax], P[i])) ymax = i;
}
}
};
BB bA{A}, bB{B};
BoundingBox bbA{{A[bA.xmin].x(), A[bA.ymin].y()}, {A[bA.xmax].x(), A[bA.ymax].y()}};
BoundingBox bbB{{B[bB.xmin].x(), B[bB.ymin].y()}, {B[bB.xmax].x(), B[bB.ymax].y()}};
// if (!bbA.overlap(bbB))
// return false;
// Establish starting antipodals as extreme vertex pairs in X or Y direction
// which reside on different polygons. If no such pair is found, the two
// polygons are certainly not disjoint.
Idx imin{bA.xmin, A}, imax{bB.xmax, B};
if (B[bB.xmin] < imin.pt()) imin = Idx{bB.xmin, B};
if (imax.pt() < A[bA.xmax]) imax = Idx{bA.xmax, A};
if (&imin.poly() == &imax.poly()) {
imin = Idx{bA.ymin, A};
imax = Idx{bB.ymax, B};
if (B[bB.ymin] < imin.pt()) imin = Idx{bB.ymin, B};
if (imax.pt() < A[bA.ymax]) imax = Idx{bA.ymax, A};
}
if (&imin.poly() == &imax.poly())
return true;
bool found_divisor = false;
visit_antipodals<AntipodalVisitMode::EdgesOnly>(
imin, imax,
[&imin, &imax, &found_divisor](size_t ia, size_t ib, const Point &dir) {
// std::cout << "A" << ia << " B" << ib << " dir " <<
// dir.x() << " " << dir.y() << std::endl;
const Polygon &A = imin.poly(), &B = imax.poly();
Point ref_a = A[(ia + 2) % A.size()], ref_b = B[(ib + 2) % B.size()];
bool is_left_a = dotperp( dir, ref_a - A[ia]) > 0;
bool is_left_b = dotperp(-dir, ref_b - B[ib]) > 0;
// If both reference points are on the left (or right) of their
// respective support lines and the opposite support line is to
// the right (or left), the divisor line is found. We only test
// the reference point, as by definition, if that is on one side,
// all the other points must be on the same side of a support
// line. If the support lines are collinear, the polygons must be
// on the same side of their respective support lines.
auto d = dotperp(dir, B[ib] - A[ia]);
if (d == 0) {
// The caliper lines are collinear, not just parallel
found_divisor = (is_left_a && is_left_b) || (!is_left_a && !is_left_b);
} else if (d > 0) { // B is to the left of (A, A+1)
found_divisor = !is_left_a && !is_left_b;
} else { // B is to the right of (A, A+1)
found_divisor = is_left_a && is_left_b;
}
return !found_divisor;
});
// Intersects if the divisor was not found
return !found_divisor;
}
}} // namespace Slic3r::Geometry

View file

@ -72,32 +72,6 @@ static inline bool is_ccw(const Polygon &poly)
return o == ORIENTATION_CCW;
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// returns true if the given polygons are identical
static inline bool are_approx(const Polygon& lhs, const Polygon& rhs)
{
if (lhs.points.size() != rhs.points.size())
return false;
size_t rhs_id = 0;
while (rhs_id < rhs.points.size()) {
if (rhs.points[rhs_id].isApprox(lhs.points.front()))
break;
++rhs_id;
}
if (rhs_id == rhs.points.size())
return false;
for (size_t i = 0; i < lhs.points.size(); ++i) {
if (!lhs.points[i].isApprox(rhs.points[(i + rhs_id) % lhs.points.size()]))
return false;
}
return true;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
inline bool ray_ray_intersection(const Vec2d &p1, const Vec2d &v1, const Vec2d &p2, const Vec2d &v2, Vec2d &res)
{
double denom = v1(0) * v2(1) - v2(0) * v1(1);
@ -313,10 +287,6 @@ bool liang_barsky_line_clipping(
return liang_barsky_line_clipping(x0clip, x1clip, bbox);
}
Pointf3s convex_hull(Pointf3s points);
Polygon convex_hull(Points points);
Polygon convex_hull(const Polygons &polygons);
bool directions_parallel(double angle1, double angle2, double max_diff = 0);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool directions_perpendicular(double angle1, double angle2, double max_diff = 0);
@ -479,10 +449,6 @@ inline bool is_rotation_ninety_degrees(const Vec3d &rotation)
return is_rotation_ninety_degrees(rotation.x()) && is_rotation_ninety_degrees(rotation.y()) && is_rotation_ninety_degrees(rotation.z());
}
// Returns true if the intersection of the two convex polygons A and B
// is not an empty set.
bool convex_polygons_intersect(const Polygon &A, const Polygon &B);
} } // namespace Slicer::Geometry
#endif

View file

@ -3,6 +3,7 @@
#include "../Polygon.hpp"
#include <numeric>
#include <random>
#include <boost/log/trivial.hpp>
namespace Slic3r { namespace Geometry {
@ -94,4 +95,44 @@ Vec2d circle_center_taubin_newton(const Vec2ds::const_iterator& input_begin, con
return center + centroid;
}
Circled circle_taubin_newton(const Vec2ds& input, size_t cycles)
{
Circled out;
if (input.size() < 3) {
out = Circled::make_invalid();
} else {
out.center = circle_center_taubin_newton(input, cycles);
out.radius = std::accumulate(input.begin(), input.end(), 0., [&out](double acc, const Vec2d& pt) { return (pt - out.center).norm() + acc; });
out.radius /= double(input.size());
}
return out;
}
Circled circle_ransac(const Vec2ds& input, size_t iterations)
{
if (input.size() < 3)
return Circled::make_invalid();
std::mt19937 rng;
std::vector<Vec2d> samples;
Circled circle_best = Circled::make_invalid();
double err_min = std::numeric_limits<double>::max();
for (size_t iter = 0; iter < iterations; ++ iter) {
samples.clear();
std::sample(input.begin(), input.end(), std::back_inserter(samples), 3, rng);
Circled c;
c.center = Geometry::circle_center(samples[0], samples[1], samples[2], EPSILON);
c.radius = std::accumulate(input.begin(), input.end(), 0., [&c](double acc, const Vec2d& pt) { return (pt - c.center).norm() + acc; });
c.radius /= double(input.size());
double err = 0;
for (const Vec2d &pt : input)
err = std::max(err, std::abs((pt - c.center).norm() - c.radius));
if (err < err_min) {
err_min = err;
circle_best = c;
}
}
return circle_best;
}
} } // namespace Slic3r::Geometry

View file

@ -7,14 +7,6 @@
namespace Slic3r { namespace Geometry {
/// Find the center of the circle corresponding to the vector of Points as an arc.
Point circle_center_taubin_newton(const Points::const_iterator& input_start, const Points::const_iterator& input_end, size_t cycles = 20);
inline Point circle_center_taubin_newton(const Points& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
/// Find the center of the circle corresponding to the vector of Pointfs as an arc.
Vec2d circle_center_taubin_newton(const Vec2ds::const_iterator& input_start, const Vec2ds::const_iterator& input_end, size_t cycles = 20);
inline Vec2d circle_center_taubin_newton(const Vec2ds& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
// https://en.wikipedia.org/wiki/Circumscribed_circle
// Circumcenter coordinates, Cartesian coordinates
template<typename Vector>
@ -100,6 +92,18 @@ using Circled = Circle<Vec2d>;
using CircleSqf = CircleSq<Vec2f>;
using CircleSqd = CircleSq<Vec2d>;
/// Find the center of the circle corresponding to the vector of Points as an arc.
Point circle_center_taubin_newton(const Points::const_iterator& input_start, const Points::const_iterator& input_end, size_t cycles = 20);
inline Point circle_center_taubin_newton(const Points& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
/// Find the center of the circle corresponding to the vector of Pointfs as an arc.
Vec2d circle_center_taubin_newton(const Vec2ds::const_iterator& input_start, const Vec2ds::const_iterator& input_end, size_t cycles = 20);
inline Vec2d circle_center_taubin_newton(const Vec2ds& input, size_t cycles = 20) { return circle_center_taubin_newton(input.cbegin(), input.cend(), cycles); }
Circled circle_taubin_newton(const Vec2ds& input, size_t cycles = 20);
// Find circle using RANSAC randomized algorithm.
Circled circle_ransac(const Vec2ds& input, size_t iterations = 20);
// Randomized algorithm by Emo Welzl, working with squared radii for efficiency. The returned circle radius is inflated by epsilon.
template<typename Vector, typename Points>
CircleSq<Vector> smallest_enclosing_circle2_welzl(const Points &points, const typename Vector::Scalar epsilon)

View file

@ -0,0 +1,398 @@
#include "libslic3r.h"
#include "ConvexHull.hpp"
#include <boost/multiprecision/integer.hpp>
namespace Slic3r { namespace Geometry {
// This implementation is based on Andrew's monotone chain 2D convex hull algorithm
Polygon convex_hull(Points pts)
{
std::sort(pts.begin(), pts.end(), [](const Point& a, const Point& b) { return a.x() < b.x() || (a.x() == b.x() && a.y() < b.y()); });
pts.erase(std::unique(pts.begin(), pts.end(), [](const Point& a, const Point& b) { return a.x() == b.x() && a.y() == b.y(); }), pts.end());
Polygon hull;
int n = (int)pts.size();
if (n >= 3) {
int k = 0;
hull.points.resize(2 * n);
// Build lower hull
for (int i = 0; i < n; ++ i) {
while (k >= 2 && pts[i].ccw(hull[k-2], hull[k-1]) <= 0)
-- k;
hull[k ++] = pts[i];
}
// Build upper hull
for (int i = n-2, t = k+1; i >= 0; i--) {
while (k >= t && pts[i].ccw(hull[k-2], hull[k-1]) <= 0)
-- k;
hull[k ++] = pts[i];
}
hull.points.resize(k);
assert(hull.points.front() == hull.points.back());
hull.points.pop_back();
}
return hull;
}
Pointf3s convex_hull(Pointf3s points)
{
assert(points.size() >= 3);
// sort input points
std::sort(points.begin(), points.end(), [](const Vec3d &a, const Vec3d &b){ return a.x() < b.x() || (a.x() == b.x() && a.y() < b.y()); });
int n = points.size(), k = 0;
Pointf3s hull;
if (n >= 3)
{
hull.resize(2 * n);
// Build lower hull
for (int i = 0; i < n; ++i)
{
Point p = Point::new_scale(points[i](0), points[i](1));
while (k >= 2)
{
Point k1 = Point::new_scale(hull[k - 1](0), hull[k - 1](1));
Point k2 = Point::new_scale(hull[k - 2](0), hull[k - 2](1));
if (p.ccw(k2, k1) <= 0)
--k;
else
break;
}
hull[k++] = points[i];
}
// Build upper hull
for (int i = n - 2, t = k + 1; i >= 0; --i)
{
Point p = Point::new_scale(points[i](0), points[i](1));
while (k >= t)
{
Point k1 = Point::new_scale(hull[k - 1](0), hull[k - 1](1));
Point k2 = Point::new_scale(hull[k - 2](0), hull[k - 2](1));
if (p.ccw(k2, k1) <= 0)
--k;
else
break;
}
hull[k++] = points[i];
}
hull.resize(k);
assert(hull.front() == hull.back());
hull.pop_back();
}
return hull;
}
Polygon convex_hull(const Polygons &polygons)
{
Points pp;
for (Polygons::const_iterator p = polygons.begin(); p != polygons.end(); ++p) {
pp.insert(pp.end(), p->points.begin(), p->points.end());
}
return convex_hull(std::move(pp));
}
namespace rotcalip {
using int256_t = boost::multiprecision::int256_t;
using int128_t = boost::multiprecision::int128_t;
template<class Scalar = int64_t>
inline Scalar magnsq(const Point &p)
{
return Scalar(p.x()) * p.x() + Scalar(p.y()) * p.y();
}
template<class Scalar = int64_t>
inline Scalar dot(const Point &a, const Point &b)
{
return Scalar(a.x()) * b.x() + Scalar(a.y()) * b.y();
}
template<class Scalar = int64_t>
inline Scalar dotperp(const Point &a, const Point &b)
{
return Scalar(a.x()) * b.y() - Scalar(a.y()) * b.x();
}
using boost::multiprecision::abs;
// Compares the angle enclosed by vectors dir and dirA (alpha) with the angle
// enclosed by -dir and dirB (beta). Returns -1 if alpha is less than beta, 0
// if they are equal and 1 if alpha is greater than beta. Note that dir is
// reversed for beta, because it represents the opposite side of a caliper.
int cmp_angles(const Point &dir, const Point &dirA, const Point &dirB) {
int128_t dotA = dot(dir, dirA);
int128_t dotB = dot(-dir, dirB);
int256_t dcosa = int256_t(magnsq(dirB)) * int256_t(abs(dotA)) * dotA;
int256_t dcosb = int256_t(magnsq(dirA)) * int256_t(abs(dotB)) * dotB;
int256_t diff = dcosa - dcosb;
return diff > 0? -1 : (diff < 0 ? 1 : 0);
}
// A helper class to navigate on a polygon. Given a vertex index, one can
// get the edge belonging to that vertex, the coordinates of the vertex, the
// next and previous edges. Stuff that is needed in the rotating calipers algo.
class Idx
{
size_t m_idx;
const Polygon *m_poly;
public:
explicit Idx(const Polygon &p): m_idx{0}, m_poly{&p} {}
explicit Idx(size_t idx, const Polygon &p): m_idx{idx}, m_poly{&p} {}
size_t idx() const { return m_idx; }
void set_idx(size_t i) { m_idx = i; }
size_t next() const { return (m_idx + 1) % m_poly->size(); }
size_t inc() { return m_idx = (m_idx + 1) % m_poly->size(); }
Point prev_dir() const {
return pt() - (*m_poly)[(m_idx + m_poly->size() - 1) % m_poly->size()];
}
const Point &pt() const { return (*m_poly)[m_idx]; }
const Point dir() const { return (*m_poly)[next()] - pt(); }
const Point next_dir() const
{
return (*m_poly)[(m_idx + 2) % m_poly->size()] - (*m_poly)[next()];
}
const Polygon &poly() const { return *m_poly; }
};
enum class AntipodalVisitMode { Full, EdgesOnly };
// Visit all antipodal pairs starting from the initial ia, ib pair which
// has to be a valid antipodal pair (not checked). fn is called for every
// antipodal pair encountered including the initial one.
// The callback Fn has a signiture of bool(size_t i, size_t j, const Point &dir)
// where i,j are the vertex indices of the antipodal pair and dir is the
// direction of the calipers touching the i vertex.
template<AntipodalVisitMode mode = AntipodalVisitMode::Full, class Fn>
void visit_antipodals (Idx& ia, Idx &ib, Fn &&fn)
{
// Set current caliper direction to be the lower edge angle from X axis
int cmp = cmp_angles(ia.prev_dir(), ia.dir(), ib.dir());
Idx *current = cmp <= 0 ? &ia : &ib, *other = cmp <= 0 ? &ib : &ia;
Idx *initial = current;
bool visitor_continue = true;
size_t start = initial->idx();
bool finished = false;
while (visitor_continue && !finished) {
Point current_dir_a = current == &ia ? current->dir() : -current->dir();
visitor_continue = fn(ia.idx(), ib.idx(), current_dir_a);
// Parallel edges encountered. An additional pair of antipodals
// can be yielded.
if constexpr (mode == AntipodalVisitMode::Full)
if (cmp == 0 && visitor_continue) {
visitor_continue = fn(current == &ia ? ia.idx() : ia.next(),
current == &ib ? ib.idx() : ib.next(),
current_dir_a);
}
cmp = cmp_angles(current->dir(), current->next_dir(), other->dir());
current->inc();
if (cmp > 0) {
std::swap(current, other);
}
if (initial->idx() == start) finished = true;
}
}
} // namespace rotcalip
bool convex_polygons_intersect(const Polygon &A, const Polygon &B)
{
using namespace rotcalip;
// Establish starting antipodals as extremes in XY plane. Use the
// easily obtainable bounding boxes to check if A and B is disjoint
// and return false if the are.
struct BB
{
size_t xmin = 0, xmax = 0, ymin = 0, ymax = 0;
const Polygon &P;
static bool cmpy(const Point &l, const Point &u)
{
return l.y() < u.y() || (l.y() == u.y() && l.x() < u.x());
}
BB(const Polygon &poly): P{poly}
{
for (size_t i = 0; i < P.size(); ++i) {
if (P[i] < P[xmin]) xmin = i;
if (P[xmax] < P[i]) xmax = i;
if (cmpy(P[i], P[ymin])) ymin = i;
if (cmpy(P[ymax], P[i])) ymax = i;
}
}
};
BB bA{A}, bB{B};
BoundingBox bbA{{A[bA.xmin].x(), A[bA.ymin].y()}, {A[bA.xmax].x(), A[bA.ymax].y()}};
BoundingBox bbB{{B[bB.xmin].x(), B[bB.ymin].y()}, {B[bB.xmax].x(), B[bB.ymax].y()}};
// if (!bbA.overlap(bbB))
// return false;
// Establish starting antipodals as extreme vertex pairs in X or Y direction
// which reside on different polygons. If no such pair is found, the two
// polygons are certainly not disjoint.
Idx imin{bA.xmin, A}, imax{bB.xmax, B};
if (B[bB.xmin] < imin.pt()) imin = Idx{bB.xmin, B};
if (imax.pt() < A[bA.xmax]) imax = Idx{bA.xmax, A};
if (&imin.poly() == &imax.poly()) {
imin = Idx{bA.ymin, A};
imax = Idx{bB.ymax, B};
if (B[bB.ymin] < imin.pt()) imin = Idx{bB.ymin, B};
if (imax.pt() < A[bA.ymax]) imax = Idx{bA.ymax, A};
}
if (&imin.poly() == &imax.poly())
return true;
bool found_divisor = false;
visit_antipodals<AntipodalVisitMode::EdgesOnly>(
imin, imax,
[&imin, &imax, &found_divisor](size_t ia, size_t ib, const Point &dir) {
// std::cout << "A" << ia << " B" << ib << " dir " <<
// dir.x() << " " << dir.y() << std::endl;
const Polygon &A = imin.poly(), &B = imax.poly();
Point ref_a = A[(ia + 2) % A.size()], ref_b = B[(ib + 2) % B.size()];
bool is_left_a = dotperp( dir, ref_a - A[ia]) > 0;
bool is_left_b = dotperp(-dir, ref_b - B[ib]) > 0;
// If both reference points are on the left (or right) of their
// respective support lines and the opposite support line is to
// the right (or left), the divisor line is found. We only test
// the reference point, as by definition, if that is on one side,
// all the other points must be on the same side of a support
// line. If the support lines are collinear, the polygons must be
// on the same side of their respective support lines.
auto d = dotperp(dir, B[ib] - A[ia]);
if (d == 0) {
// The caliper lines are collinear, not just parallel
found_divisor = (is_left_a && is_left_b) || (!is_left_a && !is_left_b);
} else if (d > 0) { // B is to the left of (A, A+1)
found_divisor = !is_left_a && !is_left_b;
} else { // B is to the right of (A, A+1)
found_divisor = is_left_a && is_left_b;
}
return !found_divisor;
});
// Intersects if the divisor was not found
return !found_divisor;
}
// Decompose source convex hull points into a top / bottom chains with monotonically increasing x,
// creating an implicit trapezoidal decomposition of the source convex polygon.
// The source convex polygon has to be CCW oriented. O(n) time complexity.
std::pair<std::vector<Vec2d>, std::vector<Vec2d>> decompose_convex_polygon_top_bottom(const std::vector<Vec2d> &src)
{
std::pair<std::vector<Vec2d>, std::vector<Vec2d>> out;
std::vector<Vec2d> &bottom = out.first;
std::vector<Vec2d> &top = out.second;
// Find the minimum point.
auto left_bottom = std::min_element(src.begin(), src.end(), [](const auto &l, const auto &r) { return l.x() < r.x() || (l.x() == r.x() && l.y() < r.y()); });
auto right_top = std::max_element(src.begin(), src.end(), [](const auto &l, const auto &r) { return l.x() < r.x() || (l.x() == r.x() && l.y() < r.y()); });
if (left_bottom != src.end() && left_bottom != right_top) {
// Produce the bottom and bottom chains.
if (left_bottom < right_top) {
bottom.assign(left_bottom, right_top + 1);
size_t cnt = (src.end() - right_top) + (left_bottom + 1 - src.begin());
top.reserve(cnt);
top.assign(right_top, src.end());
top.insert(top.end(), src.begin(), left_bottom + 1);
} else {
size_t cnt = (src.end() - left_bottom) + (right_top + 1 - src.begin());
bottom.reserve(cnt);
bottom.assign(left_bottom, src.end());
bottom.insert(bottom.end(), src.begin(), right_top + 1);
top.assign(right_top, left_bottom + 1);
}
// Remove strictly vertical segments at the end.
if (bottom.size() > 1) {
auto it = bottom.end();
for (-- it; it != bottom.begin() && (it - 1)->x() == bottom.back().x(); -- it) ;
bottom.erase(it + 1, bottom.end());
}
if (top.size() > 1) {
auto it = top.end();
for (-- it; it != top.begin() && (it - 1)->x() == top.back().x(); -- it) ;
top.erase(it + 1, top.end());
}
std::reverse(top.begin(), top.end());
}
if (top.size() < 2 || bottom.size() < 2) {
// invalid
top.clear();
bottom.clear();
}
return out;
}
// Convex polygon check using a top / bottom chain decomposition with O(log n) time complexity.
bool inside_convex_polygon(const std::pair<std::vector<Vec2d>, std::vector<Vec2d>> &top_bottom_decomposition, const Vec2d &pt)
{
auto it_bottom = std::lower_bound(top_bottom_decomposition.first.begin(), top_bottom_decomposition.first.end(), pt, [](const auto &l, const auto &r){ return l.x() < r.x(); });
auto it_top = std::lower_bound(top_bottom_decomposition.second.begin(), top_bottom_decomposition.second.end(), pt, [](const auto &l, const auto &r){ return l.x() < r.x(); });
if (it_bottom == top_bottom_decomposition.first.end()) {
// Above max x.
assert(it_top == top_bottom_decomposition.second.end());
return false;
}
if (it_bottom == top_bottom_decomposition.first.begin()) {
// Below or at min x.
if (pt.x() < it_bottom->x()) {
// Below min x.
assert(pt.x() < it_top->x());
return false;
}
// At min x.
assert(pt.x() == it_bottom->x());
assert(pt.x() == it_top->x());
assert(it_bottom->y() <= pt.y() <= it_top->y());
return pt.y() >= it_bottom->y() && pt.y() <= it_top->y();
}
// Trapezoid or a triangle.
assert(it_bottom != top_bottom_decomposition.first .begin() && it_bottom != top_bottom_decomposition.first .end());
assert(it_top != top_bottom_decomposition.second.begin() && it_top != top_bottom_decomposition.second.end());
assert(pt.x() <= it_bottom->x());
assert(pt.x() <= it_top->x());
auto it_top_prev = it_top - 1;
auto it_bottom_prev = it_bottom - 1;
assert(pt.x() >= it_top_prev->x());
assert(pt.x() >= it_bottom_prev->x());
double det = cross2(*it_bottom - *it_bottom_prev, pt - *it_bottom_prev);
if (det < 0)
return false;
det = cross2(*it_top - *it_top_prev, pt - *it_top_prev);
return det <= 0;
}
} // namespace Geometry
} // namespace Slic3r

View file

@ -0,0 +1,27 @@
#ifndef slic3r_Geometry_ConvexHull_hpp_
#define slic3r_Geometry_ConvexHull_hpp_
#include "../Polygon.hpp"
namespace Slic3r {
namespace Geometry {
Pointf3s convex_hull(Pointf3s points);
Polygon convex_hull(Points points);
Polygon convex_hull(const Polygons &polygons);
// Returns true if the intersection of the two convex polygons A and B
// is not an empty set.
bool convex_polygons_intersect(const Polygon &A, const Polygon &B);
// Decompose source convex hull points into top / bottom chains with monotonically increasing x,
// creating an implicit trapezoidal decomposition of the source convex polygon.
// The source convex polygon has to be CCW oriented. O(n) time complexity.
std::pair<std::vector<Vec2d>, std::vector<Vec2d>> decompose_convex_polygon_top_bottom(const std::vector<Vec2d> &src);
// Convex polygon check using a top / bottom chain decomposition with O(log n) time complexity.
bool inside_convex_polygon(const std::pair<std::vector<Vec2d>, std::vector<Vec2d>> &top_bottom_decomposition, const Vec2d &pt);
} } // namespace Slicer::Geometry
#endif

View file

@ -1,8 +1,9 @@
#include "libslic3r.h"
#include "BuildVolume.hpp"
#include "Exception.hpp"
#include "Model.hpp"
#include "ModelArrange.hpp"
#include "Geometry.hpp"
#include "Geometry/ConvexHull.hpp"
#include "MTUtils.hpp"
#include "TriangleMeshSlicer.hpp"
#include "TriangleSelector.hpp"
@ -26,39 +27,6 @@
namespace Slic3r {
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// Using rotating callipers to check for collision of two convex polygons. Thus both printbed_shape and obj_hull_2d are convex polygons.
ModelInstanceEPrintVolumeState printbed_collision_state(const Polygon& printbed_shape, double print_volume_height, const Polygon& obj_hull_2d, double obj_min_z, double obj_max_z)
{
if (!Geometry::convex_polygons_intersect(printbed_shape, obj_hull_2d))
return ModelInstancePVS_Fully_Outside;
bool contained_xy = true;
for (const Point& p : obj_hull_2d) {
if (!printbed_shape.contains(p)) {
contained_xy = false;
break;
}
}
const bool contained_z = -1e10 < obj_min_z && obj_max_z <= print_volume_height;
return (contained_xy && contained_z) ? ModelInstancePVS_Inside : ModelInstancePVS_Partly_Outside;
}
/*
ModelInstanceEPrintVolumeState printbed_collision_state(const Polygon& printbed_shape, double print_volume_height, const BoundingBoxf3& box)
{
const Polygon box_hull_2d({
{ scale_(box.min.x()), scale_(box.min.y()) },
{ scale_(box.max.x()), scale_(box.min.y()) },
{ scale_(box.max.x()), scale_(box.max.y()) },
{ scale_(box.min.x()), scale_(box.max.y()) }
});
return printbed_collision_state(printbed_shape, print_volume_height, box_hull_2d, box.min.z(), box.max.z());
}
*/
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Model& Model::assign_copy(const Model &rhs)
{
this->copy_id(rhs);
@ -363,24 +331,13 @@ BoundingBoxf3 Model::bounding_box() const
return bb;
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// printbed_shape is convex polygon
unsigned int Model::update_print_volume_state(const Polygon& printbed_shape, double print_volume_height)
unsigned int Model::update_print_volume_state(const BuildVolume &build_volume)
{
unsigned int num_printable = 0;
for (ModelObject* model_object : this->objects)
num_printable += model_object->check_instances_print_volume_state(printbed_shape, print_volume_height);
num_printable += model_object->update_instances_print_volume_state(build_volume);
return num_printable;
}
#else
unsigned int Model::update_print_volume_state(const BoundingBoxf3 &print_volume)
{
unsigned int num_printable = 0;
for (ModelObject *model_object : this->objects)
num_printable += model_object->check_instances_print_volume_state(print_volume);
return num_printable;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool Model::center_instances_around_point(const Vec2d &point)
{
@ -1572,9 +1529,7 @@ double ModelObject::get_instance_max_z(size_t instance_idx) const
return max_z + inst->get_offset(Z);
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// printbed_shape is convex polygon
unsigned int ModelObject::check_instances_print_volume_state(const Polygon& printbed_shape, double print_volume_height)
unsigned int ModelObject::update_instances_print_volume_state(const BuildVolume &build_volume)
{
unsigned int num_printable = 0;
enum {
@ -1586,16 +1541,10 @@ unsigned int ModelObject::check_instances_print_volume_state(const Polygon& prin
for (const ModelVolume* vol : this->volumes)
if (vol->is_model_part()) {
const Transform3d matrix = model_instance->get_matrix() * vol->get_matrix();
const BoundingBoxf3 bb = vol->mesh().transformed_bounding_box(matrix, 0.0);
if (!bb.defined) {
// this may happen if the part is fully below the printbed, leading to a crash in the following call to its_convex_hull_2d_above()
continue;
}
const Polygon volume_hull_2d = its_convex_hull_2d_above(vol->mesh().its, matrix.cast<float>(), 0.0f);
ModelInstanceEPrintVolumeState state = printbed_collision_state(printbed_shape, print_volume_height, volume_hull_2d, bb.min.z(), bb.max.z());
if (state == ModelInstancePVS_Inside)
BuildVolume::ObjectState state = build_volume.object_state(vol->mesh().its, matrix.cast<float>(), true /* may be below print bed */);
if (state == BuildVolume::ObjectState::Inside)
inside_outside |= INSIDE;
else if (state == ModelInstancePVS_Fully_Outside)
else if (state == BuildVolume::ObjectState::Outside)
inside_outside |= OUTSIDE;
else
inside_outside |= INSIDE | OUTSIDE;
@ -1608,35 +1557,6 @@ unsigned int ModelObject::check_instances_print_volume_state(const Polygon& prin
}
return num_printable;
}
#else
unsigned int ModelObject::check_instances_print_volume_state(const BoundingBoxf3& print_volume)
{
unsigned int num_printable = 0;
enum {
INSIDE = 1,
OUTSIDE = 2
};
for (ModelInstance *model_instance : this->instances) {
unsigned int inside_outside = 0;
for (const ModelVolume *vol : this->volumes)
if (vol->is_model_part()) {
BoundingBoxf3 bb = vol->get_convex_hull().transformed_bounding_box(model_instance->get_matrix() * vol->get_matrix());
if (print_volume.contains(bb))
inside_outside |= INSIDE;
else if (print_volume.intersects(bb))
inside_outside |= INSIDE | OUTSIDE;
else
inside_outside |= OUTSIDE;
}
model_instance->print_volume_state =
(inside_outside == (INSIDE | OUTSIDE)) ? ModelInstancePVS_Partly_Outside :
(inside_outside == INSIDE) ? ModelInstancePVS_Inside : ModelInstancePVS_Fully_Outside;
if (inside_outside == INSIDE)
++ num_printable;
}
return num_printable;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
void ModelObject::print_info() const
{

View file

@ -33,6 +33,7 @@ namespace cereal {
namespace Slic3r {
enum class ConversionType;
class BuildVolume;
class Model;
class ModelInstance;
class ModelMaterial;
@ -366,13 +367,6 @@ public:
double get_instance_min_z(size_t instance_idx) const;
double get_instance_max_z(size_t instance_idx) const;
// Called by Print::validate() from the UI thread.
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
unsigned int check_instances_print_volume_state(const Polygon& printbed_shape, double print_volume_height);
#else
unsigned int check_instances_print_volume_state(const BoundingBoxf3& print_volume);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// Print object statistics to console.
void print_info() const;
@ -505,6 +499,9 @@ private:
sla_support_points, sla_points_status, sla_drain_holes, printable, origin_translation,
m_bounding_box, m_bounding_box_valid, m_raw_bounding_box, m_raw_bounding_box_valid, m_raw_mesh_bounding_box, m_raw_mesh_bounding_box_valid);
}
// Called by Print::validate() from the UI thread.
unsigned int update_instances_print_volume_state(const BuildVolume &build_volume);
};
enum class EnforcerBlockerType : int8_t {
@ -908,17 +905,6 @@ enum ModelInstanceEPrintVolumeState : unsigned char
ModelInstanceNum_BedStates
};
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// return the state of the given object's volume (extrusion along z of obj_hull_2d from obj_min_z to obj_max_z)
// with respect to the given print volume (extrusion along z of printbed_shape from zero to print_volume_height)
// Using rotating callipers to check for collision of two convex polygons.
ModelInstanceEPrintVolumeState printbed_collision_state(const Polygon& printbed_shape, double print_volume_height, const Polygon& obj_hull_2d, double obj_min_z, double obj_max_z);
// return the state of the given box
// with respect to the given print volume (extrusion along z of printbed_shape from zero to print_volume_height)
// Commented out, using rotating callipers is quite expensive for a bounding box test.
//ModelInstanceEPrintVolumeState printbed_collision_state(const Polygon& printbed_shape, double print_volume_height, const BoundingBoxf3& box);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// A single instance of a ModelObject.
// Knows the affine transformation of an object.
class ModelInstance final : public ObjectBase
@ -1123,12 +1109,7 @@ public:
BoundingBoxf3 bounding_box() const;
// Set the print_volume_state of PrintObject::instances,
// return total number of printable objects.
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// printbed_shape is convex polygon
unsigned int update_print_volume_state(const Polygon& printbed_shape, double print_volume_height);
#else
unsigned int update_print_volume_state(const BoundingBoxf3 &print_volume);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
unsigned int update_print_volume_state(const BuildVolume &build_volume);
// Returns true if any ModelObject was modified.
bool center_instances_around_point(const Vec2d &point);
void translate(coordf_t x, coordf_t y, coordf_t z) { for (ModelObject *o : this->objects) o->translate(x, y, z); }

View file

@ -1,6 +1,7 @@
#include "ModelArrange.hpp"
#include <libslic3r/Model.hpp>
#include <libslic3r/Geometry/ConvexHull.hpp>
#include "MTUtils.hpp"
namespace Slic3r {

View file

@ -201,6 +201,14 @@ BoundingBox get_extents(const std::vector<Points> &pts)
return bbox;
}
BoundingBoxf get_extents(const std::vector<Vec2d> &pts)
{
BoundingBoxf bbox;
for (const Vec2d &p : pts)
bbox.merge(p);
return bbox;
}
std::ostream& operator<<(std::ostream &stm, const Vec2d &pointf)
{
return stm << pointf(0) << "," << pointf(1);

View file

@ -16,6 +16,7 @@
namespace Slic3r {
class BoundingBox;
class BoundingBoxf;
class Line;
class MultiPoint;
class Point;
@ -133,6 +134,7 @@ public:
Point(const Eigen::MatrixBase<OtherDerived> &other) : Vec2crd(other) {}
static Point new_scale(coordf_t x, coordf_t y) { return Point(coord_t(scale_(x)), coord_t(scale_(y))); }
static Point new_scale(const Vec2d &v) { return Point(coord_t(scale_(v.x())), coord_t(scale_(v.y()))); }
static Point new_scale(const Vec2f &v) { return Point(coord_t(scale_(v.x())), coord_t(scale_(v.y()))); }
// This method allows you to assign Eigen expressions to MyVectorType
template<typename OtherDerived>
@ -213,6 +215,7 @@ inline Point lerp(const Point &a, const Point &b, double t)
BoundingBox get_extents(const Points &pts);
BoundingBox get_extents(const std::vector<Points> &pts);
BoundingBoxf get_extents(const std::vector<Vec2d> &pts);
// Test for duplicate points in a vector of points.
// The points are copied, sorted and checked for duplicates globally.

View file

@ -334,6 +334,25 @@ extern std::vector<BoundingBox> get_extents_vector(const Polygons &polygons)
return out;
}
// Polygon must be valid (at least three points), collinear points and duplicate points removed.
bool polygon_is_convex(const Points &poly)
{
if (poly.size() < 3)
return false;
Point p0 = poly[poly.size() - 2];
Point p1 = poly[poly.size() - 1];
for (size_t i = 0; i < poly.size(); ++ i) {
Point p2 = poly[i];
auto det = cross2((p1 - p0).cast<int64_t>(), (p2 - p1).cast<int64_t>());
if (det < 0)
return false;
p0 = p1;
p1 = p2;
}
return true;
}
bool has_duplicate_points(const Polygons &polys)
{
#if 1

View file

@ -84,6 +84,10 @@ BoundingBox get_extents_rotated(const Polygon &poly, double angle);
BoundingBox get_extents_rotated(const Polygons &polygons, double angle);
std::vector<BoundingBox> get_extents_vector(const Polygons &polygons);
// Polygon must be valid (at least three points), collinear points and duplicate points removed.
bool polygon_is_convex(const Points &poly);
inline bool polygon_is_convex(const Polygon &poly) { return polygon_is_convex(poly.points); }
// Test for duplicate points. The points are copied, sorted and checked for duplicates globally.
inline bool has_duplicate_points(Polygon &&poly) { return has_duplicate_points(std::move(poly.points)); }
inline bool has_duplicate_points(const Polygon &poly) { return has_duplicate_points(poly.points); }

View file

@ -5,7 +5,7 @@
#include "ClipperUtils.hpp"
#include "Extruder.hpp"
#include "Flow.hpp"
#include "Geometry.hpp"
#include "Geometry/ConvexHull.hpp"
#include "I18N.hpp"
#include "ShortestPath.hpp"
#include "SupportMaterial.hpp"
@ -850,7 +850,7 @@ void Print::process()
// The export_gcode may die for various reasons (fails to process output_filename_format,
// write error into the G-code, cannot execute post-processing scripts).
// It is up to the caller to show an error message.
std::string Print::export_gcode(const std::string& path_template, GCodeProcessor::Result* result, ThumbnailsGeneratorCallback thumbnail_cb)
std::string Print::export_gcode(const std::string& path_template, GCodeProcessorResult* result, ThumbnailsGeneratorCallback thumbnail_cb)
{
// output everything to a G-code file
// The following call may die if the output_filename_format template substitution fails.

View file

@ -521,7 +521,7 @@ public:
void process() override;
// Exports G-code into a file name based on the path_template, returns the file path of the generated G-code file.
// If preview_data is not null, the preview_data is filled in for the G-code visualization (not used by the command line Slic3r).
std::string export_gcode(const std::string& path_template, GCodeProcessor::Result* result, ThumbnailsGeneratorCallback thumbnail_cb = nullptr);
std::string export_gcode(const std::string& path_template, GCodeProcessorResult* result, ThumbnailsGeneratorCallback thumbnail_cb = nullptr);
// methods for handling state
bool is_step_done(PrintStep step) const { return Inherited::is_step_done(step); }

View file

@ -4,6 +4,7 @@
#include "MeshSplitImpl.hpp"
#include "ClipperUtils.hpp"
#include "Geometry.hpp"
#include "Geometry/ConvexHull.hpp"
#include "Point.hpp"
#include "Execution/ExecutionTBB.hpp"
#include "Execution/ExecutionSeq.hpp"
@ -436,27 +437,55 @@ BoundingBoxf3 TriangleMesh::transformed_bounding_box(const Transform3d &trafo) c
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
BoundingBoxf3 TriangleMesh::transformed_bounding_box(const Transform3d& trafo, double world_min_z) const
BoundingBoxf3 TriangleMesh::transformed_bounding_box(const Transform3d& trafod, double world_min_z) const
{
BoundingBoxf3 bbox;
const Transform3f ftrafo = trafo.cast<float>();
for (const stl_triangle_vertex_indices& tri : its.indices) {
const Vec3f pts[3] = { ftrafo * its.vertices[tri(0)], ftrafo * its.vertices[tri(1)], ftrafo * its.vertices[tri(2)] };
int iprev = 2;
for (int iedge = 0; iedge < 3; ++iedge) {
const Vec3f& p1 = pts[iprev];
const Vec3f& p2 = pts[iedge];
if ((p1.z() < world_min_z && p2.z() > world_min_z) || (p2.z() < world_min_z && p1.z() > world_min_z)) {
// Edge crosses the z plane. Calculate intersection point with the plane.
const float t = (world_min_z - p1.z()) / (p2.z() - p1.z());
bbox.merge(Vec3f(p1.x() + (p2.x() - p1.x()) * t, p1.y() + (p2.y() - p1.y()) * t, world_min_z).cast<double>());
}
if (p2.z() >= world_min_z)
bbox.merge(p2.cast<double>());
iprev = iedge;
// 1) Allocate transformed vertices with their position with respect to print bed surface.
std::vector<char> sides;
size_t num_above = 0;
Eigen::AlignedBox<float, 3> bbox;
Transform3f trafo = trafod.cast<float>();
sides.reserve(its.vertices.size());
for (const stl_vertex &v : this->its.vertices) {
const stl_vertex pt = trafo * v;
const int sign = pt.z() > world_min_z ? 1 : pt.z() < world_min_z ? -1 : 0;
sides.emplace_back(sign);
if (sign >= 0) {
// Vertex above or on print bed surface. Test whether it is inside the build volume.
++ num_above;
bbox.extend(pt);
}
}
return bbox;
// 2) Calculate intersections of triangle edges with the build surface.
if (num_above < its.vertices.size()) {
// Not completely above the build surface and status may still change by testing edges intersecting the build platform.
for (const stl_triangle_vertex_indices &tri : its.indices) {
const int s[3] = { sides[tri(0)], sides[tri(1)], sides[tri(2)] };
if (std::min(s[0], std::min(s[1], s[2])) < 0 && std::max(s[0], std::max(s[1], s[2])) > 0) {
// Some edge of this triangle intersects the build platform. Calculate the intersection.
int iprev = 2;
for (int iedge = 0; iedge < 3; ++ iedge) {
if (s[iprev] * s[iedge] == -1) {
// edge intersects the build surface. Calculate intersection point.
const stl_vertex p1 = trafo * its.vertices[tri(iprev)];
const stl_vertex p2 = trafo * its.vertices[tri(iedge)];
// Edge crosses the z plane. Calculate intersection point with the plane.
const float t = (world_min_z - p1.z()) / (p2.z() - p1.z());
bbox.extend(Vec3f(p1.x() + (p2.x() - p1.x()) * t, p1.y() + (p2.y() - p1.y()) * t, world_min_z));
}
iprev = iedge;
}
}
}
}
BoundingBoxf3 out;
if (! bbox.isEmpty()) {
out.min = bbox.min().cast<double>();
out.max = bbox.max().cast<double>();
out.defined = true;
};
return out;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS