update libslic3r

This commit is contained in:
QIDI TECH
2024-11-11 14:57:19 +08:00
parent a42b7a0880
commit 87d9e1e953
432 changed files with 13838 additions and 6269 deletions

View File

@@ -1,17 +1,19 @@
#include "AABBMesh.hpp"
#include <Execution/ExecutionTBB.hpp>
#include <libslic3r/AABBTreeIndirect.hpp>
#include <libslic3r/TriangleMesh.hpp>
#include <igl/Hit.h>
#include <algorithm>
#include <numeric>
#include "admesh/stl.h"
#include "libslic3r/Point.hpp"
#ifdef SLIC3R_HOLE_RAYCASTER
#include <libslic3r/SLA/Hollowing.hpp>
#endif
namespace Slic3r {
//YYY
class AABBMesh::AABBImpl {
private:
AABBTreeIndirect::Tree3f m_tree;

View File

@@ -1,11 +1,16 @@
#ifndef QIDISLICER_AABBMESH_H
#define QIDISLICER_AABBMESH_H
#include <memory>
#include <vector>
#include <libslic3r/Point.hpp>
#include <libslic3r/TriangleMesh.hpp>
#include <assert.h>
#include <stddef.h>
#include <memory>
#include <vector>
#include <cmath>
#include <limits>
#include <cassert>
#include <cstddef>
// There is an implementation of a hole-aware raycaster that was eventually
// not used in production version. It is now hidden under following define

View File

@@ -119,10 +119,10 @@ inline std::tuple<int, int> coordinate_aligned_ray_hit_count(size_t
template<typename LineType, typename TreeType, typename VectorType>
inline void insert_intersections_with_line(std::vector<std::pair<VectorType, size_t>> &result,
size_t node_idx,
const TreeType &tree,
const std::vector<LineType> &lines,
const LineType &line,
const typename TreeType::BoundingBox &line_bb)
const TreeType &tree,
const std::vector<LineType> &lines,
const LineType &line,
const typename TreeType::BoundingBox &line_bb)
{
const auto &node = tree.node(node_idx);
assert(node.is_valid());
@@ -132,23 +132,62 @@ inline void insert_intersections_with_line(std::vector<std::pair<VectorType, siz
result.emplace_back(intersection_pt, node.idx);
}
return;
}
size_t left_node_idx = node_idx * 2 + 1;
size_t right_node_idx = left_node_idx + 1;
const auto &node_left = tree.node(left_node_idx);
const auto &node_right = tree.node(right_node_idx);
assert(node_left.is_valid());
assert(node_right.is_valid());
}
size_t left_node_idx = node_idx * 2 + 1;
size_t right_node_idx = left_node_idx + 1;
const auto &node_left = tree.node(left_node_idx);
const auto &node_right = tree.node(right_node_idx);
assert(node_left.is_valid());
assert(node_right.is_valid());
if (node_left.bbox.intersects(line_bb)) {
if (node_left.bbox.intersects(line_bb)) {
insert_intersections_with_line<LineType, TreeType, VectorType>(result, left_node_idx, tree, lines, line, line_bb);
}
}
if (node_right.bbox.intersects(line_bb)) {
if (node_right.bbox.intersects(line_bb)) {
insert_intersections_with_line<LineType, TreeType, VectorType>(result, right_node_idx, tree, lines, line, line_bb);
}
}
//// NOTE: Non recursive implementation - for my case was slower ;-(
// std::vector<size_t> node_indicies_for_check; // evaluation queue
// size_t approx_size = static_cast<size_t>(std::ceil(std::sqrt(tree.nodes().size())));
// node_indicies_for_check.reserve(approx_size);
// do {
// const auto &node = tree.node(node_index);
// assert(node.is_valid());
// if (node.is_leaf()) {
// VectorType intersection_pt;
// if (line_alg::intersection(line, lines[node.idx], &intersection_pt))
// result.emplace_back(intersection_pt, node.idx);
// node_index = 0;// clear next node
// } else {
// size_t left_node_idx = node_index * 2 + 1;
// size_t right_node_idx = left_node_idx + 1;
// const auto &node_left = tree.node(left_node_idx);
// const auto &node_right = tree.node(right_node_idx);
// assert(node_left.is_valid());
// assert(node_right.is_valid());
// // Set next node index
// node_index = 0; // clear next node
// if (node_left.bbox.intersects(line_bb))
// node_index = left_node_idx;
// if (node_right.bbox.intersects(line_bb)) {
// if (node_index == 0)
// node_index = right_node_idx;
// else
// node_indicies_for_check.push_back(right_node_idx); // store for later evaluation
// }
// }
// if (node_index == 0 && !node_indicies_for_check.empty()) {
// // no direct next node take one from queue
// node_index = node_indicies_for_check.back();
// node_indicies_for_check.pop_back();
// }
//} while (node_index != 0);
}
} // namespace detail
@@ -268,6 +307,7 @@ inline std::vector<std::pair<VectorType, size_t>> get_intersections_with_line(co
std::vector<std::pair<VectorType, size_t>> intersections; // result
detail::insert_intersections_with_line(intersections, 0, tree, lines, line, line_bb);
if (sorted) {
using Floating =
typename std::conditional<std::is_floating_point<typename LineType::Scalar>::value, typename LineType::Scalar, double>::type;
@@ -283,7 +323,6 @@ inline std::vector<std::pair<VectorType, size_t>> get_intersections_with_line(co
intersections[i] = points_with_sq_distance[i].second;
}
}
return intersections;
}

View File

@@ -1,9 +1,9 @@
#ifndef SRC_LIBSLIC3R_PATH_SORTING_HPP_
#define SRC_LIBSLIC3R_PATH_SORTING_HPP_
#include "AABBTreeLines.hpp"
#include "BoundingBox.hpp"
#include "Line.hpp"
#include "libslic3r/AABBTreeLines.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/Line.hpp"
#include "ankerl/unordered_dense.h"
#include <algorithm>
#include <iterator>
@@ -14,8 +14,39 @@
#include <type_traits>
#include <unordered_set>
namespace Slic3r {
namespace Algorithm {
namespace Slic3r::Algorithm {
bool is_first_path_touching_second_path(const AABBTreeLines::LinesDistancer<Line> &first_distancer,
const AABBTreeLines::LinesDistancer<Line> &second_distancer,
const BoundingBox &second_distancer_bbox,
const double touch_distance_threshold)
{
for (const Line &line : first_distancer.get_lines()) {
if (bbox_point_distance(second_distancer_bbox, line.a) < touch_distance_threshold && second_distancer.distance_from_lines<false>(line.a) < touch_distance_threshold) {
return true;
}
}
const Point first_distancer_last_pt = first_distancer.get_lines().back().b;
if (bbox_point_distance(second_distancer_bbox, first_distancer_last_pt) && second_distancer.distance_from_lines<false>(first_distancer_last_pt) < touch_distance_threshold) {
return true;
}
return false;
}
bool are_paths_touching(const AABBTreeLines::LinesDistancer<Line> &first_distancer, const BoundingBox &first_distancer_bbox,
const AABBTreeLines::LinesDistancer<Line> &second_distancer, const BoundingBox &second_distancer_bbox,
const double touch_distance_threshold)
{
if (is_first_path_touching_second_path(first_distancer, second_distancer, second_distancer_bbox, touch_distance_threshold)) {
return true;
} else if (is_first_path_touching_second_path(second_distancer, first_distancer, first_distancer_bbox, touch_distance_threshold)) {
return true;
}
return false;
}
//Sorts the paths such that all paths between begin and last_seed are printed first, in some order. The rest of the paths is sorted
// such that the paths that are touching some of the already printed are printed first, sorted secondary by the distance to the last point of the last
@@ -24,44 +55,34 @@ namespace Algorithm {
// to the second, then they touch.
// convert_to_lines is a lambda that should accept the path as argument and return it as Lines vector, in correct order.
template<typename RandomAccessIterator, typename ToLines>
void sort_paths(RandomAccessIterator begin, RandomAccessIterator end, Point start, double touch_limit_distance, ToLines convert_to_lines)
void sort_paths(RandomAccessIterator begin, RandomAccessIterator end, Point start, const double touch_distance_threshold, ToLines convert_to_lines)
{
size_t paths_count = std::distance(begin, end);
const size_t paths_count = std::distance(begin, end);
if (paths_count <= 1)
return;
auto paths_touch = [touch_limit_distance](const AABBTreeLines::LinesDistancer<Line> &left,
const AABBTreeLines::LinesDistancer<Line> &right) {
for (const Line &l : left.get_lines()) {
if (right.distance_from_lines<false>(l.a) < touch_limit_distance) {
return true;
}
}
if (right.distance_from_lines<false>(left.get_lines().back().b) < touch_limit_distance) {
return true;
}
for (const Line &l : right.get_lines()) {
if (left.distance_from_lines<false>(l.a) < touch_limit_distance) {
return true;
}
}
if (left.distance_from_lines<false>(right.get_lines().back().b) < touch_limit_distance) {
return true;
}
return false;
};
std::vector<AABBTreeLines::LinesDistancer<Line>> distancers(paths_count);
for (size_t path_idx = 0; path_idx < paths_count; path_idx++) {
distancers[path_idx] = AABBTreeLines::LinesDistancer<Line>{convert_to_lines(*std::next(begin, path_idx))};
}
BoundingBoxes bboxes;
bboxes.reserve(paths_count);
for (auto tp_it = begin; tp_it != end; ++tp_it) {
bboxes.emplace_back(tp_it->bounding_box());
}
std::vector<std::unordered_set<size_t>> dependencies(paths_count);
for (size_t path_idx = 0; path_idx < paths_count; path_idx++) {
for (size_t next_path_idx = path_idx + 1; next_path_idx < paths_count; next_path_idx++) {
if (paths_touch(distancers[path_idx], distancers[next_path_idx])) {
dependencies[next_path_idx].insert(path_idx);
for (size_t curr_path_idx = 0; curr_path_idx < paths_count; ++curr_path_idx) {
for (size_t next_path_idx = curr_path_idx + 1; next_path_idx < paths_count; ++next_path_idx) {
const BoundingBox &curr_path_bbox = bboxes[curr_path_idx];
const BoundingBox &next_path_bbox = bboxes[next_path_idx];
if (bbox_bbox_distance(curr_path_bbox, next_path_bbox) >= touch_distance_threshold)
continue;
if (are_paths_touching(distancers[curr_path_idx], curr_path_bbox, distancers[next_path_idx], next_path_bbox, touch_distance_threshold)) {
dependencies[next_path_idx].insert(curr_path_idx);
}
}
}
@@ -123,6 +144,6 @@ void sort_paths(RandomAccessIterator begin, RandomAccessIterator end, Point star
}
}
}} // namespace Slic3r::Algorithm
} // namespace Slic3r::Algorithm
#endif /*SRC_LIBSLIC3R_PATH_SORTING_HPP_*/
#endif /*SRC_LIBSLIC3R_PATH_SORTING_HPP_*/

View File

@@ -4,8 +4,20 @@
#include <libslic3r/ClipperZUtils.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include <libslic3r/Utils.hpp>
#include <clipper/clipper_z.hpp>
#include <numeric>
#include <cmath>
#include <iterator>
#include <utility>
#include <algorithm>
#include <cassert>
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {
namespace Algorithm {
@@ -258,14 +270,28 @@ std::vector<WaveSeed> wave_seeds(
int iseed = 0;
for (const ClipperLib_Z::Path &path : segments) {
assert(path.size() >= 2);
const ClipperLib_Z::IntPoint &front = path.front();
const ClipperLib_Z::IntPoint &back = path.back();
ClipperLib_Z::IntPoint front = path.front();
ClipperLib_Z::IntPoint back = path.back();
// Both ends of a seed segment are supposed to be inside a single boundary expolygon.
// Thus as long as the seed contour is not closed, it should be open at a boundary point.
assert((front == back && front.z() >= idx_boundary_end && front.z() < idx_src_end) ||
//(front.z() < 0 && back.z() < 0));
// Hope that at least one end of an open polyline is clipped by the boundary, thus an intersection point is created.
(front.z() < 0 || back.z() < 0));
if (front == back && (front.z() < idx_boundary_end)) {
// This should be a very rare exception.
// See https://github.com/qidi3d/QIDISlicer/issues/12469.
// Segement is open, yet its first point seems to be part of boundary polygon.
// Take the first point with src polygon index.
for (const ClipperLib_Z::IntPoint &point : path) {
if (point.z() >= idx_boundary_end) {
front = point;
back = point;
}
}
}
const Intersection *intersection = nullptr;
auto intersection_point_valid = [idx_boundary_end, idx_src_end](const Intersection &is) {
return is.first >= 1 && is.first < idx_boundary_end &&

View File

@@ -1,10 +1,14 @@
#ifndef SRC_LIBSLIC3R_ALGORITHM_REGION_EXPANSION_HPP_
#define SRC_LIBSLIC3R_ALGORITHM_REGION_EXPANSION_HPP_
#include <cstdint>
#include <libslic3r/Point.hpp>
#include <libslic3r/Polygon.hpp>
#include <libslic3r/ExPolygon.hpp>
#include <stddef.h>
#include <cstdint>
#include <algorithm>
#include <vector>
#include <cstddef>
namespace Slic3r {
namespace Algorithm {

View File

@@ -12,7 +12,6 @@
#include <boost/filesystem/path.hpp>
#include <boost/filesystem/operations.hpp>
#include <boost/nowide/cenv.hpp>
#include <boost/nowide/fstream.hpp>
#include <boost/property_tree/ini_parser.hpp>
#include <boost/property_tree/ptree_fwd.hpp>

View File

@@ -1,10 +1,8 @@
//Copyright (c) 2022 Ultimaker B.V.
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include <cassert>
#include "BeadingStrategy.hpp"
#include "Point.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r::Arachne
{

View File

@@ -4,9 +4,13 @@
#ifndef BEADING_STRATEGY_H
#define BEADING_STRATEGY_H
#include <math.h>
#include <memory>
#include <string>
#include <vector>
#include <cmath>
#include "../../libslic3r.h"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -3,13 +3,16 @@
#include "BeadingStrategyFactory.hpp"
#include <boost/log/trivial.hpp>
#include <memory>
#include <utility>
#include "LimitedBeadingStrategy.hpp"
#include "WideningBeadingStrategy.hpp"
#include "DistributedBeadingStrategy.hpp"
#include "RedistributeBeadingStrategy.hpp"
#include "OuterWallInsetBeadingStrategy.hpp"
#include <boost/log/trivial.hpp>
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne {

View File

@@ -4,8 +4,12 @@
#ifndef BEADING_STRATEGY_FACTORY_H
#define BEADING_STRATEGY_FACTORY_H
#include <math.h>
#include <cmath>
#include "BeadingStrategy.hpp"
#include "../../Point.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -1,7 +1,12 @@
// Copyright (c) 2022 Ultimaker B.V.
// CuraEngine is released under the terms of the AGPLv3 or higher.
#include <numeric>
#include <algorithm>
#include <vector>
#include <cassert>
#include "DistributedBeadingStrategy.hpp"
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne
{

View File

@@ -5,6 +5,7 @@
#define DISTRIBUTED_BEADING_STRATEGY_H
#include "BeadingStrategy.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -1,11 +1,14 @@
//Copyright (c) 2022 Ultimaker B.V.
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include <cassert>
#include <boost/log/trivial.hpp>
#include <cassert>
#include <utility>
#include <cstddef>
#include "LimitedBeadingStrategy.hpp"
#include "Point.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne
{

View File

@@ -4,7 +4,10 @@
#ifndef LIMITED_BEADING_STRATEGY_H
#define LIMITED_BEADING_STRATEGY_H
#include <string>
#include "BeadingStrategy.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -4,6 +4,9 @@
#include "OuterWallInsetBeadingStrategy.hpp"
#include <algorithm>
#include <utility>
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne
{

View File

@@ -4,7 +4,10 @@
#ifndef OUTER_WALL_INSET_BEADING_STRATEGY_H
#define OUTER_WALL_INSET_BEADING_STRATEGY_H
#include <string>
#include "BeadingStrategy.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -5,6 +5,9 @@
#include <algorithm>
#include <numeric>
#include <utility>
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne
{

View File

@@ -4,7 +4,10 @@
#ifndef REDISTRIBUTE_DISTRIBUTED_BEADING_STRATEGY_H
#define REDISTRIBUTE_DISTRIBUTED_BEADING_STRATEGY_H
#include <string>
#include "BeadingStrategy.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -3,6 +3,11 @@
#include "WideningBeadingStrategy.hpp"
#include <algorithm>
#include <utility>
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
namespace Slic3r::Arachne
{

View File

@@ -4,7 +4,11 @@
#ifndef WIDENING_BEADING_STRATEGY_H
#define WIDENING_BEADING_STRATEGY_H
#include <string>
#include <vector>
#include "BeadingStrategy.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -0,0 +1,280 @@
#include <stack>
#include <algorithm>
#include <cmath>
#include "PerimeterOrder.hpp"
#include "libslic3r/Arachne/utils/ExtrusionJunction.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r::Arachne::PerimeterOrder {
using namespace Arachne;
static size_t get_extrusion_lines_count(const Perimeters &perimeters) {
size_t extrusion_lines_count = 0;
for (const Perimeter &perimeter : perimeters)
extrusion_lines_count += perimeter.size();
return extrusion_lines_count;
}
static PerimeterExtrusions get_sorted_perimeter_extrusions_by_area(const Perimeters &perimeters) {
PerimeterExtrusions sorted_perimeter_extrusions;
sorted_perimeter_extrusions.reserve(get_extrusion_lines_count(perimeters));
for (const Perimeter &perimeter : perimeters) {
for (const ExtrusionLine &extrusion_line : perimeter) {
if (extrusion_line.empty())
continue; // This shouldn't ever happen.
const BoundingBox bbox = get_extents(extrusion_line);
// Be aware that Arachne produces contours with clockwise orientation and holes with counterclockwise orientation.
const double area = std::abs(extrusion_line.area());
const Polygon polygon = extrusion_line.is_closed ? to_polygon(extrusion_line) : Polygon{};
sorted_perimeter_extrusions.emplace_back(extrusion_line, area, polygon, bbox);
}
}
// Open extrusions have an area equal to zero, so sorting based on the area ensures that open extrusions will always be before closed ones.
std::sort(sorted_perimeter_extrusions.begin(), sorted_perimeter_extrusions.end(),
[](const PerimeterExtrusion &l, const PerimeterExtrusion &r) { return l.area < r.area; });
return sorted_perimeter_extrusions;
}
// Functions fill adjacent_perimeter_extrusions field for every PerimeterExtrusion by pointers to PerimeterExtrusions that contain or are inside this PerimeterExtrusion.
static void construct_perimeter_extrusions_adjacency_graph(PerimeterExtrusions &sorted_perimeter_extrusions) {
// Construct a graph (defined using adjacent_perimeter_extrusions field) where two PerimeterExtrusion are adjacent when one is inside the other.
std::vector<bool> root_candidates(sorted_perimeter_extrusions.size(), false);
for (PerimeterExtrusion &perimeter_extrusion : sorted_perimeter_extrusions) {
const size_t perimeter_extrusion_idx = &perimeter_extrusion - sorted_perimeter_extrusions.data();
if (!perimeter_extrusion.is_closed()) {
root_candidates[perimeter_extrusion_idx] = true;
continue;
}
for (PerimeterExtrusion &root_candidate : sorted_perimeter_extrusions) {
const size_t root_candidate_idx = &root_candidate - sorted_perimeter_extrusions.data();
if (!root_candidates[root_candidate_idx])
continue;
if (perimeter_extrusion.bbox.contains(root_candidate.bbox) && perimeter_extrusion.polygon.contains(root_candidate.extrusion.junctions.front().p)) {
perimeter_extrusion.adjacent_perimeter_extrusions.emplace_back(&root_candidate);
root_candidate.adjacent_perimeter_extrusions.emplace_back(&perimeter_extrusion);
root_candidates[root_candidate_idx] = false;
}
}
root_candidates[perimeter_extrusion_idx] = true;
}
}
// Perform the depth-first search to assign the nearest external perimeter for every PerimeterExtrusion.
// When some PerimeterExtrusion is achievable from more than one external perimeter, then we choose the
// one that comes from a contour.
static void assign_nearest_external_perimeter(PerimeterExtrusions &sorted_perimeter_extrusions) {
std::stack<PerimeterExtrusion *> stack;
for (PerimeterExtrusion &perimeter_extrusion : sorted_perimeter_extrusions) {
if (perimeter_extrusion.is_external_perimeter()) {
perimeter_extrusion.depth = 0;
perimeter_extrusion.nearest_external_perimeter = &perimeter_extrusion;
stack.push(&perimeter_extrusion);
}
}
while (!stack.empty()) {
PerimeterExtrusion *current_extrusion = stack.top();
stack.pop();
for (PerimeterExtrusion *adjacent_extrusion : current_extrusion->adjacent_perimeter_extrusions) {
const size_t adjacent_extrusion_depth = current_extrusion->depth + 1;
// Update depth when the new depth is smaller or when we can achieve the same depth from a contour.
// This will ensure that the internal perimeter will be extruded before the outer external perimeter
// when there are two external perimeters and one internal.
if (adjacent_extrusion_depth < adjacent_extrusion->depth) {
adjacent_extrusion->nearest_external_perimeter = current_extrusion->nearest_external_perimeter;
adjacent_extrusion->depth = adjacent_extrusion_depth;
stack.push(adjacent_extrusion);
} else if (adjacent_extrusion_depth == adjacent_extrusion->depth && !adjacent_extrusion->nearest_external_perimeter->is_contour() && current_extrusion->is_contour()) {
adjacent_extrusion->nearest_external_perimeter = current_extrusion->nearest_external_perimeter;
stack.push(adjacent_extrusion);
}
}
}
}
inline Point get_end_position(const ExtrusionLine &extrusion) {
if (extrusion.is_closed)
return extrusion.junctions[0].p; // We ended where we started.
else
return extrusion.junctions.back().p; // Pick the other end from where we started.
}
// Returns ordered extrusions.
static std::vector<const PerimeterExtrusion *> ordered_perimeter_extrusions_to_minimize_distances(Point current_position, std::vector<const PerimeterExtrusion *> extrusions) {
// Ensure that open extrusions will be placed before the closed one.
std::sort(extrusions.begin(), extrusions.end(),
[](const PerimeterExtrusion *l, const PerimeterExtrusion *r) -> bool { return l->is_closed() < r->is_closed(); });
std::vector<const PerimeterExtrusion *> ordered_extrusions;
std::vector<bool> already_selected(extrusions.size(), false);
while (ordered_extrusions.size() < extrusions.size()) {
double nearest_distance_sqr = std::numeric_limits<double>::max();
size_t nearest_extrusion_idx = 0;
bool is_nearest_closed = false;
for (size_t extrusion_idx = 0; extrusion_idx < extrusions.size(); ++extrusion_idx) {
if (already_selected[extrusion_idx])
continue;
const ExtrusionLine &extrusion_line = extrusions[extrusion_idx]->extrusion;
const Point &extrusion_start_position = extrusion_line.junctions.front().p;
const double distance_sqr = (current_position - extrusion_start_position).cast<double>().squaredNorm();
if (distance_sqr < nearest_distance_sqr) {
if (extrusion_line.is_closed || (!extrusion_line.is_closed && nearest_distance_sqr == std::numeric_limits<double>::max()) || (!extrusion_line.is_closed && !is_nearest_closed)) {
nearest_extrusion_idx = extrusion_idx;
nearest_distance_sqr = distance_sqr;
is_nearest_closed = extrusion_line.is_closed;
}
}
}
already_selected[nearest_extrusion_idx] = true;
const PerimeterExtrusion *nearest_extrusion = extrusions[nearest_extrusion_idx];
current_position = get_end_position(nearest_extrusion->extrusion);
ordered_extrusions.emplace_back(nearest_extrusion);
}
return ordered_extrusions;
}
struct GroupedPerimeterExtrusions
{
GroupedPerimeterExtrusions() = delete;
explicit GroupedPerimeterExtrusions(const PerimeterExtrusion *external_perimeter_extrusion)
: external_perimeter_extrusion(external_perimeter_extrusion) {}
std::vector<const PerimeterExtrusion *> extrusions;
const PerimeterExtrusion *external_perimeter_extrusion = nullptr;
};
// Returns vector of indexes that represent the order of grouped extrusions in grouped_extrusions.
static std::vector<size_t> order_of_grouped_perimeter_extrusions_to_minimize_distances(Point current_position, std::vector<GroupedPerimeterExtrusions> grouped_extrusions) {
// Ensure that holes will be placed before contour and open extrusions before the closed one.
std::sort(grouped_extrusions.begin(), grouped_extrusions.end(), [](const GroupedPerimeterExtrusions &l, const GroupedPerimeterExtrusions &r) -> bool {
return (l.external_perimeter_extrusion->is_contour() < r.external_perimeter_extrusion->is_contour()) ||
(l.external_perimeter_extrusion->is_contour() == r.external_perimeter_extrusion->is_contour() && l.external_perimeter_extrusion->is_closed() < r.external_perimeter_extrusion->is_closed());
});
const size_t holes_cnt = std::count_if(grouped_extrusions.begin(), grouped_extrusions.end(), [](const GroupedPerimeterExtrusions &grouped_extrusions) {
return !grouped_extrusions.external_perimeter_extrusion->is_contour();
});
std::vector<size_t> grouped_extrusions_order;
std::vector<bool> already_selected(grouped_extrusions.size(), false);
while (grouped_extrusions_order.size() < grouped_extrusions.size()) {
double nearest_distance_sqr = std::numeric_limits<double>::max();
size_t nearest_grouped_extrusions_idx = 0;
bool is_nearest_closed = false;
// First we order all holes and then we start ordering contours.
const size_t grouped_extrusion_end = grouped_extrusions_order.size() < holes_cnt ? holes_cnt: grouped_extrusions.size();
for (size_t grouped_extrusion_idx = 0; grouped_extrusion_idx < grouped_extrusion_end; ++grouped_extrusion_idx) {
if (already_selected[grouped_extrusion_idx])
continue;
const ExtrusionLine &external_perimeter_extrusion_line = grouped_extrusions[grouped_extrusion_idx].external_perimeter_extrusion->extrusion;
const Point &extrusion_start_position = external_perimeter_extrusion_line.junctions.front().p;
const double distance_sqr = (current_position - extrusion_start_position).cast<double>().squaredNorm();
if (distance_sqr < nearest_distance_sqr) {
if (external_perimeter_extrusion_line.is_closed || (!external_perimeter_extrusion_line.is_closed && nearest_distance_sqr == std::numeric_limits<double>::max()) || (!external_perimeter_extrusion_line.is_closed && !is_nearest_closed)) {
nearest_grouped_extrusions_idx = grouped_extrusion_idx;
nearest_distance_sqr = distance_sqr;
is_nearest_closed = external_perimeter_extrusion_line.is_closed;
}
}
}
grouped_extrusions_order.emplace_back(nearest_grouped_extrusions_idx);
already_selected[nearest_grouped_extrusions_idx] = true;
const GroupedPerimeterExtrusions &nearest_grouped_extrusions = grouped_extrusions[nearest_grouped_extrusions_idx];
const ExtrusionLine &last_extrusion_line = nearest_grouped_extrusions.extrusions.back()->extrusion;
current_position = get_end_position(last_extrusion_line);
}
return grouped_extrusions_order;
}
static PerimeterExtrusions extract_ordered_perimeter_extrusions(const PerimeterExtrusions &sorted_perimeter_extrusions, const bool external_perimeters_first) {
// Extrusions are ordered inside each group.
std::vector<GroupedPerimeterExtrusions> grouped_extrusions;
std::stack<const PerimeterExtrusion *> stack;
std::vector<bool> visited(sorted_perimeter_extrusions.size(), false);
for (const PerimeterExtrusion &perimeter_extrusion : sorted_perimeter_extrusions) {
if (!perimeter_extrusion.is_external_perimeter())
continue;
stack.push(&perimeter_extrusion);
visited.assign(sorted_perimeter_extrusions.size(), false);
grouped_extrusions.emplace_back(&perimeter_extrusion);
while (!stack.empty()) {
const PerimeterExtrusion *current_extrusion = stack.top();
const size_t current_extrusion_idx = current_extrusion - sorted_perimeter_extrusions.data();
stack.pop();
visited[current_extrusion_idx] = true;
if (current_extrusion->nearest_external_perimeter == &perimeter_extrusion) {
grouped_extrusions.back().extrusions.emplace_back(current_extrusion);
}
std::vector<const PerimeterExtrusion *> available_candidates;
for (const PerimeterExtrusion *adjacent_extrusion : current_extrusion->adjacent_perimeter_extrusions) {
const size_t adjacent_extrusion_idx = adjacent_extrusion - sorted_perimeter_extrusions.data();
if (!visited[adjacent_extrusion_idx] && !adjacent_extrusion->is_external_perimeter() && adjacent_extrusion->nearest_external_perimeter == &perimeter_extrusion) {
available_candidates.emplace_back(adjacent_extrusion);
}
}
if (available_candidates.size() == 1) {
stack.push(available_candidates.front());
} else if (available_candidates.size() > 1) {
// When there is more than one available candidate, then order candidates to minimize distances between
// candidates and also to minimize the distance from the current_position.
std::vector<const PerimeterExtrusion *> adjacent_extrusions = ordered_perimeter_extrusions_to_minimize_distances(Point::Zero(), available_candidates);
for (auto extrusion_it = adjacent_extrusions.rbegin(); extrusion_it != adjacent_extrusions.rend(); ++extrusion_it) {
stack.push(*extrusion_it);
}
}
}
if (!external_perimeters_first)
std::reverse(grouped_extrusions.back().extrusions.begin(), grouped_extrusions.back().extrusions.end());
}
const std::vector<size_t> grouped_extrusion_order = order_of_grouped_perimeter_extrusions_to_minimize_distances(Point::Zero(), grouped_extrusions);
PerimeterExtrusions ordered_extrusions;
for (size_t order_idx : grouped_extrusion_order) {
for (const PerimeterExtrusion *perimeter_extrusion : grouped_extrusions[order_idx].extrusions)
ordered_extrusions.emplace_back(*perimeter_extrusion);
}
return ordered_extrusions;
}
// FIXME: From the point of better patch planning, it should be better to do ordering when we have generated all extrusions (for now, when G-Code is exported).
// FIXME: It would be better to extract the adjacency graph of extrusions from the SkeletalTrapezoidation graph.
PerimeterExtrusions ordered_perimeter_extrusions(const Perimeters &perimeters, const bool external_perimeters_first) {
PerimeterExtrusions sorted_perimeter_extrusions = get_sorted_perimeter_extrusions_by_area(perimeters);
construct_perimeter_extrusions_adjacency_graph(sorted_perimeter_extrusions);
assign_nearest_external_perimeter(sorted_perimeter_extrusions);
return extract_ordered_perimeter_extrusions(sorted_perimeter_extrusions, external_perimeters_first);
}
} // namespace Slic3r::Arachne::PerimeterOrder

View File

@@ -0,0 +1,54 @@
#ifndef slic3r_GCode_PerimeterOrder_hpp_
#define slic3r_GCode_PerimeterOrder_hpp_
#include <stddef.h>
#include <limits>
#include <vector>
#include <cstddef>
#include "libslic3r/Arachne/utils/ExtrusionLine.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/Polygon.hpp"
namespace Slic3r::Arachne::PerimeterOrder {
// Data structure stores ExtrusionLine (closed and open) together with additional data.
struct PerimeterExtrusion
{
explicit PerimeterExtrusion(const Arachne::ExtrusionLine &extrusion, const double area, const Polygon &polygon, const BoundingBox &bbox)
: extrusion(extrusion), area(area), polygon(polygon), bbox(bbox) {}
Arachne::ExtrusionLine extrusion;
// Absolute value of the area of the polygon. The value is always non-negative, even for holes.
double area = 0;
// Polygon is non-empty only for closed extrusions.
Polygon polygon;
BoundingBox bbox;
std::vector<PerimeterExtrusion *> adjacent_perimeter_extrusions;
// How far is this perimeter from the nearest external perimeter. Contour is always preferred over holes.
size_t depth = std::numeric_limits<size_t>::max();
PerimeterExtrusion *nearest_external_perimeter = nullptr;
// Should this extrusion be fuzzyfied during path generation?
bool fuzzify = false;
// Returns if ExtrusionLine is a contour or a hole.
bool is_contour() const { return extrusion.is_contour(); }
// Returns if ExtrusionLine is closed or opened.
bool is_closed() const { return extrusion.is_closed; }
// Returns if ExtrusionLine is an external or an internal perimeter.
bool is_external_perimeter() const { return extrusion.is_external_perimeter(); }
};
using PerimeterExtrusions = std::vector<PerimeterExtrusion>;
PerimeterExtrusions ordered_perimeter_extrusions(const Perimeters &perimeters, bool external_perimeters_first);
} // namespace Slic3r::Arachne::PerimeterOrder
#endif // slic3r_GCode_Travels_hpp_

View File

@@ -3,25 +3,30 @@
#include "SkeletalTrapezoidation.hpp"
#include <stack>
#include <functional>
#include <sstream>
#include <queue>
#include <functional>
#include <boost/log/trivial.hpp>
#include <boost/polygon/polygon.hpp>
#include <queue>
#include <algorithm>
#include <cmath>
#include <cstdint>
#include <limits>
#include <utility>
#include <cassert>
#include <cstdlib>
#include "libslic3r/Geometry/VoronoiUtils.hpp"
#include "ankerl/unordered_dense.h"
#include "libslic3r/Arachne/SkeletalTrapezoidationEdge.hpp"
#include "libslic3r/Arachne/SkeletalTrapezoidationJoint.hpp"
#include "libslic3r/Arachne/utils/ExtrusionJunction.hpp"
#include "libslic3r/Arachne/utils/ExtrusionLine.hpp"
#include "utils/linearAlg2D.hpp"
#include "Utils.hpp"
#include "SVG.hpp"
#include "Geometry/VoronoiVisualUtils.hpp"
#include "Geometry/VoronoiUtilsCgal.hpp"
#include "../EdgeGrid.hpp"
#ifndef NDEBUG
#include "libslic3r/EdgeGrid.hpp"
#endif
#include "Geometry/VoronoiUtils.hpp"
#define SKELETAL_TRAPEZOIDATION_BEAD_SEARCH_MAX 1000 //A limit to how long it'll keep searching for adjacent beads. Increasing will re-use beadings more often (saving performance), but search longer for beading (costing performance).
namespace Slic3r::Arachne
{
@@ -105,7 +110,7 @@ SkeletalTrapezoidation::node_t &SkeletalTrapezoidation::makeNode(const VD::verte
}
}
void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments) {
void SkeletalTrapezoidation::transferEdge(const Point &from, const Point &to, const VD::edge_type &vd_edge, edge_t *&prev_edge, const Point &start_source_point, const Point &end_source_point, const std::vector<Segment> &segments) {
auto he_edge_it = vd_edge_to_he_edge.find(vd_edge.twin());
if (he_edge_it != vd_edge_to_he_edge.end())
{ // Twin segment(s) have already been made
@@ -153,8 +158,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_t
assert(twin->prev->twin); // Back rib
assert(twin->prev->twin->prev); // Prev segment along parabola
constexpr bool is_not_next_to_start_or_end = false; // Only ribs at the end of a cell should be skipped
graph.makeRib(prev_edge, start_source_point, end_source_point, is_not_next_to_start_or_end);
graph.makeRib(prev_edge, start_source_point, end_source_point);
}
assert(prev_edge);
}
@@ -204,10 +208,8 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_t
p0 = p1;
v0 = v1;
if (p1_idx < discretized.size() - 1)
{ // Rib for last segment gets introduced outside this function!
constexpr bool is_not_next_to_start_or_end = false; // Only ribs at the end of a cell should be skipped
graph.makeRib(prev_edge, start_source_point, end_source_point, is_not_next_to_start_or_end);
if (p1_idx < discretized.size() - 1) { // Rib for last segment gets introduced outside this function!
graph.makeRib(prev_edge, start_source_point, end_source_point);
}
}
assert(prev_edge);
@@ -218,6 +220,7 @@ void SkeletalTrapezoidation::transferEdge(Point from, Point to, const VD::edge_t
Points SkeletalTrapezoidation::discretize(const VD::edge_type& vd_edge, const std::vector<Segment>& segments)
{
assert(Geometry::VoronoiUtils::is_in_range<coord_t>(vd_edge));
/*Terminology in this function assumes that the edge moves horizontally from
left to right. This is not necessarily the case; the edge can go in any
direction, but it helps to picture it in a certain direction in your head.*/
@@ -227,7 +230,7 @@ Points SkeletalTrapezoidation::discretize(const VD::edge_type& vd_edge, const st
Point start = Geometry::VoronoiUtils::to_point(vd_edge.vertex0()).cast<coord_t>();
Point end = Geometry::VoronoiUtils::to_point(vd_edge.vertex1()).cast<coord_t>();
bool point_left = left_cell->contains_point();
bool point_right = right_cell->contains_point();
if ((!point_left && !point_right) || vd_edge.is_secondary()) // Source vert is directly connected to source segment
@@ -247,9 +250,9 @@ Points SkeletalTrapezoidation::discretize(const VD::edge_type& vd_edge, const st
beadings along the way.*/
Point left_point = Geometry::VoronoiUtils::get_source_point(*left_cell, segments.begin(), segments.end());
Point right_point = Geometry::VoronoiUtils::get_source_point(*right_cell, segments.begin(), segments.end());
coord_t d = (right_point - left_point).cast<int64_t>().norm();
Point middle = (left_point + right_point) / 2;
Point x_axis_dir = perp(Point(right_point - left_point));
coord_t d = (right_point - left_point).cast<int64_t>().norm();
Point middle = (left_point + right_point) / 2;
Point x_axis_dir = perp(Point(right_point - left_point));
coord_t x_axis_length = x_axis_dir.cast<int64_t>().norm();
const auto projected_x = [x_axis_dir, x_axis_length, middle](Point from) //Project a point on the edge.
@@ -326,51 +329,6 @@ Points SkeletalTrapezoidation::discretize(const VD::edge_type& vd_edge, const st
}
}
bool SkeletalTrapezoidation::computePointCellRange(const VD::cell_type &cell, Point &start_source_point, Point &end_source_point, const VD::edge_type *&starting_vd_edge, const VD::edge_type *&ending_vd_edge, const std::vector<Segment> &segments) {
if (cell.incident_edge()->is_infinite())
return false; //Infinite edges only occur outside of the polygon. Don't copy any part of this cell.
// Check if any point of the cell is inside or outside polygon
// Copy whole cell into graph or not at all
// If the cell.incident_edge()->vertex0() is far away so much that it doesn't even fit into Vec2i64, then there is no way that it will be inside the input polygon.
if (const VD::vertex_type &vert = *cell.incident_edge()->vertex0();
vert.x() >= double(std::numeric_limits<int64_t>::max()) || vert.x() <= double(std::numeric_limits<int64_t>::lowest()) ||
vert.y() >= double(std::numeric_limits<int64_t>::max()) || vert.y() <= double(std::numeric_limits<int64_t>::lowest()))
return false; // Don't copy any part of this cell
const Point source_point = Geometry::VoronoiUtils::get_source_point(cell, segments.begin(), segments.end());
const PolygonsPointIndex source_point_index = Geometry::VoronoiUtils::get_source_point_index(cell, segments.begin(), segments.end());
Vec2i64 some_point = Geometry::VoronoiUtils::to_point(cell.incident_edge()->vertex0());
if (some_point == source_point.cast<int64_t>())
some_point = Geometry::VoronoiUtils::to_point(cell.incident_edge()->vertex1());
//Test if the some_point is even inside the polygon.
//The edge leading out of a polygon must have an endpoint that's not in the corner following the contour of the polygon at that vertex.
//So if it's inside the corner formed by the polygon vertex, it's all fine.
//But if it's outside of the corner, it must be a vertex of the Voronoi diagram that goes outside of the polygon towards infinity.
if (!LinearAlg2D::isInsideCorner(source_point_index.prev().p(), source_point_index.p(), source_point_index.next().p(), some_point))
return false; // Don't copy any part of this cell
const VD::edge_type* vd_edge = cell.incident_edge();
do {
assert(vd_edge->is_finite());
if (Vec2i64 p1 = Geometry::VoronoiUtils::to_point(vd_edge->vertex1()); p1 == source_point.cast<int64_t>()) {
start_source_point = source_point;
end_source_point = source_point;
starting_vd_edge = vd_edge->next();
ending_vd_edge = vd_edge;
} else {
assert((Geometry::VoronoiUtils::to_point(vd_edge->vertex0()) == source_point.cast<int64_t>() || !vd_edge->is_secondary()) && "point cells must end in the point! They cannot cross the point with an edge, because collinear edges are not allowed in the input.");
}
}
while (vd_edge = vd_edge->next(), vd_edge != cell.incident_edge());
assert(starting_vd_edge && ending_vd_edge);
assert(starting_vd_edge != ending_vd_edge);
return true;
}
SkeletalTrapezoidation::SkeletalTrapezoidation(const Polygons& polys, const BeadingStrategy& beading_strategy,
double transitioning_angle, coord_t discretization_step_size,
coord_t transition_filter_dist, coord_t allowed_filter_deviation,
@@ -385,7 +343,6 @@ SkeletalTrapezoidation::SkeletalTrapezoidation(const Polygons& polys, const Bead
constructFromPolygons(polys);
}
void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
{
#ifdef ARACHNE_DEBUG
@@ -432,22 +389,27 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
if (!cell.incident_edge())
continue; // There is no spoon
Point start_source_point;
Point end_source_point;
Point start_source_point;
Point end_source_point;
const VD::edge_type *starting_voronoi_edge = nullptr;
const VD::edge_type *ending_voronoi_edge = nullptr;
// Compute and store result in above variables
if (cell.contains_point()) {
const bool keep_going = computePointCellRange(cell, start_source_point, end_source_point, starting_voronoi_edge, ending_voronoi_edge, segments);
if (!keep_going)
Geometry::PointCellRange<Point> cell_range = Geometry::VoronoiUtils::compute_point_cell_range(cell, segments.cbegin(), segments.cend());
start_source_point = cell_range.source_point;
end_source_point = cell_range.source_point;
starting_voronoi_edge = cell_range.edge_begin;
ending_voronoi_edge = cell_range.edge_end;
if (!cell_range.is_valid())
continue;
} else {
assert(cell.contains_segment());
Geometry::SegmentCellRange<Point> cell_range = Geometry::VoronoiUtils::compute_segment_cell_range(cell, segments.cbegin(), segments.cend());
assert(cell_range.is_valid());
start_source_point = cell_range.segment_start_point;
end_source_point = cell_range.segment_end_point;
start_source_point = cell_range.source_segment_start_point;
end_source_point = cell_range.source_segment_end_point;
starting_voronoi_edge = cell_range.edge_begin;
ending_voronoi_edge = cell_range.edge_end;
}
@@ -459,30 +421,26 @@ void SkeletalTrapezoidation::constructFromPolygons(const Polygons& polys)
// Copy start to end edge to graph
assert(Geometry::VoronoiUtils::is_in_range<coord_t>(*starting_voronoi_edge));
edge_t* prev_edge = nullptr;
edge_t *prev_edge = nullptr;
transferEdge(start_source_point, Geometry::VoronoiUtils::to_point(starting_voronoi_edge->vertex1()).cast<coord_t>(), *starting_voronoi_edge, prev_edge, start_source_point, end_source_point, segments);
node_t* starting_node = vd_node_to_he_node[starting_voronoi_edge->vertex0()];
node_t *starting_node = vd_node_to_he_node[starting_voronoi_edge->vertex0()];
starting_node->data.distance_to_boundary = 0;
constexpr bool is_next_to_start_or_end = true;
graph.makeRib(prev_edge, start_source_point, end_source_point, is_next_to_start_or_end);
graph.makeRib(prev_edge, start_source_point, end_source_point);
for (const VD::edge_type* vd_edge = starting_voronoi_edge->next(); vd_edge != ending_voronoi_edge; vd_edge = vd_edge->next()) {
assert(vd_edge->is_finite());
assert(Geometry::VoronoiUtils::is_in_range<coord_t>(*vd_edge));
Point v1 = Geometry::VoronoiUtils::to_point(vd_edge->vertex0()).cast<coord_t>();
Point v2 = Geometry::VoronoiUtils::to_point(vd_edge->vertex1()).cast<coord_t>();
transferEdge(v1, v2, *vd_edge, prev_edge, start_source_point, end_source_point, segments);
graph.makeRib(prev_edge, start_source_point, end_source_point, vd_edge->next() == ending_voronoi_edge);
graph.makeRib(prev_edge, start_source_point, end_source_point);
}
transferEdge(Geometry::VoronoiUtils::to_point(ending_voronoi_edge->vertex0()).cast<coord_t>(), end_source_point, *ending_voronoi_edge, prev_edge, start_source_point, end_source_point, segments);
prev_edge->to->data.distance_to_boundary = 0;
}
#ifdef ARACHNE_DEBUG
assert(Geometry::VoronoiUtilsCgal::is_voronoi_diagram_planar_intersection(voronoi_diagram));
#endif

View File

@@ -5,12 +5,11 @@
#define SKELETAL_TRAPEZOIDATION_H
#include <boost/polygon/voronoi.hpp>
#include <ankerl/unordered_dense.h>
#include <memory> // smart pointers
#include <utility> // pair
#include <ankerl/unordered_dense.h>
#include <list>
#include <vector>
#include "utils/HalfEdgeGraph.hpp"
#include "utils/PolygonsSegmentIndex.hpp"
@@ -21,6 +20,10 @@
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
#include "SkeletalTrapezoidationGraph.hpp"
#include "../Geometry/Voronoi.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
//#define ARACHNE_DEBUG
//#define ARACHNE_DEBUG_VORONOI
@@ -178,7 +181,7 @@ protected:
* Transfer an edge from the VD to the HE and perform discretization of parabolic edges (and vertex-vertex edges)
* \p prev_edge serves as input and output. May be null as input.
*/
void transferEdge(Point from, Point to, const VD::edge_type &vd_edge, edge_t *&prev_edge, Point &start_source_point, Point &end_source_point, const std::vector<Segment> &segments);
void transferEdge(const Point &from, const Point &to, const VD::edge_type &vd_edge, edge_t *&prev_edge, const Point &start_source_point, const Point &end_source_point, const std::vector<Segment> &segments);
/*!
* Discretize a Voronoi edge that represents the medial axis of a vertex-
@@ -207,32 +210,6 @@ protected:
*/
Points discretize(const VD::edge_type& segment, const std::vector<Segment>& segments);
/*!
* Compute the range of line segments that surround a cell of the skeletal
* graph that belongs to a point on the medial axis.
*
* This should only be used on cells that belong to a corner in the skeletal
* graph, e.g. triangular cells, not trapezoid cells.
*
* The resulting line segments is just the first and the last segment. They
* are linked to the neighboring segments, so you can iterate over the
* segments until you reach the last segment.
* \param cell The cell to compute the range of line segments for.
* \param[out] start_source_point The start point of the source segment of
* this cell.
* \param[out] end_source_point The end point of the source segment of this
* cell.
* \param[out] starting_vd_edge The edge of the Voronoi diagram where the
* loop around the cell starts.
* \param[out] ending_vd_edge The edge of the Voronoi diagram where the loop
* around the cell ends.
* \param points All vertices of the input Polygons.
* \param segments All edges of the input Polygons.
* /return Whether the cell is inside of the polygon. If it's outside of the
* polygon we should skip processing it altogether.
*/
static bool computePointCellRange(const VD::cell_type &cell, Point &start_source_point, Point &end_source_point, const VD::edge_type *&starting_vd_edge, const VD::edge_type *&ending_vd_edge, const std::vector<Segment> &segments);
/*!
* For VD cells associated with an input polygon vertex, we need to separate the node at the end and start of the cell into two
* That way we can reach both the quad_start and the quad_end from the [incident_edge] of the two new nodes
@@ -573,8 +550,6 @@ protected:
* Genrate small segments for local maxima where the beading would only result in a single bead
*/
void generateLocalMaximaSingleBeads();
friend bool detect_voronoi_edge_intersecting_input_segment(const VD &voronoi_diagram, const std::vector<Segment> &segments);
};
} // namespace Slic3r::Arachne

View File

@@ -4,11 +4,16 @@
#include "SkeletalTrapezoidationGraph.hpp"
#include <ankerl/unordered_dense.h>
#include <boost/log/trivial.hpp>
#include <algorithm>
#include <iostream>
#include <cassert>
#include <cinttypes>
#include "utils/linearAlg2D.hpp"
#include "../Line.hpp"
#include "libslic3r/Arachne/SkeletalTrapezoidationEdge.hpp"
#include "libslic3r/Arachne/SkeletalTrapezoidationJoint.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r::Arachne
{
@@ -314,8 +319,7 @@ void SkeletalTrapezoidationGraph::collapseSmallEdges(coord_t snap_dist)
}
}
void SkeletalTrapezoidationGraph::makeRib(edge_t*& prev_edge, Point start_source_point, Point end_source_point, bool is_next_to_start_or_end)
{
void SkeletalTrapezoidationGraph::makeRib(edge_t *&prev_edge, const Point &start_source_point, const Point &end_source_point) {
Point p;
Line(start_source_point, end_source_point).distance_to_infinite_squared(prev_edge->to->p, &p);
coord_t dist = (prev_edge->to->p - p).cast<int64_t>().norm();

View File

@@ -5,14 +5,19 @@
#define SKELETAL_TRAPEZOIDATION_GRAPH_H
#include <optional>
#include <utility>
#include "utils/HalfEdgeGraph.hpp"
#include "SkeletalTrapezoidationEdge.hpp"
#include "SkeletalTrapezoidationJoint.hpp"
#include "libslic3r/Arachne/utils/HalfEdge.hpp"
#include "libslic3r/Arachne/utils/HalfEdgeNode.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r
{
class Line;
class Point;
};
namespace Slic3r::Arachne
@@ -88,7 +93,7 @@ public:
*/
void collapseSmallEdges(coord_t snap_dist = 5);
void makeRib(edge_t*& prev_edge, Point start_source_point, Point end_source_point, bool is_next_to_start_or_end);
void makeRib(edge_t*& prev_edge, const Point &start_source_point, const Point &end_source_point);
/*!
* Insert a node into the graph and connect it to the input polygon using ribs

View File

@@ -2,20 +2,28 @@
// CuraEngine is released under the terms of the AGPLv3 or higher.
#include <algorithm> //For std::partition_copy and std::min_element.
#include <limits>
#include <memory>
#include <cassert>
#include <cinttypes>
#include <cmath>
#include "WallToolPaths.hpp"
#include "SkeletalTrapezoidation.hpp"
#include "../ClipperUtils.hpp"
#include "utils/linearAlg2D.hpp"
#include "EdgeGrid.hpp"
#include "utils/SparseLineGrid.hpp"
#include "Geometry.hpp"
#include "libslic3r/Geometry.hpp"
#include "utils/PolylineStitcher.hpp"
#include "SVG.hpp"
#include "Utils.hpp"
#include <boost/log/trivial.hpp>
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategy.hpp"
#include "libslic3r/Arachne/BeadingStrategy/BeadingStrategyFactory.hpp"
#include "libslic3r/Arachne/utils/ExtrusionJunction.hpp"
#include "libslic3r/Arachne/utils/ExtrusionLine.hpp"
#include "libslic3r/Arachne/utils/PolygonsPointIndex.hpp"
#include "libslic3r/Flow.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/PrintConfig.hpp"
//#define ARACHNE_STITCH_PATCH_DEBUG
@@ -758,14 +766,7 @@ bool WallToolPaths::removeEmptyToolPaths(std::vector<VariableWidthLines> &toolpa
return toolpaths.empty();
}
/*!
* Get the order constraints of the insets when printing walls per region / hole.
* Each returned pair consists of adjacent wall lines where the left has an inset_idx one lower than the right.
*
* Odd walls should always go after their enclosing wall polygons.
*
* \param outer_to_inner Whether the wall polygons with a lower inset_idx should go before those with a higher one.
*/
WallToolPaths::ExtrusionLineSet WallToolPaths::getRegionOrder(const std::vector<ExtrusionLine *> &input, const bool outer_to_inner)
{
ExtrusionLineSet order_requirements;

View File

@@ -4,14 +4,23 @@
#ifndef CURAENGINE_WALLTOOLPATHS_H
#define CURAENGINE_WALLTOOLPATHS_H
#include <memory>
#include <ankerl/unordered_dense.h>
#include <stddef.h>
#include <memory>
#include <utility>
#include <vector>
#include <cstddef>
#include "BeadingStrategy/BeadingStrategyFactory.hpp"
#include "utils/ExtrusionLine.hpp"
#include "../Polygon.hpp"
#include "../PrintConfig.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
namespace boost {
template <class T> struct hash;
} // namespace boost
namespace Slic3r::Arachne
{
@@ -75,14 +84,7 @@ public:
static bool removeEmptyToolPaths(std::vector<VariableWidthLines> &toolpaths);
using ExtrusionLineSet = ankerl::unordered_dense::set<std::pair<const ExtrusionLine *, const ExtrusionLine *>, boost::hash<std::pair<const ExtrusionLine *, const ExtrusionLine *>>>;
/*!
* Get the order constraints of the insets when printing walls per region / hole.
* Each returned pair consists of adjacent wall lines where the left has an inset_idx one lower than the right.
*
* Odd walls should always go after their enclosing wall polygons.
*
* \param outer_to_inner Whether the wall polygons with a lower inset_idx should go before those with a higher one.
*/
static ExtrusionLineSet getRegionOrder(const std::vector<ExtrusionLine *> &input, bool outer_to_inner);
protected:

View File

@@ -1,18 +0,0 @@
//Copyright (c) 2020 Ultimaker B.V.
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include "ExtrusionJunction.hpp"
namespace Slic3r::Arachne
{
bool ExtrusionJunction::operator ==(const ExtrusionJunction& other) const
{
return p == other.p
&& w == other.w
&& perimeter_index == other.perimeter_index;
}
ExtrusionJunction::ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index) : p(p), w(w), perimeter_index(perimeter_index) {}
}

View File

@@ -37,9 +37,11 @@ struct ExtrusionJunction
*/
size_t perimeter_index;
ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index);
ExtrusionJunction(const Point p, const coord_t w, const coord_t perimeter_index) : p(p), w(w), perimeter_index(perimeter_index) {}
bool operator==(const ExtrusionJunction& other) const;
bool operator==(const ExtrusionJunction &other) const {
return p == other.p && w == other.w && perimeter_index == other.perimeter_index;
}
};
inline Point operator-(const ExtrusionJunction& a, const ExtrusionJunction& b)

View File

@@ -2,10 +2,21 @@
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include <algorithm>
#include <cmath>
#include <cstdlib>
#include "ExtrusionLine.hpp"
#include "linearAlg2D.hpp"
#include "../../PerimeterGenerator.hpp"
#include "libslic3r/Arachne/utils/ExtrusionJunction.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExtrusionEntity.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
namespace Slic3r {
class Flow;
} // namespace Slic3r
namespace Slic3r::Arachne
{
@@ -29,15 +40,6 @@ int64_t ExtrusionLine::getLength() const
return len;
}
coord_t ExtrusionLine::getMinimalWidth() const
{
return std::min_element(junctions.cbegin(), junctions.cend(),
[](const ExtrusionJunction& l, const ExtrusionJunction& r)
{
return l.w < r.w;
})->w;
}
void ExtrusionLine::simplify(const int64_t smallest_line_segment_squared, const int64_t allowed_error_distance_squared, const int64_t maximum_extrusion_area_deviation)
{
const size_t min_path_size = is_closed ? 3 : 2;
@@ -236,9 +238,10 @@ bool ExtrusionLine::is_contour() const
return poly.is_clockwise();
}
double ExtrusionLine::area() const
{
assert(this->is_closed);
double ExtrusionLine::area() const {
if (!this->is_closed)
return 0.;
double a = 0.;
if (this->junctions.size() >= 3) {
Vec2d p1 = this->junctions.back().p.cast<double>();
@@ -248,9 +251,25 @@ double ExtrusionLine::area() const
p1 = p2;
}
}
return 0.5 * a;
}
Points to_points(const ExtrusionLine &extrusion_line) {
Points points;
points.reserve(extrusion_line.junctions.size());
for (const ExtrusionJunction &junction : extrusion_line.junctions)
points.emplace_back(junction.p);
return points;
}
BoundingBox get_extents(const ExtrusionLine &extrusion_line) {
BoundingBox bbox;
for (const ExtrusionJunction &junction : extrusion_line.junctions)
bbox.merge(junction.p);
return bbox;
}
} // namespace Slic3r::Arachne
namespace Slic3r {

View File

@@ -5,16 +5,29 @@
#ifndef UTILS_EXTRUSION_LINE_H
#define UTILS_EXTRUSION_LINE_H
#include <clipper/clipper_z.hpp>
#include <assert.h>
#include <stddef.h>
#include <stdint.h>
#include <algorithm>
#include <utility>
#include <vector>
#include <cassert>
#include <cinttypes>
#include <cstddef>
#include "ExtrusionJunction.hpp"
#include "../../Polyline.hpp"
#include "../../Polygon.hpp"
#include "../../BoundingBox.hpp"
#include "../../ExtrusionEntity.hpp"
#include "../../Flow.hpp"
#include "../../../clipper/clipper_z.hpp"
#include "libslic3r/ExtrusionRole.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r {
struct ThickPolyline;
class Flow;
}
namespace Slic3r::Arachne
@@ -136,11 +149,6 @@ struct ExtrusionLine
return ret;
}
/*!
* Get the minimal width of this path
*/
coord_t getMinimalWidth() const;
/*!
* Removes vertices of the ExtrusionLines to make sure that they are not too high
* resolution.
@@ -192,6 +200,8 @@ struct ExtrusionLine
bool is_contour() const;
double area() const;
bool is_external_perimeter() const { return this->inset_idx == 0; }
};
static inline Slic3r::ThickPolyline to_thick_polyline(const Arachne::ExtrusionLine &line_junctions)
@@ -237,6 +247,7 @@ static inline Slic3r::ThickPolyline to_thick_polyline(const ClipperLib_Z::Path &
static inline Polygon to_polygon(const ExtrusionLine &line)
{
Polygon out;
assert(line.is_closed);
assert(line.junctions.size() >= 3);
assert(line.junctions.front().p == line.junctions.back().p);
out.points.reserve(line.junctions.size() - 1);
@@ -245,15 +256,11 @@ static inline Polygon to_polygon(const ExtrusionLine &line)
return out;
}
#if 0
static BoundingBox get_extents(const ExtrusionLine &extrusion_line)
{
BoundingBox bbox;
for (const ExtrusionJunction &junction : extrusion_line.junctions)
bbox.merge(junction.p);
return bbox;
}
Points to_points(const ExtrusionLine &extrusion_line);
BoundingBox get_extents(const ExtrusionLine &extrusion_line);
#if 0
static BoundingBox get_extents(const std::vector<ExtrusionLine> &extrusion_lines)
{
BoundingBox bbox;
@@ -272,15 +279,6 @@ static BoundingBox get_extents(const std::vector<const ExtrusionLine *> &extrusi
return bbox;
}
static Points to_points(const ExtrusionLine &extrusion_line)
{
Points points;
points.reserve(extrusion_line.junctions.size());
for (const ExtrusionJunction &junction : extrusion_line.junctions)
points.emplace_back(junction.p);
return points;
}
static std::vector<Points> to_points(const std::vector<const ExtrusionLine *> &extrusion_lines)
{
std::vector<Points> points;
@@ -293,6 +291,8 @@ static std::vector<Points> to_points(const std::vector<const ExtrusionLine *> &e
#endif
using VariableWidthLines = std::vector<ExtrusionLine>; //<! The ExtrusionLines generated by libArachne
using Perimeter = VariableWidthLines;
using Perimeters = std::vector<Perimeter>;
} // namespace Slic3r::Arachne

View File

@@ -156,7 +156,6 @@ struct PathsPointIndexLocator
}
};
}//namespace Slic3r::Arachne
namespace std

View File

@@ -2,7 +2,16 @@
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include "PolylineStitcher.hpp"
#include "ExtrusionLine.hpp"
#include "libslic3r/Arachne/utils/PolygonsPointIndex.hpp"
#include "libslic3r/Polygon.hpp"
namespace Slic3r {
namespace Arachne {
struct ExtrusionJunction;
} // namespace Arachne
} // namespace Slic3r
namespace Slic3r::Arachne {

View File

@@ -4,10 +4,20 @@
#ifndef UTILS_POLYLINE_STITCHER_H
#define UTILS_POLYLINE_STITCHER_H
#include <stddef.h>
#include <stdint.h>
#include <cassert>
#include <functional>
#include <limits>
#include <vector>
#include <cinttypes>
#include <cstddef>
#include "SparsePointGrid.hpp"
#include "PolygonsPointIndex.hpp"
#include "../../Polygon.hpp"
#include <cassert>
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne
{

View File

@@ -39,16 +39,6 @@ public:
*/
void insert(const Elem &elem);
/*!
* Get just any element that's within a certain radius of a point.
*
* Rather than giving a vector of nearby elements, this function just gives
* a single element, any element, in no particular order.
* \param query_pt The point to query for an object nearby.
* \param radius The radius of what is considered "nearby".
*/
const ElemT *getAnyNearby(const Point &query_pt, coord_t radius);
protected:
using GridPoint = typename SparseGrid<ElemT>::GridPoint;
@@ -68,22 +58,6 @@ void SparsePointGrid<ElemT, Locator>::insert(const Elem &elem)
SparseGrid<ElemT>::m_grid.emplace(grid_loc, elem);
}
template<class ElemT, class Locator>
const ElemT *SparsePointGrid<ElemT, Locator>::getAnyNearby(const Point &query_pt, coord_t radius)
{
const ElemT *ret = nullptr;
const std::function<bool(const ElemT &)> &process_func = [&ret, query_pt, radius, this](const ElemT &maybe_nearby) {
if (shorter_then(m_locator(maybe_nearby) - query_pt, radius)) {
ret = &maybe_nearby;
return false;
}
return true;
};
SparseGrid<ElemT>::processNearby(query_pt, radius, process_func);
return ret;
}
} // namespace Slic3r::Arachne
#endif // UTILS_SPARSE_POINT_GRID_H

View File

@@ -2,7 +2,10 @@
//CuraEngine is released under the terms of the AGPLv3 or higher.
#include "SquareGrid.hpp"
#include "../../Point.hpp"
#include <cassert>
#include "libslic3r/Point.hpp"
using namespace Slic3r::Arachne;

View File

@@ -4,11 +4,15 @@
#ifndef UTILS_SQUARE_GRID_H
#define UTILS_SQUARE_GRID_H
#include "../../Point.hpp"
#include <stdint.h>
#include <cassert>
#include <vector>
#include <functional>
#include <utility>
#include <cinttypes>
#include "../../Point.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r::Arachne {

View File

@@ -9,59 +9,6 @@
namespace Slic3r::Arachne::LinearAlg2D
{
/*!
* Test whether a point is inside a corner.
* Whether point \p query_point is left of the corner abc.
* Whether the \p query_point is in the circle half left of ab and left of bc, rather than to the right.
*
* Test whether the \p query_point is inside of a polygon w.r.t a single corner.
*/
inline static bool isInsideCorner(const Point &a, const Point &b, const Point &c, const Vec2i64 &query_point)
{
// Visualisation for the algorithm below:
//
// query
// |
// |
// |
// perp-----------b
// / \ (note that the lines
// / \ AB and AC are normalized
// / \ to 10000 units length)
// a c
//
auto normal = [](const Point &p0, coord_t len) -> Point {
int64_t _len = p0.cast<int64_t>().norm();
if (_len < 1)
return {len, 0};
return (p0.cast<int64_t>() * int64_t(len) / _len).cast<coord_t>();
};
constexpr coord_t normal_length = 10000; //Create a normal vector of reasonable length in order to reduce rounding error.
const Point ba = normal(a - b, normal_length);
const Point bc = normal(c - b, normal_length);
const Vec2d bq = query_point.cast<double>() - b.cast<double>();
const Vec2d perpendicular = perp(bq); //The query projects to this perpendicular to coordinate 0.
const double project_a_perpendicular = ba.cast<double>().dot(perpendicular); //Project vertex A on the perpendicular line.
const double project_c_perpendicular = bc.cast<double>().dot(perpendicular); //Project vertex C on the perpendicular line.
if ((project_a_perpendicular > 0.) != (project_c_perpendicular > 0.)) //Query is between A and C on the projection.
{
return project_a_perpendicular > 0.; //Due to the winding order of corner ABC, this means that the query is inside.
}
else //Beyond either A or C, but it could still be inside of the polygon.
{
const double project_a_parallel = ba.cast<double>().dot(bq); //Project not on the perpendicular, but on the original.
const double project_c_parallel = bc.cast<double>().dot(bq);
//Either:
// * A is to the right of B (project_a_perpendicular > 0) and C is below A (project_c_parallel < project_a_parallel), or
// * A is to the left of B (project_a_perpendicular < 0) and C is above A (project_c_parallel > project_a_parallel).
return (project_c_parallel < project_a_parallel) == (project_a_perpendicular > 0.);
}
}
/*!
* Returns the determinant of the 2D matrix defined by the the vectors ab and ap as rows.
*

View File

@@ -254,7 +254,7 @@ void fill_rotations(const Range<It> &items,
}
}
// An arranger put together to fulfill all the requirements based
// An arranger put together to fulfill all the requirements of QIDISlicer based
// on the supplied ArrangeSettings
template<class ArrItem>
class DefaultArranger: public Arranger<ArrItem> {

View File

@@ -1,6 +1,10 @@
#include "ArrangeSettingsDb_AppCfg.hpp"
#include "LocalesUtils.hpp"
#include "libslic3r/AppConfig.hpp"
#include "libslic3r/Arrange/ArrangeSettingsView.hpp"
namespace Slic3r {
ArrangeSettingsDb_AppCfg::ArrangeSettingsDb_AppCfg(AppConfig *appcfg) : m_appcfg{appcfg}
@@ -41,16 +45,6 @@ void ArrangeSettingsDb_AppCfg::sync()
std::string en_rot_sla_str =
m_appcfg->get("arrange", "enable_rotation_sla");
// std::string alignment_fff_str =
// m_appcfg->get("arrange", "alignment_fff");
// std::string alignment_fff_seqp_str =
// m_appcfg->get("arrange", "alignment_fff_seq_pring");
// std::string alignment_sla_str =
// m_appcfg->get("arrange", "alignment_sla");
// Override default alignment and save save/load it to a temporary slot "alignment_xl"
std::string alignment_xl_str =
m_appcfg->get("arrange", "alignment_xl");
@@ -100,19 +94,10 @@ void ArrangeSettingsDb_AppCfg::sync()
if (!en_rot_sla_str.empty())
m_settings_sla.vals.rotations = (en_rot_sla_str == "1" || en_rot_sla_str == "yes");
// if (!alignment_sla_str.empty())
// m_arrange_settings_sla.alignment = std::stoi(alignment_sla_str);
// if (!alignment_fff_str.empty())
// m_arrange_settings_fff.alignment = std::stoi(alignment_fff_str);
// if (!alignment_fff_seqp_str.empty())
// m_arrange_settings_fff_seq_print.alignment = std::stoi(alignment_fff_seqp_str);
else
m_settings_sla.vals.rotations = m_settings_sla.defaults.rotations;
// Override default alignment and save save/load it to a temporary slot "alignment_xl"
// Override default alignment and save/load it to a temporary slot "alignment_xl"
auto arr_alignment = ArrangeSettingsView::to_xl_pivots(alignment_xl_str)
.value_or(m_settings_fff.defaults.xl_align);

View File

@@ -2,11 +2,14 @@
#ifndef ARRANGESETTINGSDB_APPCFG_HPP
#define ARRANGESETTINGSDB_APPCFG_HPP
#include <string>
#include "ArrangeSettingsView.hpp"
#include "libslic3r/AppConfig.hpp"
#include "libslic3r/PrintConfig.hpp"
namespace Slic3r {
class AppConfig;
class ArrangeSettingsDb_AppCfg: public arr2::ArrangeSettingsDb
{
@@ -53,6 +56,7 @@ public:
explicit ArrangeSettingsDb_AppCfg(AppConfig *appcfg);
void sync();
float get_distance_from_objects() const override { return get_ref(this).d_obj; }
float get_distance_from_bed() const override { return get_ref(this).d_bed; }
bool is_rotation_enabled() const override { return get_ref(this).rotations; }

View File

@@ -6,9 +6,11 @@
#include <array>
#include "libslic3r/StaticMap.hpp"
namespace Slic3r { namespace arr2 {
using namespace std::string_view_literals;
class ArrangeSettingsView
{
public:
@@ -33,6 +35,7 @@ public:
virtual XLPivots get_xl_alignment() const = 0;
virtual GeometryHandling get_geometry_handling() const = 0;
virtual ArrangeStrategy get_arrange_strategy() const = 0;
static constexpr std::string_view get_label(GeometryHandling v)
{
constexpr auto STR = std::array{

View File

@@ -1,6 +1,12 @@
#include "Beds.hpp"
#include <cstdlib>
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r { namespace arr2 {
BoundingBox bounding_box(const InfiniteBed &bed)

View File

@@ -2,14 +2,19 @@
#ifndef BEDS_HPP
#define BEDS_HPP
#include <numeric>
#include <libslic3r/Point.hpp>
#include <libslic3r/ExPolygon.hpp>
#include <libslic3r/BoundingBox.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include <boost/variant.hpp>
#include <boost/variant/variant.hpp>
#include <numeric>
#include <cmath>
#include <limits>
#include <type_traits>
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r { namespace arr2 {
@@ -186,6 +191,7 @@ template<> struct IsRectangular_<RectangleBed>: public std::true_type {};
template<> struct IsRectangular_<BoundingBox>: public std::true_type {};
template<class Bed> static constexpr bool IsRectangular = IsRectangular_<Bed>::value;
} // namespace arr2
inline BoundingBox &bounding_box(BoundingBox &bb) { return bb; }

View File

@@ -1,6 +1,11 @@
#include "EdgeCache.hpp"
#include <iterator>
#include "CircularEdgeIterator.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Line.hpp"
namespace Slic3r { namespace arr2 {

View File

@@ -2,9 +2,18 @@
#ifndef EDGECACHE_HPP
#define EDGECACHE_HPP
#include <vector>
#include <libslic3r/ExPolygon.hpp>
#include <assert.h>
#include <stddef.h>
#include <vector>
#include <algorithm>
#include <cmath>
#include <cassert>
#include <cstddef>
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r { namespace arr2 {

View File

@@ -87,14 +87,12 @@ public:
// Will hold the resulting score
double score = 0;
// Distinction of cases for the arrangement scene
enum e_cases {
// This branch is for big items in a mixed (big and small) scene
// OR for all items in a small-only scene.
BIG_ITEM,
// For small items in a mixed scene.
SMALL_ITEM,
@@ -165,7 +163,8 @@ public:
// The final mix of the score is the balance between the
// distance from the full pile center, the pack density and
// the alignment with the neighbors
// Let the density matter more when fewer objects remain
// Let the density matter more when fewer objects remain
score = 0.6 * dist + 0.1 * alignment_score + (1.0 - R) * (0.3 * dist) + R * 0.3 * alignment_score;
break;

View File

@@ -3,18 +3,33 @@
#define NFP_CPP
#include "NFP.hpp"
#include "CircularEdgeIterator.hpp"
#include "CircularEdgeIterator.hpp"
#include "NFPConcave_Tesselate.hpp"
#include "libslic3r/Arrange/Core/Beds.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/libslic3r.h"
#if !defined(_MSC_VER) && defined(__SIZEOF_INT128__) && !defined(__APPLE__)
namespace Slic3r { using LargeInt = __int128; }
#else
#include <boost/multiprecision/integer.hpp>
namespace Slic3r { using LargeInt = boost::multiprecision::int128_t; }
#endif
#include <boost/rational.hpp>
#include <algorithm>
#include <array>
#include <cstddef>
#include <cstdint>
#include <iterator>
#include <limits>
#include <utility>
#include <vector>
#include <cassert>
namespace Slic3r {

View File

@@ -4,6 +4,12 @@
#include <libslic3r/ExPolygon.hpp>
#include <libslic3r/Arrange/Core/Beds.hpp>
#include <stdint.h>
#include <boost/variant.hpp>
#include <cinttypes>
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
namespace Slic3r {

View File

@@ -1,14 +1,20 @@
#include "NFP.hpp"
#include "NFPConcave_CGAL.hpp"
#include <CGAL/Exact_predicates_inexact_constructions_kernel.h>
#include <CGAL/partition_2.h>
#include <CGAL/Partition_traits_2.h>
#include <CGAL/property_map.h>
#include <CGAL/Polygon_vertical_decomposition_2.h>
#include <iterator>
#include <utility>
#include <vector>
#include <cstddef>
#include "NFP.hpp"
#include "NFPConcave_CGAL.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {

View File

@@ -4,6 +4,8 @@
#include <libslic3r/ExPolygon.hpp>
#include "libslic3r/Polygon.hpp"
namespace Slic3r {
Polygons convex_decomposition_cgal(const Polygon &expoly);

View File

@@ -3,8 +3,15 @@
#include <libslic3r/ClipperUtils.hpp>
#include <libslic3r/Tesselate.hpp>
#include <algorithm>
#include <iterator>
#include <vector>
#include <cstddef>
#include "NFP.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {

View File

@@ -4,6 +4,8 @@
#include <libslic3r/ExPolygon.hpp>
#include "libslic3r/Polygon.hpp"
namespace Slic3r {
Polygons convex_decomposition_tess(const Polygon &expoly);

View File

@@ -1,13 +1,13 @@
#include "ArrangeItem.hpp"
#include <numeric>
#include "libslic3r/Arrange/Core/NFP/NFPConcave_Tesselate.hpp"
#include "libslic3r/Arrange/ArrangeImpl.hpp"
#include "libslic3r/Arrange/Tasks/ArrangeTaskImpl.hpp"
#include "libslic3r/Arrange/Tasks/FillBedTaskImpl.hpp"
#include "libslic3r/Arrange/Tasks/MultiplySelectionTaskImpl.hpp"
#include "libslic3r/Arrange/ArrangeImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/ArrangeTaskImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/FillBedTaskImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/MultiplySelectionTaskImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Geometry/ConvexHull.hpp"
namespace Slic3r { namespace arr2 {

View File

@@ -2,29 +2,42 @@
#ifndef ARRANGEITEM_HPP
#define ARRANGEITEM_HPP
#include <optional>
#include <boost/variant.hpp>
#include <libslic3r/ClipperUtils.hpp>
#include <assert.h>
#include <stddef.h>
#include <optional>
#include <algorithm>
#include <initializer_list>
#include <memory>
#include <string>
#include <type_traits>
#include <utility>
#include <vector>
#include <cassert>
#include <cstddef>
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/AnyPtr.hpp"
#include "libslic3r/Arrange/Core/PackingContext.hpp"
#include "libslic3r/Arrange/Core/NFP/NFPArrangeItemTraits.hpp"
#include "libslic3r/Arrange/Core/NFP/NFP.hpp"
#include "libslic3r/Arrange/Items/MutableItemTraits.hpp"
#include "libslic3r/Arrange/Arrange.hpp"
#include "libslic3r/Arrange/Tasks/ArrangeTask.hpp"
#include "libslic3r/Arrange/Tasks/FillBedTask.hpp"
#include "libslic3r/Arrange/Tasks/MultiplySelectionTask.hpp"
#include "libslic3r/Arrange/Items/ArbitraryDataStore.hpp"
#include <libslic3r/ClipperUtils.hpp>
#include "libslic3r/Arrange/Core/ArrangeBase.hpp"
#include "libslic3r/Arrange/Core/ArrangeItemTraits.hpp"
#include "libslic3r/Arrange/Core/DataStoreTraits.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r { namespace arr2 {
struct InfiniteBed;
inline bool check_polygons_are_convex(const Polygons &pp) {
return std::all_of(pp.begin(), pp.end(), [](const Polygon &p) {

View File

@@ -1,9 +1,9 @@
#include "SimpleArrangeItem.hpp"
#include "libslic3r/Arrange/ArrangeImpl.hpp"
#include "libslic3r/Arrange/Tasks/ArrangeTaskImpl.hpp"
#include "libslic3r/Arrange/Tasks/FillBedTaskImpl.hpp"
#include "libslic3r/Arrange/Tasks/MultiplySelectionTaskImpl.hpp"
#include "libslic3r/Arrange/ArrangeImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/ArrangeTaskImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/FillBedTaskImpl.hpp" // IWYU pragma: keep
#include "libslic3r/Arrange/Tasks/MultiplySelectionTaskImpl.hpp" // IWYU pragma: keep
namespace Slic3r { namespace arr2 {

View File

@@ -2,22 +2,30 @@
#ifndef SIMPLEARRANGEITEM_HPP
#define SIMPLEARRANGEITEM_HPP
#include "libslic3r/Arrange/Core/PackingContext.hpp"
#include <optional>
#include <string>
#include <type_traits>
#include <utility>
#include <vector>
#include "libslic3r/Arrange/Core/PackingContext.hpp"
#include "libslic3r/Arrange/Core/NFP/NFPArrangeItemTraits.hpp"
#include "libslic3r/Arrange/Core/NFP/NFP.hpp"
#include "libslic3r/Arrange/Arrange.hpp"
#include "libslic3r/Arrange/Tasks/ArrangeTask.hpp"
#include "libslic3r/Arrange/Tasks/FillBedTask.hpp"
#include "libslic3r/Arrange/Tasks/MultiplySelectionTask.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Geometry/ConvexHull.hpp"
#include "MutableItemTraits.hpp"
#include "libslic3r/Arrange/Core/ArrangeItemTraits.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/ObjectID.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r { namespace arr2 {
struct InfiniteBed;
class SimpleArrangeItem {
Polygon m_shape;

View File

@@ -2,13 +2,30 @@
#ifndef ARR2_SCENE_HPP
#define ARR2_SCENE_HPP
#include <stddef.h>
#include <boost/variant.hpp>
#include <boost/variant/variant.hpp>
#include <any>
#include <string_view>
#include <algorithm>
#include <functional>
#include <memory>
#include <set>
#include <type_traits>
#include <utility>
#include <vector>
#include <cstddef>
#include "libslic3r/ObjectID.hpp"
#include "libslic3r/AnyPtr.hpp"
#include "libslic3r/Arrange/ArrangeSettingsView.hpp"
#include "libslic3r/Arrange/SegmentedRectangleBed.hpp"
#include "libslic3r/Arrange/Core/Beds.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r { namespace arr2 {
@@ -261,8 +278,8 @@ class Scene
ExtendedBed m_bed;
public:
// Can only be built from an rvalue SceneBuilder, as it's content will
// potentially be moved to the constructed ArrangeScene object
// Scene can only be built from an rvalue SceneBuilder whose content will
// potentially be moved to the constructed Scene object.
template<class Sub>
explicit Scene(SceneBuilderBase<Sub> &&bld)
{
@@ -284,8 +301,10 @@ public:
std::vector<ObjectID> selected_ids() const;
};
// Get all the ObjectIDs of Arrangeables which are in selected state
std::set<ObjectID> selected_geometry_ids(const Scene &sc);
// A dummy, empty ArrangeableModel for testing and as placeholder to avoiod using nullptr
class EmptyArrangeableModel: public ArrangeableModel
{
public:
@@ -305,12 +324,20 @@ void SceneBuilderBase<Subclass>::build_scene(Scene &sc) &&
if (!m_settings)
m_settings = std::make_unique<arr2::ArrangeSettings>();
// Apply the bed minimum distance by making the original bed smaller
// and arranging on this smaller bed.
coord_t inset = std::max(scaled(m_settings->get_distance_from_bed()),
m_skirt_offs + m_brims_offs);
// Objects have also a minimum distance from each other implemented
// as inflation applied to object outlines. This object distance
// does not apply to the bed, so the bed is inflated by this amount
// to compensate.
coord_t md = scaled(m_settings->get_distance_from_objects());
md = md / 2 - inset;
// Applying the final bed with the corrected dimensions to account
// for safety distances
visit_bed([md](auto &rawbed) { rawbed = offset(rawbed, md); }, m_bed);
sc.m_settings = std::move(m_settings);

View File

@@ -4,12 +4,25 @@
#include "SceneBuilder.hpp"
#include <cmath>
#include <limits>
#include <numeric>
#include <cstdlib>
#include <iterator>
#include "libslic3r/Model.hpp"
#include "libslic3r/Print.hpp"
#include "libslic3r/SLAPrint.hpp"
#include "Core/ArrangeItemTraits.hpp"
#include "Geometry/ConvexHull.hpp"
#include "libslic3r/Arrange/Core/ArrangeItemTraits.hpp"
#include "libslic3r/Geometry/ConvexHull.hpp"
#include "libslic3r/Arrange/Scene.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/Geometry.hpp"
#include "libslic3r/PrintConfig.hpp"
#include "libslic3r/SLA/Pad.hpp"
#include "libslic3r/TriangleMesh.hpp"
#include "libslic3r/TriangleMeshSlicer.hpp"
#include "libslic3r/Arrange/Core/Beds.hpp"
namespace Slic3r { namespace arr2 {
@@ -179,6 +192,7 @@ void SceneBuilder::build_scene(Scene &sc) &&
}
}
// Call the parent class implementation of build_scene to finish constructing of the scene
std::move(*this).SceneBuilderBase<SceneBuilder>::build_scene(sc);
}

View File

@@ -2,9 +2,29 @@
#ifndef SCENEBUILDER_HPP
#define SCENEBUILDER_HPP
#include "Scene.hpp"
#include <assert.h>
#include <stddef.h>
#include <algorithm>
#include <functional>
#include <initializer_list>
#include <memory>
#include <type_traits>
#include <utility>
#include <vector>
#include <cassert>
#include <cstddef>
#include "Scene.hpp"
#include "Core/ArrangeItemTraits.hpp"
#include "libslic3r/AnyPtr.hpp"
#include "libslic3r/Arrange/Core/Beds.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Model.hpp"
#include "libslic3r/ObjectID.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {
@@ -21,6 +41,9 @@ namespace arr2 {
using SelectionPredicate = std::function<bool()>;
// Objects implementing this interface should know how to present the wipe tower
// as an Arrangeable. If the wipe tower is not present, the overloads of visit() shouldn't do
// anything. (See MissingWipeTowerHandler)
class WipeTowerHandler
{
public:
@@ -31,6 +54,9 @@ public:
virtual void set_selection_predicate(SelectionPredicate pred) = 0;
};
// Something that has a bounding box and can be displaced by arbitrary 2D offset and rotated
// by arbitrary rotation. Used as targets to place on virtual beds. Normally this would correspond
// to ModelInstances but the same functionality was needed in more contexts.
class VBedPlaceable {
public:
virtual ~VBedPlaceable() = default;
@@ -39,11 +65,11 @@ public:
virtual void displace(const Vec2d &transl, double rot) = 0;
};
// An interface to handle virtual beds for ModelInstances. A ModelInstance
// An interface to handle virtual beds for VBedPlaceable objects. A VBedPlaceable
// may be assigned to a logical bed identified by an integer index value (zero
// is the actual physical bed). The ModelInstance may still be outside of it's
// is the actual physical bed). The VBedPlaceable may still be outside of it's
// bed, regardless of being assigned to it. The handler object should provide
// means to read the assigned bed index of a ModelInstance, to assign a
// means to read the assigned bed index of a VBedPlaceable, to assign a
// different bed index and to provide a trafo that maps it to the physical bed
// given a logical bed index. The reason is that the arrangement expects items
// to be in the coordinate system of the physical bed.
@@ -52,15 +78,15 @@ class VirtualBedHandler
public:
virtual ~VirtualBedHandler() = default;
// Returns the bed index on which the given ModelInstance is sitting.
// Returns the bed index on which the given VBedPlaceable is sitting.
virtual int get_bed_index(const VBedPlaceable &obj) const = 0;
// The returned trafo can be used to move the outline of the ModelInstance
// The returned trafo can be used to displace the VBedPlaceable
// to the coordinate system of the physical bed, should that differ from
// the coordinate space of a logical bed.
virtual Transform3d get_physical_bed_trafo(int bed_index) const = 0;
// Assign the ModelInstance to the given bed index. Note that this
// Assign the VBedPlaceable to the given bed index. Note that this
// method can return false, indicating that the given bed is not available
// to be occupied (e.g. the handler has a limited amount of logical bed)
virtual bool assign_bed(VBedPlaceable &obj, int bed_idx) = 0;
@@ -73,6 +99,7 @@ public:
static std::unique_ptr<VirtualBedHandler> create(const ExtendedBed &bed);
};
// Holds the info about which object (ID) is selected/unselected
class SelectionMask
{
public:
@@ -111,6 +138,7 @@ public:
bool is_wipe_tower() const override { return m_wp; }
};
// Common part of any Arrangeable which is a wipe tower
struct ArrangeableWipeTowerBase: public Arrangeable
{
ObjectID oid;
@@ -163,13 +191,15 @@ class SceneBuilder;
struct InstPos { size_t obj_idx = 0, inst_idx = 0; };
// Implementing ArrangeableModel interface for QIDISlicer's Model, ModelObject, ModelInstance data
// hierarchy
class ArrangeableSlicerModel: public ArrangeableModel
{
protected:
AnyPtr<Model> m_model;
AnyPtr<WipeTowerHandler> m_wth;
AnyPtr<VirtualBedHandler> m_vbed_handler;
AnyPtr<const SelectionMask> m_selmask;
AnyPtr<WipeTowerHandler> m_wth; // Determines how wipe tower is handled
AnyPtr<VirtualBedHandler> m_vbed_handler; // Determines how virtual beds are handled
AnyPtr<const SelectionMask> m_selmask; // Determines which objects are selected/unselected
private:
friend class SceneBuilder;
@@ -196,6 +226,7 @@ public:
const Model &get_model() const { return *m_model; }
};
// SceneBuilder implementation for QIDISlicer API.
class SceneBuilder: public SceneBuilderBase<SceneBuilder>
{
protected:
@@ -409,6 +440,7 @@ public:
}
};
// Arrangeable interface implementation for ModelInstances
template<class InstPtr, class VBedHPtr>
class ArrangeableModelInstance : public Arrangeable, VBedPlaceable
{
@@ -451,6 +483,7 @@ public:
extern template class ArrangeableModelInstance<ModelInstance, VirtualBedHandler>;
extern template class ArrangeableModelInstance<const ModelInstance, const VirtualBedHandler>;
// Arrangeable implementation for an SLAPrintObject to be able to arrange with the supports and pad
class ArrangeableSLAPrintObject : public Arrangeable
{
const SLAPrintObject *m_po;
@@ -488,6 +521,7 @@ public:
int priority() const override { return m_arrbl->priority(); }
};
// Extension of ArrangeableSlicerModel for SLA
class ArrangeableSLAPrint : public ArrangeableSlicerModel {
const SLAPrint *m_slaprint;
@@ -619,6 +653,8 @@ public:
extern template class ArrangeableFullModel<Model, ModelDuplicate, VirtualBedHandler>;
extern template class ArrangeableFullModel<const Model, const ModelDuplicate, const VirtualBedHandler>;
// An implementation of the ArrangeableModel to be used for the full model 'duplicate' feature
// accessible from CLI
class DuplicableModel: public ArrangeableModel {
AnyPtr<Model> m_model;
AnyPtr<VirtualBedHandler> m_vbh;

View File

@@ -104,6 +104,7 @@ ExPolygons to_expolygons(const SegmentedRectangleBed<Args...> &bed)
template<class SegB>
struct IsRectangular_<SegB, std::enable_if_t<IsSegmentedBed<SegB>, void>> : public std::true_type
{};
}} // namespace Slic3r::arr2
#endif // SEGMENTEDRECTANGLEBED_HPP

View File

@@ -17,7 +17,10 @@ struct FillBedTask: public ArrangeTaskBase
std::vector<ArrItem> selected, unselected;
// For workaround regarding "holes" when filling the bed with the same
// item's copies
std::vector<ArrItem> selected_fillers;
ArrangeSettings settings;
ExtendedBed bed;
size_t selected_existing_count = 0;

View File

@@ -4,7 +4,7 @@
#include "FillBedTask.hpp"
#include "Arrange/Core/NFP/NFPArrangeItemTraits.hpp"
#include "libslic3r/Arrange/Core/NFP/NFPArrangeItemTraits.hpp"
#include <boost/log/trivial.hpp>
@@ -71,8 +71,7 @@ void extract(FillBedTask<ArrItem> &task,
// Workaround for missing items when arranging the same geometry only:
// Injecting a number of items but with slightly shrinked shape, so that
// they can fill the emerging holes. Priority is set to lowest so that
// these filler items will only be inserted as the last ones.
// they can fill the emerging holes.
ArrItem prototype_item_shrinked;
scene.model().visit_arrangeable(selected_ids.front(),
[&prototype_item_shrinked, &itm_conv](const Arrangeable &arrbl) {
@@ -101,8 +100,6 @@ void extract(FillBedTask<ArrItem> &task,
}
};
// Set the lowest priority to the shrinked prototype (hole filler) item
scene.model().for_each_arrangeable(collect_task_items);
int needed_items = calculate_items_needed_to_fill_bed(task.bed,
@@ -185,6 +182,7 @@ std::unique_ptr<FillBedTaskResult> FillBedTask<ArrItem>::process_native(
}
arranger->arrange(selected_fillers, unsel_cpy, bed, FillBedCtl{ctl, *this});
auto arranged_range = Range{selected.begin(),
selected.begin() + selected_existing_count};
@@ -200,6 +198,7 @@ std::unique_ptr<FillBedTaskResult> FillBedTask<ArrItem>::process_native(
for (auto &itm : selected_fillers)
if (get_bed_index(itm) == PhysicalBedId)
result->add_new_item(itm);
return result;
}

View File

@@ -1,8 +1,5 @@
#include "BlacklistedLibraryCheck.hpp"
#include <cstdio>
#include <boost/nowide/convert.hpp>
#ifdef WIN32
#include <psapi.h>
# endif //WIN32

View File

@@ -1,8 +1,10 @@
#include "BoundingBox.hpp"
#include <algorithm>
#include <assert.h>
#include <Eigen/Dense>
#include <algorithm>
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {
@@ -48,6 +50,13 @@ BoundingBox BoundingBox::rotated(double angle, const Point &center) const
return out;
}
BoundingBox BoundingBox::scaled(double factor) const
{
BoundingBox out(*this);
out.scale(factor);
return out;
}
template <class PointType, typename APointsType> void
BoundingBoxBase<PointType, APointsType>::scale(double factor)
{

View File

@@ -1,12 +1,20 @@
#ifndef slic3r_BoundingBox_hpp_
#define slic3r_BoundingBox_hpp_
#include <assert.h>
#include <algorithm>
#include <vector>
#include <cassert>
#include <cmath>
#include <cstddef>
#include "libslic3r.h"
#include "Exception.hpp"
#include "Point.hpp"
#include "Polygon.hpp"
namespace Slic3r {
class BoundingBox;
template <typename PointType, typename APointsType = std::vector<PointType>>
class BoundingBoxBase
@@ -31,12 +39,7 @@ public:
: BoundingBoxBase(points.begin(), points.end())
{}
void reset()
{
this->defined = false;
this->min = PointType::Zero();
this->max = PointType::Zero();
}
void reset() { this->defined = false; this->min = PointType::Zero(); this->max = PointType::Zero(); }
// B66
Polygon polygon(bool is_scaled = false) const
{
@@ -164,6 +167,7 @@ public:
return this->min.x() < other.max.x() && this->max.x() > other.min.x() && this->min.y() < other.max.y() && this->max.y() > other.min.y() &&
this->min.z() < other.max.z() && this->max.z() > other.min.z();
}
// Shares some boundary.
bool shares_boundary(const BoundingBox3Base<PointType>& other) const {
return is_approx(this->min.x(), other.max.x()) ||
@@ -228,7 +232,9 @@ public:
BoundingBox(const BoundingBoxBase<Vec2crd> &bb): BoundingBox(bb.min, bb.max) {}
BoundingBox(const Points &points) : BoundingBoxBase<Point, Points>(points) {}
BoundingBox inflated(coordf_t delta) const throw() { BoundingBox out(*this); out.offset(delta); return out; }
BoundingBox inflated(coordf_t delta) const noexcept { BoundingBox out(*this); out.offset(delta); return out; }
BoundingBox scaled(double factor) const;
friend BoundingBox get_extents_rotated(const Points &points, double angle);
};
@@ -339,6 +345,23 @@ inline double bbox_point_distance_squared(const BoundingBox &bbox, const Point &
coord_t(0));
}
// Minimum distance between two Bounding boxes.
// Returns zero when Bounding boxes overlap.
inline double bbox_bbox_distance(const BoundingBox &first_bbox, const BoundingBox &second_bbox) {
if (first_bbox.overlap(second_bbox))
return 0.;
double bboxes_distance_squared = 0.;
for (size_t axis = 0; axis < 2; ++axis) {
const coord_t axis_distance = std::max(std::max(0, first_bbox.min[axis] - second_bbox.max[axis]),
second_bbox.min[axis] - first_bbox.max[axis]);
bboxes_distance_squared += Slic3r::sqr(static_cast<double>(axis_distance));
}
return std::sqrt(bboxes_distance_squared);
}
template<class T>
BoundingBoxBase<Vec<2, T>> to_2d(const BoundingBox3Base<Vec<3, T>> &bb)
{

View File

@@ -1,11 +1,14 @@
#include "BranchingTree.hpp"
#include "PointCloud.hpp"
#include <numeric>
#include <optional>
#include <algorithm>
#include <cstddef>
#include "PointCloud.hpp"
#include "libslic3r/TriangleMesh.hpp"
#include "libslic3r/BoundingBox.hpp"
struct indexed_triangle_set;
namespace Slic3r { namespace branchingtree {

View File

@@ -3,8 +3,15 @@
// For indexed_triangle_set
#include <admesh/stl.h>
#include <optional>
#include <utility>
#include <vector>
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
struct indexed_triangle_set;
namespace Slic3r { namespace branchingtree {

View File

@@ -1,9 +1,14 @@
#include "PointCloud.hpp"
#include <igl/random_points_on_mesh.h> // IWYU pragma: keep
#include <array>
#include <limits>
#include "libslic3r/Tesselate.hpp"
#include "libslic3r/SLA/SupportTreeUtils.hpp"
#include <igl/random_points_on_mesh.h>
#include "admesh/stl.h"
#include "libslic3r/BranchingTree/BranchingTree.hpp"
#include "libslic3r/SLA/Pad.hpp"
namespace Slic3r { namespace branchingtree {

View File

@@ -1,15 +1,30 @@
#ifndef POINTCLOUD_HPP
#define POINTCLOUD_HPP
#include <assert.h>
#include <stddef.h>
#include <boost/geometry.hpp>
#include <optional>
#include <Eigen/Geometry>
#include <algorithm>
#include <cmath>
#include <type_traits>
#include <utility>
#include <vector>
#include <cassert>
#include <cstdlib>
#include "BranchingTree.hpp"
//#include "libslic3r/Execution/Execution.hpp"
#include "libslic3r/MutablePriorityQueue.hpp"
#include "libslic3r/BoostAdapter.hpp"
#include "boost/geometry/index/rtree.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/libslic3r.h"
struct indexed_triangle_set;
namespace Slic3r { namespace branchingtree {

View File

@@ -1,7 +1,17 @@
#include "BridgeDetector.hpp"
#include <algorithm>
#include <cstddef>
#include "ClipperUtils.hpp"
#include "Geometry.hpp"
#include <algorithm>
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {

View File

@@ -1,6 +1,15 @@
#ifndef slic3r_BridgeDetector_hpp_
#define slic3r_BridgeDetector_hpp_
#include <cmath>
#include <string>
#include <unordered_map>
#include <vector>
#include <algorithm>
#include <limits>
#include <tuple>
#include <utility>
#include "ClipperUtils.hpp"
#include "Line.hpp"
#include "Point.hpp"
@@ -9,10 +18,6 @@
#include "PrincipalComponents2D.hpp"
#include "libslic3r.h"
#include "ExPolygon.hpp"
#include <cmath>
#include <string>
#include <unordered_map>
#include <vector>
namespace Slic3r {

View File

@@ -1,23 +1,39 @@
#include "clipper/clipper_z.hpp"
#include <boost/thread/lock_guard.hpp>
#include <oneapi/tbb/blocked_range.h>
#include <oneapi/tbb/parallel_for.h>
#include <algorithm>
#include <numeric>
#include <unordered_set>
#include <mutex>
#include <cmath>
#include <functional>
#include <utility>
#include <vector>
#include <cassert>
#include <cinttypes>
#include <cstddef>
#include "clipper/clipper_z.hpp"
#include "ClipperUtils.hpp"
#include "EdgeGrid.hpp"
#include "Layer.hpp"
#include "Print.hpp"
#include "ShortestPath.hpp"
#include "libslic3r.h"
#include <algorithm>
#include <numeric>
#include <unordered_set>
#include <mutex>
#include <tbb/parallel_for.h>
#include <boost/thread/lock_guard.hpp>
#ifndef NDEBUG
// #define BRIM_DEBUG_TO_SVG
#endif
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/ExtrusionEntity.hpp"
#include "libslic3r/ExtrusionEntityCollection.hpp"
#include "libslic3r/ExtrusionRole.hpp"
#include "libslic3r/Flow.hpp"
#include "libslic3r/Geometry.hpp"
#include "libslic3r/LayerRegion.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/PrintBase.hpp"
#include "libslic3r/PrintConfig.hpp"
#if defined(BRIM_DEBUG_TO_SVG)
#include "SVG.hpp"

View File

@@ -1,16 +1,26 @@
#include "BuildVolume.hpp"
#include "ClipperUtils.hpp"
#include "Geometry/ConvexHull.hpp"
#include "GCode/GCodeProcessor.hpp"
#include "Point.hpp"
#include <boost/log/trivial.hpp>
#include <algorithm>
#include <cmath>
#include <limits>
#include <cassert>
#include <cstddef>
#include "ClipperUtils.hpp"
#include "Geometry/ConvexHull.hpp"
#include "libslic3r/GCode/GCodeProcessor.hpp"
#include "Point.hpp"
#include "admesh/stl.h"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExtrusionRole.hpp"
#include "libslic3r/Geometry/Circle.hpp"
#include "libslic3r/Polygon.hpp"
namespace Slic3r {
//B52
BuildVolume::BuildVolume(const std::vector<Vec2d> &bed_shape, const double max_print_height, const std::vector<Vec2d> &exclude_bed_shape)
: m_bed_shape(bed_shape), m_max_print_height(max_print_height),m_exclude_bed_shape(exclude_bed_shape)
BuildVolume::BuildVolume(const std::vector<Vec2d> &bed_shape, const double max_print_height, const std::vector<Vec2d> &exclude_bed_shape): m_bed_shape(bed_shape), m_max_print_height(max_print_height), m_exclude_bed_shape(exclude_bed_shape)
{
assert(max_print_height >= 0);
@@ -398,7 +408,7 @@ bool BuildVolume::all_paths_inside(const GCodeProcessorResult& paths, const Boun
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.0 ?
return m_max_print_height == 0.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)
@@ -429,40 +439,6 @@ inline bool all_inside_vertices_normals_interleaved(const std::vector<float> &pa
return true;
}
bool BuildVolume::all_paths_inside_vertices_and_normals_interleaved(const std::vector<float>& paths, const Eigen::AlignedBox<float, 3>& paths_bbox, bool ignore_bottom) 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.0)
build_volume.max.z() = std::numeric_limits<double>::max();
if (ignore_bottom)
build_volume.min.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.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.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;

View File

@@ -1,13 +1,18 @@
#ifndef slic3r_BuildVolume_hpp_
#define slic3r_BuildVolume_hpp_
#include <admesh/stl.h>
#include <string_view>
#include <utility>
#include <vector>
#include "Point.hpp"
#include "Geometry/Circle.hpp"
#include "Polygon.hpp"
#include "BoundingBox.hpp"
#include <admesh/stl.h>
#include "libslic3r/libslic3r.h"
#include <string_view>
struct indexed_triangle_set;
namespace Slic3r {
@@ -96,9 +101,6 @@ public:
// 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, bool ignore_bottom = true) 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, bool ignore_bottom = true) const;
const std::pair<std::vector<Vec2d>, std::vector<Vec2d>>& top_bottom_convex_hull_decomposition_scene() const { return m_top_bottom_convex_hull_decomposition_scene; }
const std::pair<std::vector<Vec2d>, std::vector<Vec2d>>& top_bottom_convex_hull_decomposition_bed() const { return m_top_bottom_convex_hull_decomposition_bed; }

View File

@@ -18,6 +18,7 @@ find_package(LibBGCode REQUIRED COMPONENTS Convert)
slic3r_remap_configs(LibBGCode::bgcode_core RelWithDebInfo Release)
slic3r_remap_configs(LibBGCode::bgcode_binarize RelWithDebInfo Release)
slic3r_remap_configs(LibBGCode::bgcode_convert RelWithDebInfo Release)
set(SLIC3R_SOURCES
pchheader.cpp
pchheader.hpp
@@ -145,6 +146,8 @@ set(SLIC3R_SOURCES
Format/SVG.cpp
Format/SLAArchiveFormatRegistry.hpp
Format/SLAArchiveFormatRegistry.cpp
Format/PrintRequest.cpp
Format/PrintRequest.cpp
GCode/ThumbnailData.cpp
GCode/ThumbnailData.hpp
GCode/Thumbnails.cpp
@@ -173,6 +176,24 @@ set(SLIC3R_SOURCES
GCode/SpiralVase.hpp
GCode/SeamPlacer.cpp
GCode/SeamPlacer.hpp
GCode/SeamChoice.cpp
GCode/SeamChoice.hpp
GCode/SeamPerimeters.cpp
GCode/SeamPerimeters.hpp
GCode/SeamShells.cpp
GCode/SeamShells.hpp
GCode/SeamGeometry.cpp
GCode/SeamGeometry.hpp
GCode/SeamAligned.cpp
GCode/SeamAligned.hpp
GCode/SeamRear.cpp
GCode/SeamRear.hpp
GCode/SeamRandom.cpp
GCode/SeamRandom.hpp
GCode/SeamPainting.cpp
GCode/SeamPainting.hpp
GCode/ModelVisibility.cpp
GCode/ModelVisibility.hpp
GCode/SmoothPath.cpp
GCode/SmoothPath.hpp
GCode/ToolOrdering.cpp
@@ -189,6 +210,8 @@ set(SLIC3R_SOURCES
GCode/AvoidCrossingPerimeters.hpp
GCode/Travels.cpp
GCode/Travels.hpp
GCode/ExtrusionOrder.cpp
GCode/ExtrusionOrder.hpp
GCode.cpp
GCode.hpp
GCodeReader.cpp
@@ -213,7 +236,6 @@ set(SLIC3R_SOURCES
Geometry/VoronoiUtils.hpp
Geometry/VoronoiUtils.cpp
Geometry/VoronoiVisualUtils.hpp
Int128.hpp
JumpPointSearch.cpp
JumpPointSearch.hpp
KDTreeIndirect.hpp
@@ -227,8 +249,6 @@ set(SLIC3R_SOURCES
Line.hpp
BlacklistedLibraryCheck.cpp
BlacklistedLibraryCheck.hpp
LocalesUtils.cpp
LocalesUtils.hpp
CutUtils.cpp
CutUtils.hpp
Model.cpp
@@ -459,11 +479,12 @@ set(SLIC3R_SOURCES
SLA/DefaultSupportTree.cpp
SLA/BranchingTreeSLA.hpp
SLA/BranchingTreeSLA.cpp
SLA/ZCorrection.hpp
SLA/ZCorrection.cpp
BranchingTree/BranchingTree.cpp
BranchingTree/BranchingTree.hpp
BranchingTree/PointCloud.cpp
BranchingTree/PointCloud.hpp
Arachne/BeadingStrategy/BeadingStrategy.hpp
Arachne/BeadingStrategy/BeadingStrategy.cpp
Arachne/BeadingStrategy/BeadingStrategyFactory.hpp
@@ -479,7 +500,6 @@ set(SLIC3R_SOURCES
Arachne/BeadingStrategy/WideningBeadingStrategy.hpp
Arachne/BeadingStrategy/WideningBeadingStrategy.cpp
Arachne/utils/ExtrusionJunction.hpp
Arachne/utils/ExtrusionJunction.cpp
Arachne/utils/ExtrusionLine.hpp
Arachne/utils/ExtrusionLine.cpp
Arachne/utils/HalfEdge.hpp
@@ -497,6 +517,8 @@ set(SLIC3R_SOURCES
Geometry/Voronoi.cpp
Geometry/VoronoiUtils.hpp
Geometry/VoronoiUtils.cpp
Arachne/PerimeterOrder.hpp
Arachne/PerimeterOrder.cpp
Arachne/SkeletalTrapezoidation.hpp
Arachne/SkeletalTrapezoidation.cpp
Arachne/SkeletalTrapezoidationEdge.hpp
@@ -506,8 +528,20 @@ set(SLIC3R_SOURCES
Arachne/WallToolPaths.hpp
Arachne/WallToolPaths.cpp
StaticMap.hpp
ProfilesSharingUtils.hpp
ProfilesSharingUtils.cpp
Utils/DirectoriesUtils.hpp
Utils/DirectoriesUtils.cpp
Utils/JsonUtils.hpp
Utils/JsonUtils.cpp
)
if (APPLE)
list(APPEND SLIC3R_SOURCES
MacUtils.mm
)
endif ()
add_library(libslic3r STATIC ${SLIC3R_SOURCES})
if (WIN32)
@@ -539,6 +573,7 @@ add_library(libslic3r_cgal STATIC
Triangulation.hpp Triangulation.cpp
)
target_include_directories(libslic3r_cgal PRIVATE ${CMAKE_CURRENT_BINARY_DIR})
target_include_directories(libslic3r_cgal PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/..)
# Reset compile options of libslic3r_cgal. Despite it being linked privately, CGAL options
# (-frounding-math) still propagate to dependent libs which is not desired.
@@ -557,6 +592,7 @@ if (_opts)
endif()
target_link_libraries(libslic3r_cgal PRIVATE ${_cgal_tgt} libigl)
target_link_libraries(libslic3r_cgal PUBLIC semver admesh localesutils)
if (MSVC AND "${CMAKE_SIZEOF_VOID_P}" STREQUAL "4") # 32 bit MSVC workaround
target_compile_definitions(libslic3r_cgal PRIVATE CGAL_DO_NOT_USE_MPZF)
@@ -565,24 +601,19 @@ endif ()
encoding_check(libslic3r)
target_compile_definitions(libslic3r PUBLIC -DUSE_TBB -DTBB_USE_CAPTURED_EXCEPTION=0)
target_include_directories(libslic3r PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} PUBLIC ${CMAKE_CURRENT_BINARY_DIR})
target_include_directories(libslic3r PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}/.. ${CMAKE_CURRENT_BINARY_DIR})
target_include_directories(libslic3r PUBLIC ${EXPAT_INCLUDE_DIRS})
find_package(JPEG REQUIRED)
target_link_libraries(libslic3r
target_link_libraries(libslic3r PRIVATE
libnest2d
admesh
libcereal
libigl
miniz
boost_libs
clipper
nowide
libexpat
glu-libtess
qhull
semver
TBB::tbb
TBB::tbbmalloc
libslic3r_cgal
@@ -591,20 +622,33 @@ target_link_libraries(libslic3r
ZLIB::ZLIB
JPEG::JPEG
qoi
fastfloat
int128
)
target_link_libraries(libslic3r PUBLIC
Eigen3::Eigen
semver
admesh
localesutils
LibBGCode::bgcode_convert
)
tcbspan
miniz
libigl
agg
ankerl
)
if (APPLE)
# TODO: we need to fix notarization with the separate shared library
target_link_libraries(libslic3r OCCTWrapper)
target_link_libraries(libslic3r PUBLIC OCCTWrapper)
endif ()
if (TARGET OpenVDB::openvdb)
target_link_libraries(libslic3r OpenVDB::openvdb)
target_link_libraries(libslic3r PUBLIC OpenVDB::openvdb)
endif()
if(WIN32)
target_link_libraries(libslic3r Psapi.lib)
target_link_libraries(libslic3r PUBLIC Psapi.lib)
endif()
if (APPLE)

View File

@@ -83,6 +83,7 @@ struct CSGPart {
{}
};
// Check if there are only positive parts (Union) within the collection.
template<class Cont> bool is_all_positive(const Cont &csgmesh)
{
bool is_all_pos =
@@ -95,6 +96,8 @@ template<class Cont> bool is_all_positive(const Cont &csgmesh)
return is_all_pos;
}
// Merge all the positive parts of the collection into a single triangle mesh without performing
// any booleans.
template<class Cont>
indexed_triangle_set csgmesh_merge_positive_parts(const Cont &csgmesh)
{

View File

@@ -51,6 +51,8 @@ void copy_csgrange_deep(const Range<It> &csgrange, OutIt out)
}
}
// Compare two csgmeshes. They are the same if all the triangle mesh pointers are equal and contain
// the same operations and transformed similarly.
template<class ItA, class ItB>
bool is_same(const Range<ItA> &A, const Range<ItB> &B)
{

View File

@@ -132,6 +132,9 @@ void perform_csgmesh_booleans(MeshBoolean::cgal::CGALMeshPtr &cgalm,
cgalm = std::move(opstack.top().cgalptr);
}
// Check if all requirements for doing mesh booleans are met by the input csgrange.
// Returns the iterator to the first part which breaks criteria or csgrange.end() if all the parts
// are ok. The Visitor vfn is called for each "bad" part.
template<class It, class Visitor>
It check_csgmesh_booleans(const Range<It> &csgrange, Visitor &&vfn)
{
@@ -182,6 +185,7 @@ It check_csgmesh_booleans(const Range<It> &csgrange, Visitor &&vfn)
return ret;
}
// Overload of the previous check_csgmesh_booleans without the visitor argument
template<class It>
It check_csgmesh_booleans(const Range<It> &csgrange)
{

View File

@@ -45,6 +45,8 @@ inline void collect_nonempty_indices(csg::CSGType op,
} // namespace detail
// Slice the input csgrange and return the corresponding layers as a vector of ExPolygons.
// All boolean operations are performed on the 2D slices.
template<class ItCSG>
std::vector<ExPolygons> slice_csgmesh_ex(
const Range<ItCSG> &csgrange,

View File

@@ -54,6 +54,7 @@ inline void perform_csg(CSGType op, VoxelGridPtr &dst, VoxelGridPtr &src)
} // namespace detail
// Convert the input csgrange to a voxel grid performing the boolean operations in the voxel realm.
template<class It>
VoxelGridPtr voxelize_csgmesh(const Range<It> &csgrange,
const VoxelizeParams &params = {})

View File

@@ -1,7 +1,13 @@
#include "ClipperUtils.hpp"
#include "Geometry.hpp"
#include <cmath>
#include "ShortestPath.hpp"
#include "Utils.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Surface.hpp"
#include "libslic3r/libslic3r.h"
// #define CLIPPER_UTILS_TIMING
@@ -9,7 +15,9 @@
// time limit for one ClipperLib operation (union / diff / offset), in ms
#define CLIPPER_UTILS_TIME_LIMIT_DEFAULT 50
#include <boost/current_function.hpp>
#include "Timer.hpp"
#define CLIPPER_UTILS_TIME_LIMIT_SECONDS(limit) Timing::TimeLimitAlarm time_limit_alarm(uint64_t(limit) * 1000000000l, BOOST_CURRENT_FUNCTION)
#define CLIPPER_UTILS_TIME_LIMIT_MILLIS(limit) Timing::TimeLimitAlarm time_limit_alarm(uint64_t(limit) * 1000000l, BOOST_CURRENT_FUNCTION)
#else
@@ -209,7 +217,7 @@ namespace ClipperUtils {
out.insert(out.end(), temp.begin(), temp.end());
}
out.erase(std::remove_if(out.begin(), out.end(), [](const Polygon &polygon) { return polygon.empty(); }), out.end());
out.erase(std::remove_if(out.begin(), out.end(), [](const Polygon &polygon) {return polygon.empty(); }), out.end());
return out;
}
}
@@ -833,7 +841,6 @@ Slic3r::ExPolygons union_ex(const Slic3r::ExPolygons &subject, const Slic3r::Pol
Slic3r::ExPolygons union_ex(const Slic3r::Surfaces &subject)
{ return PolyTreeToExPolygons(clipper_do_polytree(ClipperLib::ctUnion, ClipperUtils::SurfacesProvider(subject), ClipperUtils::EmptyPathsProvider(), ClipperLib::pftNonZero)); }
template<typename PathsProvider1, typename PathsProvider2>
Polylines _clipper_pl_open(ClipperLib::ClipType clipType, PathsProvider1 &&subject, PathsProvider2 &&clip)
{
@@ -1290,12 +1297,6 @@ static void variable_offset_inner_raw(const ExPolygon &expoly, const std::vector
holes.reserve(expoly.holes.size());
for (const Polygon &hole : expoly.holes)
append(holes, fix_after_outer_offset(mittered_offset_path_scaled(hole.points, deltas[1 + &hole - expoly.holes.data()], miter_limit), ClipperLib::pftNegative, false));
#ifndef NDEBUG
// Offsetting a hole curve of a C shape may close the C into a ring with a new hole inside, thus creating a hole inside a hole shape, thus a hole will be created with negative area
// and the following test will fail.
// for (auto &c : holes)
// assert(ClipperLib::Area(c) > 0.);
#endif /* NDEBUG */
}
Polygons variable_offset_inner(const ExPolygon &expoly, const std::vector<std::vector<float>> &deltas, double miter_limit)
@@ -1369,12 +1370,6 @@ static void variable_offset_outer_raw(const ExPolygon &expoly, const std::vector
contours = fix_after_outer_offset(mittered_offset_path_scaled(expoly.contour.points, deltas.front(), miter_limit), ClipperLib::pftPositive, false);
// Inflating a contour must not remove it.
assert(contours.size() >= 1);
#ifndef NDEBUG
// Offsetting a positive curve of a C shape may close the C into a ring with hole shape, thus a hole will be created with negative area
// and the following test will fail.
// for (auto &c : contours)
// assert(ClipperLib::Area(c) > 0.);
#endif /* NDEBUG */
// 2) Offset the holes one by one, collect the results.
holes.reserve(expoly.holes.size());

View File

@@ -3,10 +3,22 @@
//#define SLIC3R_USE_CLIPPER2
#include <assert.h>
#include <cstddef>
#include <iterator>
#include <utility>
#include <vector>
#include <cassert>
#include "libslic3r.h"
#include "ExPolygon.hpp"
#include "Polygon.hpp"
#include "Surface.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/BoundingBox.hpp"
#ifdef SLIC3R_USE_CLIPPER2
@@ -14,7 +26,8 @@
#else /* SLIC3R_USE_CLIPPER2 */
#include "clipper.hpp"
#include "libslic3r/clipper.hpp"
// import these wherever we're included
using Slic3r::ClipperLib::jtMiter;
using Slic3r::ClipperLib::jtRound;
@@ -29,8 +42,10 @@ class BoundingBox;
static constexpr const float ClipperSafetyOffset = 10.f;
static constexpr const Slic3r::ClipperLib::JoinType DefaultJoinType = Slic3r::ClipperLib::jtMiter;
//FIXME evaluate the default miter limit. 3 seems to be extreme, Cura uses 1.2.
static constexpr const Slic3r::ClipperLib::EndType DefaultEndType = Slic3r::ClipperLib::etOpenButt;
//FIXME evaluate the default miter limit. 3 seems to be extreme, Cura uses 1.2.
// Mitter Limit 3 is useful for perimeter generator, where sharp corners are extruded without needing a gap fill.
// However such a high limit causes issues with large positive or negative offsets, where a sharp corner
// is extended excessively.
@@ -364,8 +379,10 @@ Slic3r::ExPolygons offset_ex(const Slic3r::ExPolygons &expolygons, const float d
Slic3r::ExPolygons offset_ex(const Slic3r::Surfaces &surfaces, const float delta, ClipperLib::JoinType joinType = DefaultJoinType, double miterLimit = DefaultMiterLimit);
Slic3r::ExPolygons offset_ex(const Slic3r::SurfacesPtr &surfaces, const float delta, ClipperLib::JoinType joinType = DefaultJoinType, double miterLimit = DefaultMiterLimit);
// convert stroke to path by offsetting of contour
Polygons contour_to_polygons(const Polygon &polygon, const float line_width, ClipperLib::JoinType join_type = DefaultJoinType, double miter_limit = DefaultMiterLimit);
Polygons contour_to_polygons(const Polygons &polygon, const float line_width, ClipperLib::JoinType join_type = DefaultJoinType, double miter_limit = DefaultMiterLimit);
inline Slic3r::Polygons union_safety_offset (const Slic3r::Polygons &polygons) { return offset (polygons, ClipperSafetyOffset); }
inline Slic3r::Polygons union_safety_offset (const Slic3r::ExPolygons &expolygons) { return offset (expolygons, ClipperSafetyOffset); }
inline Slic3r::ExPolygons union_safety_offset_ex(const Slic3r::Polygons &polygons) { return offset_ex(polygons, ClipperSafetyOffset); }
@@ -461,7 +478,6 @@ Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::ExPol
Slic3r::Polylines diff_pl(const Slic3r::Polylines &subject, const Slic3r::ExPolygons &clip);
Slic3r::Polylines diff_pl(const Slic3r::Polygons &subject, const Slic3r::Polygons &clip);
inline Slic3r::Lines diff_ln(const Slic3r::Lines &subject, const Slic3r::Polygons &clip)
{
return _clipper_ln(ClipperLib::ctDifference, subject, clip);
@@ -488,7 +504,6 @@ Slic3r::ExPolygons intersection_ex(const Slic3r::Surfaces &subject, const Slic3r
Slic3r::ExPolygons intersection_ex(const Slic3r::Surfaces &subject, const Slic3r::ExPolygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::ExPolygons intersection_ex(const Slic3r::Surfaces &subject, const Slic3r::Surfaces &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::ExPolygons intersection_ex(const Slic3r::SurfacesPtr &subject, const Slic3r::ExPolygons &clip, ApplySafetyOffset do_safety_offset = ApplySafetyOffset::No);
Slic3r::Polylines intersection_pl(const Slic3r::Polylines &subject, const Slic3r::Polygon &clip);
Slic3r::Polylines intersection_pl(const Slic3r::Polyline &subject, const Slic3r::ExPolygon &clip);
Slic3r::Polylines intersection_pl(const Slic3r::Polylines &subject, const Slic3r::ExPolygon &clip);

View File

@@ -1,7 +1,9 @@
#include "libslic3r.h"
#include "Color.hpp"
#include <random>
#include <cmath>
#include <cstdio>
#include <cstdlib>
#include "Color.hpp"
static const float INV_255 = 1.0f / 255.0f;

View File

@@ -1,8 +1,12 @@
#ifndef slic3r_Color_hpp_
#define slic3r_Color_hpp_
#include <assert.h>
#include <array>
#include <algorithm>
#include <string>
#include <vector>
#include <cassert>
#include "Point.hpp"

View File

@@ -1,33 +1,32 @@
#include "Config.hpp"
#include "format.hpp"
#include "Utils.hpp"
#include "LocalesUtils.hpp"
#include <assert.h>
#include <fstream>
#include <iostream>
#include <iomanip>
#include <boost/algorithm/string.hpp>
#include <boost/algorithm/string/classification.hpp>
#include <boost/algorithm/string/erase.hpp>
#include <boost/algorithm/string/predicate.hpp>
#include <boost/algorithm/string/replace.hpp>
#include <boost/algorithm/string/split.hpp>
#include <boost/config.hpp>
#include <boost/foreach.hpp>
#include <boost/lexical_cast.hpp>
#include <boost/nowide/cenv.hpp>
#include <boost/nowide/cstdio.hpp>
#include <boost/nowide/cstdlib.hpp>
#include <boost/nowide/iostream.hpp>
#include <boost/nowide/fstream.hpp>
#include <boost/nowide/cstdio.hpp>
#include <boost/property_tree/ini_parser.hpp>
#include <boost/format.hpp>
#include <string.h>
#include <LibBGCode/binarize/binarize.hpp>
//FIXME for GCodeFlavor and gcfMarlin (for forward-compatibility conversion)
// This is not nice, likely it would be better to pass the ConfigSubstitutionContext to handle_legacy().
#include "PrintConfig.hpp"
#include <boost/algorithm/string/join.hpp>
#include <boost/multi_index_container.hpp>
#include <cereal/cereal.hpp>
#include <core/core.hpp>
#include <iostream>
#include <iomanip>
#include <cstddef>
#include <set>
#include <cstdlib>
#include <cstring>
#include "format.hpp"
#include "Utils.hpp"
#include "LocalesUtils.hpp"
#include "libslic3r/Exception.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Semver.hpp"
namespace Slic3r {
@@ -273,6 +272,7 @@ ConfigOption* ConfigOptionDef::create_empty_option() const
case coBool: return new ConfigOptionBool();
case coBools: return new ConfigOptionBools();
case coEnum: return new ConfigOptionEnumGeneric(this->enum_def->m_enum_keys_map);
case coEnums: return new ConfigOptionEnumsGeneric(this->enum_def->m_enum_keys_map);
default: throw ConfigurationError(std::string("Unknown option type for option ") + this->label);
}
}
@@ -283,7 +283,10 @@ ConfigOption* ConfigOptionDef::create_default_option() const
if (this->default_value)
return (this->default_value->type() == coEnum) ?
// Special case: For a DynamicConfig, convert a templated enum to a generic enum.
new ConfigOptionEnumGeneric(this->enum_def->m_enum_keys_map, this->default_value->getInt()) :
new ConfigOptionEnumGeneric(this->enum_def->m_enum_keys_map, this->default_value->getInt()) :
(this->default_value->type() == coEnums) ?
// Special case: For a DynamicConfig, convert a templated enums to a generic enums.
new ConfigOptionEnumsGeneric(this->enum_def->m_enum_keys_map, this->default_value->getInts()) :
this->default_value->clone();
return this->create_empty_option();
}
@@ -312,7 +315,7 @@ void ConfigDef::finalize()
// Validate & finalize open & closed enums.
for (std::pair<const t_config_option_key, ConfigOptionDef> &kvp : options) {
ConfigOptionDef& def = kvp.second;
if (def.type == coEnum) {
if (def.type == coEnum || def.type == coEnums) {
assert(def.enum_def);
assert(def.enum_def->is_valid_closed_enum());
assert(! def.is_gui_type_enum_open());
@@ -353,6 +356,9 @@ std::ostream& ConfigDef::print_cli_help(std::ostream& out, bool show_defaults, s
return wrapped.str();
};
// List of opt_keys that should be hidden from the CLI help.
const std::vector<std::string> silent_options = { "webdev", "single_instance_on_url" };
// get the unique categories
std::set<std::string> categories;
for (const auto& opt : this->options) {
@@ -372,6 +378,9 @@ std::ostream& ConfigDef::print_cli_help(std::ostream& out, bool show_defaults, s
const ConfigOptionDef& def = opt.second;
if (def.category != category || def.cli == ConfigOptionDef::nocli || !filter(def))
continue;
if (std::find(silent_options.begin(), silent_options.end(), opt.second.opt_key) != silent_options.end())
continue;
// get all possible variations: --foo, --foobar, -f...
std::vector<std::string> cli_args = def.cli_args(opt.first);
@@ -746,7 +755,7 @@ ConfigSubstitutions ConfigBase::load(const std::string& filename, ForwardCompati
file_type = EFileType::Ini;
switch (file_type)
{
{
case EFileType::Ini: { return this->load_from_ini(filename, compatibility_rule); }
case EFileType::AsciiGCode: { return this->load_from_gcode_file(filename, compatibility_rule);}
case EFileType::BinaryGCode: { return this->load_from_binary_gcode_file(filename, compatibility_rule);}
@@ -888,6 +897,7 @@ size_t ConfigBase::load_from_gcode_string_legacy(ConfigBase& config, const char*
// Do legacy conversion on a completely loaded dictionary.
// Perform composite conversions, for example merging multiple keys into one key.
config.handle_legacy_composite();
return num_key_value_pairs;
}
@@ -1048,8 +1058,8 @@ ConfigSubstitutions ConfigBase::load_from_gcode_file(const std::string &filename
// Try a heuristics reading the G-code from back.
ifs.seekg(0, ifs.end);
auto file_length = ifs.tellg();
auto data_length = std::min<std::fstream::pos_type>(65535, file_length - header_end_pos);
ifs.seekg(file_length - data_length, ifs.beg);
auto data_length = std::min<std::fstream::pos_type>(65535, file_length - header_end_pos);
ifs.seekg(file_length - data_length, ifs.beg);
std::vector<char> data(size_t(data_length) + 1, 0);
ifs.read(data.data(), data_length);
ifs.close();
@@ -1406,7 +1416,7 @@ t_config_option_keys DynamicConfig::equal(const DynamicConfig &other) const
}
#include <cereal/types/polymorphic.hpp>
#include <cereal/types/polymorphic.hpp> // IWYU pragma: keep
CEREAL_REGISTER_TYPE(Slic3r::ConfigOption)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionSingle<double>)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionSingle<int>)
@@ -1446,6 +1456,7 @@ CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionBool)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionBools)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionBoolsNullable)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionEnumGeneric)
CEREAL_REGISTER_TYPE(Slic3r::ConfigOptionEnumsGeneric)
CEREAL_REGISTER_TYPE(Slic3r::ConfigBase)
CEREAL_REGISTER_TYPE(Slic3r::DynamicConfig)
@@ -1487,4 +1498,5 @@ CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigOptionSingle<bool>, Slic3r::C
CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigOptionVector<unsigned char>, Slic3r::ConfigOptionBools)
CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigOptionVector<unsigned char>, Slic3r::ConfigOptionBoolsNullable)
CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigOptionInt, Slic3r::ConfigOptionEnumGeneric)
CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigOptionInts, Slic3r::ConfigOptionEnumsGeneric)
CEREAL_REGISTER_POLYMORPHIC_RELATION(Slic3r::ConfigBase, Slic3r::DynamicConfig)

View File

@@ -2,6 +2,17 @@
#define slic3r_Config_hpp_
#include <assert.h>
#include <float.h>
#include <boost/algorithm/string/predicate.hpp>
#include <boost/algorithm/string/trim.hpp>
#include <boost/format/format_fwd.hpp>
#include <boost/functional/hash.hpp>
#include <boost/property_tree/ptree_fwd.hpp>
#include <cereal/access.hpp>
#include <cereal/types/base_class.hpp>
#include <ctype.h>
#include <boost/container_hash/hash.hpp>
#include <cereal/cereal.hpp>
#include <map>
#include <climits>
#include <limits>
@@ -14,20 +25,22 @@
#include <string_view>
#include <type_traits>
#include <vector>
#include <float.h>
#include <algorithm>
#include <cmath>
#include <initializer_list>
#include <memory>
#include <optional>
#include <utility>
#include <variant>
#include <cassert>
#include <cctype>
#include <cfloat>
#include "libslic3r.h"
#include "clonable_ptr.hpp"
#include "Exception.hpp"
#include "Point.hpp"
#include <boost/algorithm/string/predicate.hpp>
#include <boost/algorithm/string/trim.hpp>
#include <boost/format/format_fwd.hpp>
#include <boost/functional/hash.hpp>
#include <boost/property_tree/ptree_fwd.hpp>
#include <cereal/access.hpp>
#include <cereal/types/base_class.hpp>
#include "LocalesUtils.hpp"
namespace Slic3r {
struct FloatOrPercent
@@ -193,6 +206,8 @@ enum ConfigOptionType {
coBools = coBool + coVectorType,
// a generic enum
coEnum = 9,
// vector of enum values
coEnums = coEnum + coVectorType,
};
enum ConfigOptionMode {
@@ -231,6 +246,7 @@ enum ForwardCompatibilitySubstitutionRule
class ConfigDef;
class ConfigOption;
class ConfigOptionDef;
// For forward definition of ConfigOption in ConfigOptionUniquePtr, we have to define a custom deleter.
struct ConfigOptionDeleter { void operator()(ConfigOption* p); };
using ConfigOptionUniquePtr = std::unique_ptr<ConfigOption, ConfigOptionDeleter>;
@@ -269,6 +285,7 @@ public:
// Set a value from a ConfigOption. The two options should be compatible.
virtual void set(const ConfigOption *option) = 0;
virtual int getInt() const { throw BadOptionTypeException("Calling ConfigOption::getInt on a non-int ConfigOption"); }
virtual std::vector<int> getInts() const { throw BadOptionTypeException("Calling ConfigOption::getInts on a non-ints ConfigOption"); }
virtual double getFloat() const { throw BadOptionTypeException("Calling ConfigOption::getFloat on a non-float ConfigOption"); }
virtual bool getBool() const { throw BadOptionTypeException("Calling ConfigOption::getBool on a non-boolean ConfigOption"); }
virtual void setInt(int /* val */) { throw BadOptionTypeException("Calling ConfigOption::setInt on a non-int ConfigOption"); }
@@ -318,7 +335,7 @@ template<class T>
struct NilValueTempl<T, std::enable_if_t<std::is_enum_v<T>, void>>
{
using NilType = T;
static constexpr auto value = static_cast<T>(std::numeric_limits<std::underlying_type_t<T>>::max());
static constexpr auto value = static_cast<std::underlying_type_t<T>>(std::numeric_limits<std::underlying_type_t<T>>::max());
};
template<class T> struct NilValueTempl<T, std::enable_if_t<std::is_floating_point_v<T>, void>> {
@@ -346,6 +363,7 @@ template<class T> using NilType = typename NilValueTempl<remove_cvref_t<T>>::Nil
// Define shortcut as a function instead of a static const var so that it can be constexpr
// even if the NilValueTempl::value is not constexpr.
template<class T> static constexpr NilType<T> NilValue() noexcept { return NilValueTempl<remove_cvref_t<T>>::value; }
// Value of a single valued option (bool, int, float, string, point, enum)
template <class T, bool NULLABLE = false>
class ConfigOptionSingle : public ConfigOption {
@@ -430,6 +448,7 @@ public:
return ret;
}
private:
friend class cereal::access;
template<class Archive> void serialize(Archive & ar) { ar(this->value); }
@@ -437,6 +456,7 @@ private:
template<class T>
using ConfigOptionSingleNullable = ConfigOptionSingle<T, true>;
// Value of a vector valued option (bools, ints, floats, strings, points)
class ConfigOptionVectorBase : public ConfigOption {
public:
@@ -683,6 +703,7 @@ public:
throw ConfigurationError("Serializing NaN");
} else
throw ConfigurationError("Serializing invalid number");
return ss.str();
}
@@ -690,14 +711,16 @@ public:
{
UNUSED(append);
std::istringstream iss(str);
if (str == "nil") {
if (NULLABLE)
this->value = this->nil_value();
else
throw ConfigurationError("Deserializing nil into a non-nullable object");
} else {
iss >> this->value;
iss >> this->value;
}
return !iss.fail();
}
@@ -711,6 +734,7 @@ public:
{
return std::isnan(this->value);
}
private:
friend class cereal::access;
template<class Archive> void serialize(Archive &ar) { ar(cereal::base_class<ConfigOptionSingle<double, NULLABLE>>(this)); }
@@ -868,7 +892,8 @@ public:
else
throw ConfigurationError("Serializing NaN");
} else
ss << this->value;
ss << this->value;
return ss.str();
}
@@ -876,14 +901,16 @@ public:
{
UNUSED(append);
std::istringstream iss(str);
if (str == "nil") {
if (NULLABLE)
this->value = this->nil_value();
else
throw ConfigurationError("Deserializing nil into a non-nullable object");
} else {
iss >> this->value;
iss >> this->value;
}
return !iss.fail();
}
@@ -900,6 +927,7 @@ private:
using ConfigOptionInt = ConfigOptionIntTempl<false>;
using ConfigOptionIntNullable = ConfigOptionIntTempl<true>;
template<bool NULLABLE>
class ConfigOptionIntsTempl : public ConfigOptionVector<int>
{
@@ -1709,6 +1737,113 @@ public:
}
};
template <class T>
class ConfigOptionEnums : public ConfigOptionVector<T>
{
public:
// by default, use the first value (0) of the T enum type
ConfigOptionEnums() : ConfigOptionVector<T>() {}
explicit ConfigOptionEnums(size_t n, const T& value) : ConfigOptionVector<T>(n, value) {}
explicit ConfigOptionEnums(std::initializer_list<T> il) : ConfigOptionVector<T>(std::move(il)) {}
explicit ConfigOptionEnums(const std::vector<T>& values) : ConfigOptionVector<T>(values) {}
static ConfigOptionType static_type() { return coEnums; }
ConfigOptionType type() const override { return static_type(); }
ConfigOption* clone() const override { return new ConfigOptionEnums<T>(*this); }
ConfigOptionEnums<T>& operator=(const ConfigOption *opt) { this->set(opt); return *this; }
bool operator==(const ConfigOptionEnums<T> &rhs) const throw() { return this->values == rhs.values; }
bool operator< (const ConfigOptionEnums<T> &rhs) const throw() { return this->values < rhs.values; }
bool is_nil(size_t) const override { return false; }
std::vector<int> getInts() const override {
std::vector<int> ret;
ret.reserve(this->values.size());
for (const auto& v : this->values)
ret.push_back(int(v));
return ret;
}
bool operator==(const ConfigOption& rhs) const override
{
if (rhs.type() != this->type())
throw ConfigurationError("ConfigOptionEnums<T>: Comparing incompatible types");
// rhs could be of the following type: ConfigOptionEnumsGeneric or ConfigOptionEnums<T>
return this->getInts() == rhs.getInts();
}
void set(const ConfigOption* rhs) override {
if (rhs->type() != this->type())
throw ConfigurationError("ConfigOptionEnums<T>: Assigning an incompatible type");
// rhs could be of the following type: ConfigOptionEnumGeneric or ConfigOptionEnum<T>
std::vector<T> ret;
std::vector<int> rhs_vals = rhs->getInts();
ret.reserve(rhs_vals.size());
for (const int& v : rhs_vals)
ret.push_back(T(v));
this->values = ret;
}
std::string serialize() const override
{
const t_config_enum_names& names = ConfigOptionEnum<T>::get_enum_names();
std::ostringstream ss;
for (const T& v : this->values) {
assert(static_cast<int>(v) < int(names.size()));
if (&v != &this->values.front())
ss << "," << names[static_cast<int>(v)];
}
return ss.str();
}
std::vector<std::string> vserialize() const override
{
std::vector<std::string> vv;
vv.reserve(this->values.size());
for (const T v : this->values) {
std::ostringstream ss;
serialize_single_value(ss, int(v));
vv.push_back(ss.str());
}
return vv;
}
bool deserialize(const std::string& str, bool append = false) override
{
if (!append)
this->values.clear();
std::istringstream is(str);
std::string item_str;
while (std::getline(is, item_str, ',')) {
boost::trim(item_str);
if (item_str == "nil") {
throw ConfigurationError("Deserializing nil into a non-nullable object");
}
else {
std::istringstream iss(item_str);
int value;
iss >> value;
this->values.push_back(static_cast<T>(value));
}
}
return true;
}
static bool from_string(const std::string &str, T &value)
{
const t_config_enum_values &enum_keys_map = ConfigOptionEnum<T>::get_enum_values();
auto it = enum_keys_map.find(str);
if (it == enum_keys_map.end())
return false;
value = static_cast<T>(it->second);
return true;
}
private:
void serialize_single_value(std::ostringstream& ss, const int v) const {
ss << v;
}
};
// Generic enum configuration value.
// We use this one in DynamicConfig objects when creating a config value object for ConfigOptionType == coEnum.
// In the StaticConfig, it is better to use the specialized ConfigOptionEnum<T> containers.
@@ -1765,6 +1900,132 @@ private:
template<class Archive> void serialize(Archive& ar) { ar(cereal::base_class<ConfigOptionInt>(this)); }
};
template<bool NULLABLE>
class ConfigOptionEnumsGenericTempl : public ConfigOptionIntsTempl<NULLABLE>
{
public:
ConfigOptionEnumsGenericTempl(const t_config_enum_values* keys_map = nullptr) : keys_map(keys_map) {}
explicit ConfigOptionEnumsGenericTempl(const t_config_enum_values* keys_map, std::vector<int> values) : keys_map(keys_map) { this->values = values; }
const t_config_enum_values* keys_map;
ConfigOptionEnumsGenericTempl() : ConfigOptionIntsTempl<NULLABLE>() {}
explicit ConfigOptionEnumsGenericTempl(size_t n, int value) : ConfigOptionIntsTempl<NULLABLE>(n, value) {}
explicit ConfigOptionEnumsGenericTempl(std::initializer_list<int> il) : ConfigOptionIntsTempl<NULLABLE>(std::move(il)) {}
explicit ConfigOptionEnumsGenericTempl(const std::vector<int>& v) : ConfigOptionIntsTempl<NULLABLE>(v) {}
explicit ConfigOptionEnumsGenericTempl(std::vector<int>&& v) : ConfigOptionIntsTempl<NULLABLE>(std::move(v)) {}
static ConfigOptionType static_type() { return coEnums; }
ConfigOptionType type() const override { return static_type(); }
ConfigOption* clone() const override { return new ConfigOptionEnumsGenericTempl(*this); }
ConfigOptionEnumsGenericTempl& operator= (const ConfigOption* opt) { this->set(opt); return *this; }
bool operator==(const ConfigOptionEnumsGenericTempl& rhs) const throw() { return this->values == rhs.values; }
bool operator< (const ConfigOptionEnumsGenericTempl& rhs) const throw() { return this->values < rhs.values; }
std::vector<int> getInts() const override { return this->values; }
bool operator==(const ConfigOption& rhs) const override
{
if (rhs.type() != this->type())
throw ConfigurationError("ConfigOptionEnumsGeneric: Comparing incompatible types");
// rhs could be of the following type: ConfigOptionEnumsGeneric or ConfigOptionEnums<T>
return this->values == rhs.getInts();
}
void set(const ConfigOption* rhs) override {
if (rhs->type() != this->type())
throw ConfigurationError("ConfigOptionEnumsGeneric: Assigning an incompatible type");
// rhs could be of the following type: ConfigOptionEnumsGeneric or ConfigOptionEnums<T>
this->values = rhs->getInts();
}
// Could a special "nil" value be stored inside the vector, indicating undefined value?
bool nullable() const override { return NULLABLE; }
// Special "nil" value to be stored into the vector if this->supports_nil().
static int nil_value() { return std::numeric_limits<int>::max(); }
// A scalar is nil, or all values of a vector are nil.
bool is_nil() const override { for (auto v : this->values) if (v != nil_value()) return false; return true; }
bool is_nil(size_t idx) const override { return this->values[idx < this->values.size() ? idx : 0] == nil_value(); }
int& get_at(size_t i) {
assert(!this->values.empty());
return *reinterpret_cast<int*>(&((i < this->values.size()) ? this->values[i] : this->values.front()));
}
int get_at(size_t i) const { return i < this->values.size() ? this->values[i] : this->values.front(); }
std::string serialize() const override
{
std::ostringstream ss;
for (const int& v : this->values) {
if (&v != &this->values.front())
ss << ",";
serialize_single_value(ss, v);
}
return ss.str();
}
std::vector<std::string> vserialize() const override
{
std::vector<std::string> vv;
vv.reserve(this->values.size());
for (const int v : this->values) {
std::ostringstream ss;
serialize_single_value(ss, v);
vv.push_back(ss.str());
}
return vv;
}
bool deserialize(const std::string& str, bool append = false) override
{
if (!append)
this->values.clear();
std::istringstream is(str);
std::string item_str;
while (std::getline(is, item_str, ',')) {
boost::trim(item_str);
if (item_str == "nil") {
if (NULLABLE)
this->values.push_back(nil_value());
else
throw ConfigurationError("Deserializing nil into a non-nullable object");
}
else {
auto it = this->keys_map->find(item_str);
if (it == this->keys_map->end())
return false;
this->values.push_back(it->second);
}
}
return true;
}
private:
void serialize_single_value(std::ostringstream& ss, const int v) const {
if (v == nil_value()) {
if (NULLABLE)
ss << "nil";
else
throw ConfigurationError("Serializing NaN");
}
else {
for (const auto& kvp : *this->keys_map)
if (kvp.second == v) {
ss << kvp.first;
return;
}
ss << std::string();
}
}
friend class cereal::access;
template<class Archive> void serialize(Archive& ar) { ar(cereal::base_class<ConfigOptionVector<int>>(this)); }
};
using ConfigOptionEnumsGeneric = ConfigOptionEnumsGenericTempl<false>;
using ConfigOptionEnumsGenericNullable = ConfigOptionEnumsGenericTempl<true>;
// Definition of values / labels for a combo box.
// Mostly used for closed enums (when type == coEnum), but may be used for
// open enums with ints resp. floats, if gui_type is set to GUIType::i_enum_open" resp. GUIType::f_enum_open.
@@ -1958,6 +2219,8 @@ public:
one_string,
// Close parameter, string value could be one of the list values.
select_close,
// Password, string vaule is hidden by asterisk.
password,
};
static bool is_gui_type_enum_open(const GUIType gui_type)
{ return gui_type == ConfigOptionDef::GUIType::i_enum_open || gui_type == ConfigOptionDef::GUIType::f_enum_open || gui_type == ConfigOptionDef::GUIType::select_open; }
@@ -1979,6 +2242,7 @@ public:
ConfigOption* create_default_option() const;
bool is_scalar() const { return (int(this->type) & int(coVectorType)) == 0; }
template<class Archive> ConfigOption* load_option_from_archive(Archive &archive) const {
if (this->nullable) {
switch (this->type) {
@@ -2008,6 +2272,7 @@ public:
case coBool: { auto opt = new ConfigOptionBool(); archive(*opt); return opt; }
case coBools: { auto opt = new ConfigOptionBools(); archive(*opt); return opt; }
case coEnum: { auto opt = new ConfigOptionEnumGeneric(this->enum_def->m_enum_keys_map); archive(*opt); return opt; }
case coEnums: { auto opt = new ConfigOptionEnumsGeneric(this->enum_def->m_enum_keys_map); archive(*opt); return opt; }
default: throw ConfigurationError(std::string("ConfigOptionDef::load_option_from_archive(): Unknown option type for option ") + this->opt_key);
}
}
@@ -2042,6 +2307,7 @@ public:
case coBool: archive(*static_cast<const ConfigOptionBool*>(opt)); break;
case coBools: archive(*static_cast<const ConfigOptionBools*>(opt)); break;
case coEnum: archive(*static_cast<const ConfigOptionEnumGeneric*>(opt)); break;
case coEnums: archive(*static_cast<const ConfigOptionEnumsGeneric*>(opt)); break;
default: throw ConfigurationError(std::string("ConfigOptionDef::save_option_to_archive(): Unknown option type for option ") + this->opt_key);
}
}
@@ -2449,6 +2715,8 @@ public:
// Thus the virtual method getInt() is used to retrieve the enum value.
template<typename ENUM>
ENUM opt_enum(const t_config_option_key &opt_key) const { return static_cast<ENUM>(this->option(opt_key)->getInt()); }
template<typename ENUM>
ENUM opt_enum(const t_config_option_key &opt_key, unsigned int idx) const { return dynamic_cast<const ConfigOptionEnums<ENUM>*>(this->option(opt_key))->get_at(idx);}
bool opt_bool(const t_config_option_key &opt_key) const { return this->option<ConfigOptionBool>(opt_key)->value != 0; }
bool opt_bool(const t_config_option_key &opt_key, unsigned int idx) const { return this->option<ConfigOptionBools>(opt_key)->get_at(idx) != 0; }

View File

@@ -1,7 +1,10 @@
#include "CustomGCode.hpp"
#include <cassert>
#include "Config.hpp"
#include "GCode.hpp"
#include "GCode/GCodeWriter.hpp"
#include "libslic3r/PrintConfig.hpp"
namespace Slic3r {
@@ -83,6 +86,7 @@ std::vector<std::pair<double, unsigned int>> custom_color_changes(const Info& cu
}
return custom_color_changes;
}
} // namespace CustomGCode
} // namespace Slic3r

View File

@@ -1,8 +1,11 @@
#ifndef slic3r_CustomGCode_hpp_
#define slic3r_CustomGCode_hpp_
#include <stddef.h>
#include <string>
#include <vector>
#include <utility>
#include <cstddef>
namespace Slic3r {
@@ -10,6 +13,11 @@ class DynamicPrintConfig;
namespace CustomGCode {
/* For exporting GCode in GCodeWriter is used XYZF_NUM(val) = PRECISION(val, 3) for XYZ values.
* So, let use same value as a permissible error for layer height.
*/
constexpr double epsilon() { return 0.0011; }
enum Type
{
ColorChange,
@@ -90,6 +98,7 @@ std::vector<std::pair<double, unsigned int>> custom_tool_changes(const Info& cus
// Return pairs of <print_z, 1-based extruder ID> sorted by increasing print_z from custom_gcode_per_print_z.
// Where print_z corresponds to the layer on which we perform a color change for the specified extruder.
std::vector<std::pair<double, unsigned int>> custom_color_changes(const Info& custom_gcode_per_print_z, size_t num_extruders);
} // namespace CustomGCode
} // namespace Slic3r

View File

@@ -23,18 +23,41 @@
//#define DEBUG_OUTPUT_DIR std::string("C:/data/temp/cutSurface/")
using namespace Slic3r;
#include "ExPolygonsIndex.hpp"
#include <CGAL/Polygon_mesh_processing/corefinement.h>
#include <CGAL/Exact_integer.h>
#include <CGAL/Surface_mesh.h>
#include <CGAL/Cartesian_converter.h>
#include <tbb/parallel_for.h>
#include <oneapi/tbb/blocked_range.h>
#include <oneapi/tbb/parallel_for.h>
#include <boost/property_map/property_map.hpp>
#include <algorithm>
#include <array>
#include <cmath>
#include <cstddef>
#include <cstdint>
#include <iterator>
#include <limits>
#include <map>
#include <optional>
#include <queue>
#include <set>
#include <tuple>
#include <utility>
#include <cassert>
#include "ExPolygonsIndex.hpp"
// libslic3r
#include "TriangleMesh.hpp" // its_merge
#include "Utils.hpp" // next_highest_power_of_2
#include "ClipperUtils.hpp" // union_ex + offset_ex
#include "admesh/stl.h"
#include "libslic3r/AABBTreeIndirect.hpp"
#include "libslic3r/ClipperUtils.hpp"
#include "libslic3r/Emboss.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Exception.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/libslic3r.h"
namespace priv {
@@ -449,17 +472,21 @@ ProjectionDistances choose_best_distance(
/// </summary>
/// <param name="best_distances">For each point selected closest distance</param>
/// <param name="patches">All patches</param>
/// <param name="shapes">All patches</param>
/// <param name="shapes">Shape to cut</param>
/// <param name="shapes_bb">Bound of shapes</param>
/// <param name="s2i"></param>
/// <param name="cutAOIs"></param>
/// <param name="meshes"></param>
/// <param name="projection"></param>
/// <returns>Mask of used patch</returns>
std::vector<bool> select_patches(const ProjectionDistances &best_distances,
const SurfacePatches &patches,
const ExPolygons &shapes,
const ExPolygons &shapes,
const BoundingBox &shapes_bb,
const ExPolygonsIndices &s2i,
const VCutAOIs &cutAOIs,
const CutMeshes &meshes,
const Project &projection);
const ExPolygonsIndices &s2i,
const VCutAOIs &cutAOIs,
const CutMeshes &meshes,
const Project &projection);
/// <summary>
/// Merge two surface cuts together
@@ -513,9 +540,10 @@ void store(const Emboss::IProjection &projection, const Point &point_to_project,
} // namespace privat
#ifdef DEBUG_OUTPUT_DIR
#include "libslic3r/SVG.hpp"
#include <boost/log/trivial.hpp>
#include <filesystem>
#include "libslic3r/SVG.hpp"
#endif // DEBUG_OUTPUT_DIR
SurfaceCut Slic3r::cut_surface(const ExPolygons &shapes,
@@ -1771,6 +1799,7 @@ priv::VDistances priv::calc_distances(const SurfacePatches &patches,
#include "libslic3r/AABBTreeLines.hpp"
#include "libslic3r/Line.hpp"
// functions for choose_best_distance
namespace priv {
@@ -2242,7 +2271,7 @@ priv::ProjectionDistances priv::choose_best_distance(
if (unfinished_index >= s2i.get_count())
// no point to select
return result;
#ifdef DEBUG_OUTPUT_DIR
Connections connections;
connections.reserve(shapes.size());
@@ -2552,6 +2581,7 @@ void priv::create_face_types(FaceTypeMap &map,
#include <CGAL/Polygon_mesh_processing/clip.h>
#include <CGAL/Polygon_mesh_processing/corefinement.h>
bool priv::clip_cut(SurfacePatch &cut, CutMesh clipper)
{
CutMesh& tm = cut.mesh;
@@ -3218,15 +3248,15 @@ bool priv::is_over_whole_expoly(const CutAOI &cutAOI,
std::vector<bool> priv::select_patches(const ProjectionDistances &best_distances,
const SurfacePatches &patches,
const ExPolygons &shapes,
const ExPolygons &shapes,
const BoundingBox &shapes_bb,
const ExPolygonsIndices &s2i,
const VCutAOIs &cutAOIs,
const CutMeshes &meshes,
const Project &projection)
const ExPolygonsIndices &s2i,
const VCutAOIs &cutAOIs,
const CutMeshes &meshes,
const Project &projection)
{
// extension to cover numerical mistake made by back projection patch from 3d to 2d
// Calculated as one percent of average size(width and height)
Point s = shapes_bb.size();
const float extend_delta = (s.x() + s.y())/ float(2 * 100);

View File

@@ -1,12 +1,19 @@
#ifndef slic3r_CutSurface_hpp_
#define slic3r_CutSurface_hpp_
#include <vector>
#include <admesh/stl.h> // indexed_triangle_set
#include <vector>
#include <string>
#include "ExPolygon.hpp"
#include "Emboss.hpp" // IProjection
#include "libslic3r/BoundingBox.hpp"
namespace Slic3r{
namespace Emboss {
class IProject3d;
class IProjection;
} // namespace Emboss
/// <summary>
/// Represents cutted surface from object

View File

@@ -1,13 +1,21 @@
#include "CutUtils.hpp"
#include <boost/log/trivial.hpp>
#include <cmath>
#include <string>
#include <utility>
#include <cassert>
#include <cstddef>
#include "Geometry.hpp"
#include "libslic3r.h"
#include "Model.hpp"
#include "TriangleMeshSlicer.hpp"
#include "TriangleSelector.hpp"
#include "ObjectID.hpp"
#include <boost/log/trivial.hpp>
#include "admesh/stl.h"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/TriangleMesh.hpp"
namespace Slic3r {
@@ -391,14 +399,20 @@ static void distribute_modifiers_from_object(ModelObject* from_obj, const int in
for (ModelVolume* vol : from_obj->volumes)
if (!vol->is_model_part()) {
// Don't add modifiers which are processed connectors
if (vol->cut_info.is_connector && !vol->cut_info.is_processed)
continue;
// Modifiers are not cut, but we still need to add the instance transformation
// to the modifier volume transformation to preserve their shape properly.
const auto modifier_trafo = Transformation(from_obj->instances[instance_idx]->get_transformation().get_matrix_no_offset() * vol->get_matrix());
auto bb = vol->mesh().transformed_bounding_box(inst_matrix * vol->get_matrix());
// Don't add modifiers which are not intersecting with solid parts
if (obj1_bb.intersects(bb))
to_obj1->add_volume(*vol);
to_obj1->add_volume(*vol)->set_transformation(modifier_trafo);
if (obj2_bb.intersects(bb))
to_obj2->add_volume(*vol);
to_obj2->add_volume(*vol)->set_transformation(modifier_trafo);
}
}
@@ -423,6 +437,7 @@ static void merge_solid_parts_inside_object(ModelObjectPtrs& objects)
if (mv->is_model_part() && !mv->is_cut_connector())
mo->delete_volume(i);
}
// Ensuring that volumes start with solid parts for proper slicing
mo->sort_volumes(true);
}
}
@@ -463,6 +478,8 @@ const ModelObjectPtrs& Cut::perform_by_contour(std::vector<Part> parts, int dowe
// Just add Upper and Lower objects to cut_object_ptrs
post_process(upper, lower, cut_object_ptrs);
// Now merge all model parts together:
merge_solid_parts_inside_object(cut_object_ptrs);
// replace initial objects in model with cut object
@@ -493,17 +510,18 @@ const ModelObjectPtrs& Cut::perform_by_contour(std::vector<Part> parts, int dowe
// Add Upper and Lower objects to cut_object_ptrs
post_process(upper, lower, cut_object_ptrs);
// Add Dowel-connectors as separate objects to cut_object_ptrs
// Now merge all model parts together:
merge_solid_parts_inside_object(cut_object_ptrs);
// Now merge all model parts together:
merge_solid_parts_inside_object(cut_object_ptrs);
finalize(cut_object_ptrs);
// replace initial objects in model with cut object
finalize(cut_object_ptrs);
// Add Dowel-connectors as separate objects to model
if (cut_connectors_obj.size() >= 3)
for (size_t id = 2; id < cut_connectors_obj.size(); id++)
m_model.add_object(*cut_connectors_obj[id]);
}
return m_model.objects;
}
@@ -618,8 +636,12 @@ const ModelObjectPtrs& Cut::perform_with_groove(const Groove& groove, const Tran
// add modifiers
for (const ModelVolume* volume : cut_mo->volumes)
if (!volume->is_model_part())
upper->add_volume(*volume);
if (!volume->is_model_part()) {
// Modifiers are not cut, but we still need to add the instance transformation
// to the modifier volume transformation to preserve their shape properly.
const auto modifier_trafo = Transformation(cut_mo->instances[m_instance]->get_transformation().get_matrix_no_offset() * volume->get_matrix());
upper->add_volume(*volume)->set_transformation(modifier_trafo);
}
cut_object_ptrs.push_back(upper);
@@ -627,7 +649,11 @@ const ModelObjectPtrs& Cut::perform_with_groove(const Groove& groove, const Tran
cut_object_ptrs.push_back(lower);
}
else {
// add modifiers if object has any
reset_instance_transformation(upper, m_instance, m_cut_matrix);
reset_instance_transformation(lower, m_instance, m_cut_matrix);
// Add modifiers if object has any
// Note: make it after all transformations are reset for upper/lower object
for (const ModelVolume* volume : cut_mo->volumes)
if (!volume->is_model_part()) {
distribute_modifiers_from_object(cut_mo, m_instance, upper, lower);

View File

@@ -1,9 +1,9 @@
#include <algorithm>
#include <vector>
#include <float.h>
#include <unordered_map>
#include <png.h>
#include <cstdint>
#include <set>
#include <cfloat>
#include "libslic3r.h"
#include "ClipperUtils.hpp"
@@ -11,6 +11,9 @@
#include "Geometry.hpp"
#include "SVG.hpp"
#include "PNGReadWrite.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Point.hpp"
// #define EDGE_GRID_DEBUG_OUTPUT
@@ -21,8 +24,6 @@
#undef NDEBUG
#endif
#include <assert.h>
namespace Slic3r {
void EdgeGrid::Grid::create(const Polygons &polygons, coord_t resolution)

View File

@@ -3,10 +3,25 @@
#include <stdint.h>
#include <math.h>
#include <assert.h>
#include <stdlib.h>
#include <algorithm>
#include <cmath>
#include <limits>
#include <string>
#include <utility>
#include <vector>
#include <cassert>
#include <cinttypes>
#include <cstdlib>
#include "Point.hpp"
#include "BoundingBox.hpp"
#include "ExPolygon.hpp"
#include "libslic3r/Line.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/libslic3r.h"
namespace Slic3r {
namespace EdgeGrid {

View File

@@ -1,5 +1,13 @@
#include "clipper/clipper_z.hpp"
#include <cmath>
#include <cassert>
#include <algorithm>
#include <limits>
#include <utility>
#include <vector>
#include <cstddef>
#include "libslic3r.h"
#include "ClipperUtils.hpp"
#include "EdgeGrid.hpp"
@@ -7,11 +15,10 @@
#include "ElephantFootCompensation.hpp"
#include "Flow.hpp"
#include "Geometry.hpp"
#include "SVG.hpp"
#include "Utils.hpp"
#include <cmath>
#include <cassert>
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polygon.hpp"
// #define CONTOUR_DISTANCE_DEBUG_SVG

View File

@@ -1,9 +1,10 @@
#ifndef slic3r_ElephantFootCompensation_hpp_
#define slic3r_ElephantFootCompensation_hpp_
#include <vector>
#include "libslic3r.h"
#include "ExPolygon.hpp"
#include <vector>
namespace Slic3r {

View File

@@ -1,22 +1,36 @@
#include <numeric>
#include "Emboss.hpp"
#include <stdio.h>
#include <numeric>
#include <cstdlib>
#include <boost/nowide/convert.hpp>
#include <boost/log/trivial.hpp>
#include <ClipperUtils.hpp> // union_ex + for boldness(polygon extend(offset))
#include <numeric>
#include <cstdlib>
#include <algorithm>
#include <cctype>
#include <cmath>
#include <cstdint>
#include <cstdio>
#include <iterator>
#include <limits>
#include "Emboss.hpp"
#include "IntersectionPoints.hpp"
#include "admesh/stl.h"
#include "libslic3r/AABBTreeIndirect.hpp"
#include "libslic3r/EmbossShape.hpp"
#include "libslic3r/ExPolygon.hpp"
#include "libslic3r/Exception.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/TextConfiguration.hpp"
#define STB_TRUETYPE_IMPLEMENTATION // force following include to generate implementation
#include "imgui/imstb_truetype.h" // stbtt_fontinfo
#include <libslic3r/Triangulation.hpp> // CGAL project
// Explicit horror include (used to be implicit) - libslic3r "officialy" does not depend on imgui.
#include "../../bundled_deps/imgui/imgui/imstb_truetype.h" // stbtt_fontinfo
#include "Utils.hpp" // ScopeGuard
#include <Triangulation.hpp> // CGAL project
#include "libslic3r.h"
// to heal shape
#include "ExPolygonsIndex.hpp"
#include "libslic3r/ClipperUtils.hpp" // union_ex + for boldness(polygon extend(offset))
#include "libslic3r/ExPolygonsIndex.hpp"
#include "libslic3r/AABBTreeLines.hpp" // search structure for found close points
#include "libslic3r/Line.hpp"
#include "libslic3r/BoundingBox.hpp"
@@ -52,6 +66,8 @@ namespace {
// for debug purpose only
// NOTE: check scale when store svg !!
#include "libslic3r/SVG.hpp" // for visualize_heal
Points get_unique_intersections(const Slic3r::IntersectionsLines &intersections); // fast forward declaration
static std::string visualize_heal_svg_filepath = "C:/data/temp/heal.svg";
void visualize_heal(const std::string &svg_filepath, const ExPolygons &expolygons)
{
@@ -635,6 +651,10 @@ bool heal_dupl_inter(ExPolygons &shape, unsigned max_iteration)
expoly = create_bounding_rect({expoly});
}
}
// After insert bounding box unify and heal
shape = union_ex(shape);
heal_dupl_inter(shape, 1);
return false;
}
@@ -766,14 +786,13 @@ const Glyph* get_glyph(
unsigned int font_index = font_prop.collection_number.value_or(0);
if (!is_valid(font, font_index)) return nullptr;
if (!font_info_opt.has_value()) {
font_info_opt = load_font_info(font.data->data(), font_index);
if (!font_info_opt.has_value()) {
font_info_opt = load_font_info(font.data->data(), font_index);
// can load font info?
if (!font_info_opt.has_value()) return nullptr;
}
float flatness = font.infos[font_index].ascent * RESOLUTION / font_prop.size_in_mm;
float flatness = font.infos[font_index].unit_per_em / font_prop.size_in_mm * RESOLUTION;
// Fix for very small flatness because it create huge amount of points from curve
if (flatness < RESOLUTION) flatness = RESOLUTION;
@@ -1057,11 +1076,10 @@ std::unique_ptr<FontFile> Emboss::create_font_file(
int ascent, descent, linegap;
stbtt_GetFontVMetrics(info, &ascent, &descent, &linegap);
float pixels = 1000.; // value is irelevant
float em_pixels = stbtt_ScaleForMappingEmToPixels(info, pixels);
int units_per_em = static_cast<int>(std::round(pixels / em_pixels));
infos.emplace_back(FontFile::Info{ascent, descent, linegap, units_per_em});
float pixels = 1000.; // value is irelevant
float em_pixels = stbtt_ScaleForMappingEmToPixels(info, pixels);
int unit_per_em = static_cast<int>(std::round(pixels / em_pixels));
infos.emplace_back(FontFile::Info{ascent, descent, linegap, unit_per_em});
}
return std::make_unique<FontFile>(std::move(data), std::move(infos));
}
@@ -1191,15 +1209,13 @@ int Emboss::get_line_height(const FontFile &font, const FontProp &prop) {
namespace {
ExPolygons letter2shapes(
wchar_t letter, Point &cursor, FontFileWithCache &font_with_cache, const FontProp &font_prop, fontinfo_opt& font_info_cache)
{
assert(font_with_cache.has_value());
if (!font_with_cache.has_value())
return {};
Glyphs &cache = *font_with_cache.cache;
const FontFile &font = *font_with_cache.font_file;
wchar_t letter,
Point &cursor,
const FontFile &font,
Glyphs &cache,
const FontProp &font_prop,
fontinfo_opt &font_info_cache
) {
if (letter == '\n') {
cursor.x() = 0;
// 2d shape has opposit direction of y
@@ -1313,12 +1329,16 @@ void align_shape(ExPolygonsWithIds &shapes, const std::wstring &text, const Font
ExPolygonsWithIds Emboss::text2vshapes(FontFileWithCache &font_with_cache, const std::wstring& text, const FontProp &font_prop, const std::function<bool()>& was_canceled){
assert(font_with_cache.has_value());
if (!font_with_cache.has_value())
return {};
const FontFile &font = *font_with_cache.font_file;
unsigned int font_index = font_prop.collection_number.value_or(0);
if (!is_valid(font, font_index))
return {};
unsigned counter = 0;
std::shared_ptr<Glyphs> cache = font_with_cache.cache; // copy pointer
unsigned counter = CANCEL_CHECK-1; // it is needed to validate using of cache
Point cursor(0, 0);
fontinfo_opt font_info_cache;
@@ -1331,14 +1351,13 @@ ExPolygonsWithIds Emboss::text2vshapes(FontFileWithCache &font_with_cache, const
return {};
}
unsigned id = static_cast<unsigned>(letter);
result.push_back({id, letter2shapes(letter, cursor, font_with_cache, font_prop, font_info_cache)});
result.push_back({id, letter2shapes(letter, cursor, font, *cache, font_prop, font_info_cache)});
}
align_shape(result, text, font_prop, font);
return result;
}
#include <boost/range/adaptor/reversed.hpp>
unsigned Emboss::get_count_lines(const std::wstring& ws)
{
if (ws.empty())
@@ -1878,12 +1897,27 @@ double Emboss::calculate_angle(int32_t distance, PolygonPoint polygon_point, con
return std::atan2(norm_d.y(), norm_d.x());
}
std::vector<double> Emboss::calculate_angles(int32_t distance, const PolygonPoints& polygon_points, const Polygon &polygon)
std::vector<double> Emboss::calculate_angles(const BoundingBoxes &glyph_sizes, const PolygonPoints& polygon_points, const Polygon &polygon)
{
const int32_t default_distance = static_cast<int32_t>(std::round(scale_(5.)));
const int32_t min_distance = static_cast<int32_t>(std::round(scale_(.1)));
std::vector<double> result;
result.reserve(polygon_points.size());
for(const PolygonPoint& pp: polygon_points)
result.emplace_back(calculate_angle(distance, pp, polygon));
assert(glyph_sizes.size() == polygon_points.size());
if (glyph_sizes.size() != polygon_points.size()) {
// only backup solution should not be used
for (const PolygonPoint &pp : polygon_points)
result.emplace_back(calculate_angle(default_distance, pp, polygon));
return result;
}
for (size_t i = 0; i < polygon_points.size(); i++) {
int32_t distance = glyph_sizes[i].size().x() / 2;
if (distance < min_distance) // too small could lead to false angle
distance = default_distance;
result.emplace_back(calculate_angle(distance, polygon_points[i], polygon));
}
return result;
}
@@ -2025,6 +2059,7 @@ double Emboss::get_align_y_offset_in_mm(FontProp::VerticalAlign align, unsigned
#ifdef REMOVE_SPIKES
#include <Geometry.hpp>
void remove_spikes(Polygon &polygon, const SpikeDesc &spike_desc)
{
enum class Type {

View File

@@ -1,16 +1,29 @@
#ifndef slic3r_Emboss_hpp_
#define slic3r_Emboss_hpp_
#include <admesh/stl.h> // indexed_triangle_set
#include <assert.h>
#include <stddef.h>
#include <stdint.h>
#include <vector>
#include <set>
#include <optional>
#include <memory>
#include <admesh/stl.h> // indexed_triangle_set
#include <Eigen/Geometry>
#include <functional>
#include <map>
#include <string>
#include <utility>
#include <cassert>
#include <cinttypes>
#include <cstddef>
#include "Polygon.hpp"
#include "ExPolygon.hpp"
#include "EmbossShape.hpp" // ExPolygonsWithIds
#include "BoundingBox.hpp"
#include "TextConfiguration.hpp"
#include "libslic3r/Point.hpp"
namespace Slic3r {
@@ -20,8 +33,6 @@ namespace Slic3r {
/// </summary>
namespace Emboss
{
// every glyph's shape point is divided by SHAPE_SCALE - increase precission of fixed point value
// stored in fonts (to be able represents curve by sequence of lines)
static const float UNION_DELTA = 50.0f; // [approx in nano meters depends on volume scale]
static const unsigned UNION_MAX_ITERATIN = 10; // [count]
@@ -167,8 +178,9 @@ namespace Emboss
/// Fix duplicit points and self intersections in polygons.
/// Also try to reduce amount of points and remove useless polygon parts
/// </summary>
/// <param name="precision">Define wanted precision of shape after heal</param>
/// <returns>Healed shapes</returns>
/// <param name="is_non_zero">Fill type ClipperLib::pftNonZero for overlapping otherwise </param>
/// <param name="max_iteration">Look at heal_expolygon()::max_iteration</param>
/// <returns>Healed shapes with flag is fully healed</returns>
HealedExPolygons heal_polygons(const Polygons &shape, bool is_non_zero = true, unsigned max_iteration = 10);
/// <summary>
@@ -199,8 +211,8 @@ namespace Emboss
/// <summary>
/// Use data from font property to modify transformation
/// </summary>
/// <param name="font_prop">Z-move as surface distance(FontProp::distance)
/// Z-rotation as angle to Y axis(FontProp::angle)</param>
/// <param name="angle">Z-rotation as angle to Y axis</param>
/// <param name="distance">Z-move as surface distance</param>
/// <param name="transformation">In / Out transformation to modify by property</param>
void apply_transformation(const std::optional<float> &angle, const std::optional<float> &distance, Transform3d &transformation);
@@ -244,7 +256,7 @@ namespace Emboss
/// </summary>
/// <param name="font">Infos for collections</param>
/// <param name="prop">Collection index + Additional line gap</param>
/// <returns>Line height with spacing in ExPolygon size</returns>
/// <returns>Line height with spacing in scaled font points (same as ExPolygons)</returns>
int get_line_height(const FontFile &font, const FontProp &prop);
/// <summary>
@@ -279,8 +291,6 @@ namespace Emboss
class IProjection : public IProject3d
{
public:
virtual ~IProjection() = default;
/// <summary>
/// convert 2d point to 3d points
/// </summary>
@@ -458,9 +468,16 @@ namespace Emboss
/// <param name="polygon">Polygon know neighbor of point</param>
/// <returns>angle(atan2) of normal in polygon point</returns>
double calculate_angle(int32_t distance, PolygonPoint polygon_point, const Polygon &polygon);
std::vector<double> calculate_angles(int32_t distance, const PolygonPoints& polygon_points, const Polygon &polygon);
std::vector<double> calculate_angles(
const BoundingBoxes &glyph_sizes,
const PolygonPoints &polygon_points,
const Polygon &polygon
);
} // namespace Emboss
///////////////////////
// Move to ExPolygonsWithIds Utils
void translate(ExPolygonsWithIds &e, const Point &p);
BoundingBox get_extents(const ExPolygonsWithIds &e);
void center(ExPolygonsWithIds &e);

Some files were not shown because too many files have changed in this diff Show More