Merge remote-tracking branch 'remotes/origin/master' into vb_treesupports

This commit is contained in:
Vojtech Bubnik 2022-11-18 13:26:48 +01:00
commit a98467f661
39 changed files with 1796 additions and 322 deletions

View file

@ -1,9 +1,18 @@
#ifndef slic3r_BridgeDetector_hpp_
#define slic3r_BridgeDetector_hpp_
#include "ClipperUtils.hpp"
#include "Line.hpp"
#include "Point.hpp"
#include "Polygon.hpp"
#include "Polyline.hpp"
#include "PrincipalComponents2D.hpp"
#include "libslic3r.h"
#include "ExPolygon.hpp"
#include <cmath>
#include <string>
#include <unordered_map>
#include <vector>
namespace Slic3r {
@ -64,6 +73,60 @@ private:
ExPolygons _anchor_regions;
};
//return ideal bridge direction and unsupported bridge endpoints distance.
inline std::tuple<Vec2d, double> detect_bridging_direction(const Polygons &to_cover, const Polygons &anchors_area)
{
Polygons overhang_area = diff(to_cover, anchors_area);
Polylines floating_polylines = diff_pl(to_polylines(overhang_area), expand(anchors_area, float(SCALED_EPSILON)));
if (floating_polylines.empty()) {
// consider this area anchored from all sides, pick bridging direction that will likely yield shortest bridges
//use 3mm resolution (should be quite fast, and rough estimation should not cause any problems here)
auto [pc1, pc2] = compute_principal_components(overhang_area, 3.0);
if (pc2 == Vec2d::Zero()) { // overhang may be smaller than resolution. In this case, any direction is ok
return {Vec2d{1.0,0.0}, 0.0};
} else {
return {pc2.normalized(), 0.0};
}
}
// Overhang is not fully surrounded by anchors, in that case, find such direction that will minimize the number of bridge ends/180turns in the air
Lines floating_edges = to_lines(floating_polylines);
std::unordered_map<double, Vec2d> directions{};
for (const Line &l : floating_edges) {
Vec2d normal = l.normal().cast<double>().normalized();
double quantized_angle = std::ceil(std::atan2(normal.y(),normal.x()) * 1000.0);
directions.emplace(quantized_angle, normal);
}
std::vector<std::pair<Vec2d, double>> direction_costs{};
// it is acutally cost of a perpendicular bridge direction - we find the minimal cost and then return the perpendicular dir
for (const auto& d : directions) {
direction_costs.emplace_back(d.second, 0.0);
}
for (const Line &l : floating_edges) {
Vec2d line = (l.b - l.a).cast<double>();
for (auto &dir_cost : direction_costs) {
// the dot product already contains the length of the line. dir_cost.first is normalized.
dir_cost.second += std::abs(line.dot(dir_cost.first));
}
}
Vec2d result_dir = Vec2d::Ones();
double min_cost = std::numeric_limits<double>::max();
for (const auto &cost : direction_costs) {
if (cost.second < min_cost) {
// now flip the orientation back and return the direction of the bridge extrusions
result_dir = Vec2d{cost.first.y(), -cost.first.x()};
min_cost = cost.second;
}
}
return {result_dir, min_cost};
};
}
#endif

View file

@ -160,6 +160,8 @@ set(SLIC3R_SOURCES
Geometry/VoronoiOffset.hpp
Geometry/VoronoiVisualUtils.hpp
Int128.hpp
JumpPointSearch.cpp
JumpPointSearch.hpp
KDTreeIndirect.hpp
Layer.cpp
Layer.hpp
@ -214,6 +216,8 @@ set(SLIC3R_SOURCES
Preset.hpp
PresetBundle.cpp
PresetBundle.hpp
PrincipalComponents2D.hpp
PrincipalComponents2D.cpp
AppConfig.cpp
AppConfig.hpp
Print.cpp

View file

@ -7,6 +7,9 @@
#include "GCode/PrintExtents.hpp"
#include "GCode/Thumbnails.hpp"
#include "GCode/WipeTower.hpp"
#include "Point.hpp"
#include "Polygon.hpp"
#include "PrintConfig.hpp"
#include "ShortestPath.hpp"
#include "Print.hpp"
#include "Thread.hpp"
@ -2157,6 +2160,14 @@ LayerResult GCode::process_layer(
Skirt::make_skirt_loops_per_extruder_1st_layer(print, layer_tools, m_skirt_done) :
Skirt::make_skirt_loops_per_extruder_other_layers(print, layer_tools, m_skirt_done);
if (this->config().avoid_curled_filament_during_travels) {
m_avoid_curled_filaments.clear();
for (const ObjectLayerToPrint &layer_to_print : layers) {
m_avoid_curled_filaments.add_obstacles(layer_to_print.object_layer, Point(scaled(this->origin())));
m_avoid_curled_filaments.add_obstacles(layer_to_print.support_layer, Point(scaled(this->origin())));
}
}
// Extrude the skirt, brim, support, perimeters, infill ordered by the extruders.
for (unsigned int extruder_id : layer_tools.extruders)
{
@ -2988,6 +2999,12 @@ std::string GCode::travel_to(const Point &point, ExtrusionRole role, std::string
this->origin in order to get G-code coordinates. */
Polyline travel { this->last_pos(), point };
if (this->config().avoid_curled_filament_during_travels) {
Point scaled_origin = Point(scaled(this->origin()));
travel = m_avoid_curled_filaments.find_path(this->last_pos() + scaled_origin, point + scaled_origin);
travel.translate(-scaled_origin);
}
// check whether a straight travel move would need retraction
bool needs_retraction = this->needs_retraction(travel, role);
// check whether wipe could be disabled without causing visible stringing

View file

@ -1,6 +1,7 @@
#ifndef slic3r_GCode_hpp_
#define slic3r_GCode_hpp_
#include "JumpPointSearch.hpp"
#include "libslic3r.h"
#include "ExPolygon.hpp"
#include "GCodeWriter.hpp"
@ -347,6 +348,7 @@ private:
OozePrevention m_ooze_prevention;
Wipe m_wipe;
AvoidCrossingPerimeters m_avoid_crossing_perimeters;
JPSPathFinder m_avoid_curled_filaments;
bool m_enable_loop_clipping;
// If enabled, the G-code generator will put following comments at the ends
// of the G-code lines: _EXTRUDE_SET_SPEED, _WIPE, _BRIDGE_FAN_START, _BRIDGE_FAN_END

View file

@ -116,6 +116,18 @@ Polygon convex_hull(const ExPolygons &expolygons)
return convex_hull(pp);
}
Polygon convex_hulll(const Polylines &polylines)
{
Points pp;
size_t sz = 0;
for (const auto &polyline : polylines)
sz += polyline.points.size();
pp.reserve(sz);
for (const auto &polyline : polylines)
pp.insert(pp.end(), polyline.points.begin(), polyline.points.end());
return convex_hull(pp);
}
namespace rotcalip {
using int256_t = boost::multiprecision::int256_t;

View file

@ -16,6 +16,7 @@ Pointf3s convex_hull(Pointf3s points);
Polygon convex_hull(Points points);
Polygon convex_hull(const Polygons &polygons);
Polygon convex_hull(const ExPolygons &expolygons);
Polygon convex_hulll(const Polylines &polylines);
// Returns true if the intersection of the two convex polygons A and B
// is not an empty set.

View file

@ -0,0 +1,364 @@
#include "JumpPointSearch.hpp"
#include "BoundingBox.hpp"
#include "Point.hpp"
#include "libslic3r/AStar.hpp"
#include "libslic3r/KDTreeIndirect.hpp"
#include "libslic3r/Polygon.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/libslic3r.h"
#include <algorithm>
#include <cmath>
#include <cstddef>
#include <cstdint>
#include <cstdlib>
#include <iterator>
#include <limits>
#include <optional>
#include <string>
#include <unordered_map>
#include <vector>
//#define DEBUG_FILES
#ifdef DEBUG_FILES
#include "libslic3r/SVG.hpp"
#endif
namespace Slic3r {
template<typename PointFn> void dda(coord_t x0, coord_t y0, coord_t x1, coord_t y1, const PointFn &fn)
{
coord_t dx = abs(x1 - x0);
coord_t dy = abs(y1 - y0);
coord_t x = x0;
coord_t y = y0;
coord_t n = 1 + dx + dy;
coord_t x_inc = (x1 > x0) ? 1 : -1;
coord_t y_inc = (y1 > y0) ? 1 : -1;
coord_t error = dx - dy;
dx *= 2;
dy *= 2;
for (; n > 0; --n) {
fn(x, y);
if (error > 0) {
x += x_inc;
error -= dy;
} else {
y += y_inc;
error += dx;
}
}
}
// will draw the line twice, second time with and offset of 1 in the direction of normal
// may call the fn on the same coordiantes multiple times!
template<typename PointFn> void double_dda_with_offset(coord_t x0, coord_t y0, coord_t x1, coord_t y1, const PointFn &fn)
{
Vec2d normal = Point{y1 - y0, x1 - x0}.cast<double>().normalized();
normal.x() = ceil(normal.x());
normal.y() = ceil(normal.y());
Point start_offset = Point(x0,y0) + (normal).cast<coord_t>();
Point end_offset = Point(x1,y1) + (normal).cast<coord_t>();
dda(x0, y0, x1, y1, fn);
dda(start_offset.x(), start_offset.y(), end_offset.x(), end_offset.y(), fn);
}
template<typename CellPositionType, typename CellQueryFn> class JPSTracer
{
public:
// Use incoming_dir [0,0] for starting points, so that all directions are checked from that point
struct Node
{
CellPositionType position;
CellPositionType incoming_dir;
};
JPSTracer(CellPositionType target, CellQueryFn is_passable) : target(target), is_passable(is_passable) {}
private:
CellPositionType target;
CellQueryFn is_passable; // should return boolean whether the cell is passable or not
CellPositionType find_jump_point(CellPositionType start, CellPositionType forward_dir) const
{
CellPositionType next = start + forward_dir;
while (next != target && is_passable(next) && !(is_jump_point(next, forward_dir))) { next = next + forward_dir; }
if (is_passable(next)) {
return next;
} else {
return start;
}
}
bool is_jump_point(CellPositionType pos, CellPositionType forward_dir) const
{
if (abs(forward_dir.x()) + abs(forward_dir.y()) == 2) {
// diagonal
CellPositionType horizontal_check_dir = CellPositionType{forward_dir.x(), 0};
CellPositionType vertical_check_dir = CellPositionType{0, forward_dir.y()};
if (!is_passable(pos - horizontal_check_dir) && is_passable(pos + forward_dir - 2 * horizontal_check_dir)) { return true; }
if (!is_passable(pos - vertical_check_dir) && is_passable(pos + forward_dir - 2 * vertical_check_dir)) { return true; }
if (find_jump_point(pos, horizontal_check_dir) != pos) { return true; }
if (find_jump_point(pos, vertical_check_dir) != pos) { return true; }
return false;
} else { // horizontal or vertical
CellPositionType side_dir = CellPositionType(forward_dir.y(), forward_dir.x());
if (!is_passable(pos + side_dir) && is_passable(pos + forward_dir + side_dir)) { return true; }
if (!is_passable(pos - side_dir) && is_passable(pos + forward_dir - side_dir)) { return true; }
return false;
}
}
public:
template<class Fn> void foreach_reachable(const Node &from, Fn &&fn) const
{
const CellPositionType &pos = from.position;
const CellPositionType &forward_dir = from.incoming_dir;
std::vector<CellPositionType> dirs_to_check{};
if (abs(forward_dir.x()) + abs(forward_dir.y()) == 0) { // special case for starting point
dirs_to_check = all_directions;
} else if (abs(forward_dir.x()) + abs(forward_dir.y()) == 2) {
// diagonal
CellPositionType horizontal_check_dir = CellPositionType{forward_dir.x(), 0};
CellPositionType vertical_check_dir = CellPositionType{0, forward_dir.y()};
if (!is_passable(pos - horizontal_check_dir) && is_passable(pos + forward_dir - 2 * horizontal_check_dir)) {
dirs_to_check.push_back(forward_dir - 2 * horizontal_check_dir);
}
if (!is_passable(pos - vertical_check_dir) && is_passable(pos + forward_dir - 2 * vertical_check_dir)) {
dirs_to_check.push_back(forward_dir - 2 * vertical_check_dir);
}
dirs_to_check.push_back(horizontal_check_dir);
dirs_to_check.push_back(vertical_check_dir);
dirs_to_check.push_back(forward_dir);
} else { // horizontal or vertical
CellPositionType side_dir = CellPositionType(forward_dir.y(), forward_dir.x());
if (!is_passable(pos + side_dir) && is_passable(pos + forward_dir + side_dir)) {
dirs_to_check.push_back(forward_dir + side_dir);
}
if (!is_passable(pos - side_dir) && is_passable(pos + forward_dir - side_dir)) {
dirs_to_check.push_back(forward_dir - side_dir);
}
dirs_to_check.push_back(forward_dir);
}
for (const CellPositionType &dir : dirs_to_check) {
CellPositionType jp = find_jump_point(pos, dir);
if (jp != pos) fn(Node{jp, dir});
}
}
float distance(Node a, Node b) const { return (a.position - b.position).template cast<double>().norm(); }
float goal_heuristic(Node n) const { return n.position == target ? -1.f : (target - n.position).template cast<double>().norm(); }
size_t unique_id(Node n) const { return (static_cast<size_t>(uint16_t(n.position.x())) << 16) + static_cast<size_t>(uint16_t(n.position.y())); }
const std::vector<CellPositionType> all_directions{{1, 0}, {1, 1}, {0, 1}, {-1, 1}, {-1, 0}, {-1, -1}, {0, -1}, {1, -1}};
};
void JPSPathFinder::clear()
{
inpassable.clear();
obstacle_max = Pixel(std::numeric_limits<coord_t>::min(), std::numeric_limits<coord_t>::min());
obstacle_min = Pixel(std::numeric_limits<coord_t>::max(), std::numeric_limits<coord_t>::max());
}
void JPSPathFinder::add_obstacles(const Lines &obstacles)
{
auto store_obstacle = [&](coord_t x, coord_t y) {
obstacle_max.x() = std::max(obstacle_max.x(), x);
obstacle_max.y() = std::max(obstacle_max.y(), y);
obstacle_min.x() = std::min(obstacle_min.x(), x);
obstacle_min.y() = std::min(obstacle_min.y(), y);
inpassable.insert(Pixel{x, y});
};
for (const Line &l : obstacles) {
Pixel start = pixelize(l.a);
Pixel end = pixelize(l.b);
double_dda_with_offset(start.x(), start.y(), end.x(), end.y(), store_obstacle);
}
}
void JPSPathFinder::add_obstacles(const Layer *layer, const Point &global_origin)
{
if (layer != nullptr) { this->print_z = layer->print_z; }
auto store_obstacle = [&](coord_t x, coord_t y) {
obstacle_max.x() = std::max(obstacle_max.x(), x);
obstacle_max.y() = std::max(obstacle_max.y(), y);
obstacle_min.x() = std::min(obstacle_min.x(), x);
obstacle_min.y() = std::min(obstacle_min.y(), y);
inpassable.insert(Pixel{x, y});
};
Lines obstacles;
for (size_t step = 0; step < 3; step++) {
if (layer != nullptr) {
obstacles.insert(obstacles.end(), layer->malformed_lines.begin(), layer->malformed_lines.end());
layer = layer->lower_layer;
} else {
break;
}
}
for (const Line &l : obstacles) {
Pixel start = pixelize(l.a + global_origin);
Pixel end = pixelize(l.b + global_origin);
double_dda_with_offset(start.x(), start.y(), end.x(), end.y(), store_obstacle);
}
#ifdef DEBUG_FILES
::Slic3r::SVG svg(debug_out_path(("obstacles_jps" + std::to_string(print_z) + "_" + std::to_string(rand() % 1000)).c_str()).c_str(),
get_extents(obstacles));
svg.draw(obstacles);
svg.Close();
#endif
}
Polyline JPSPathFinder::find_path(const Point &p0, const Point &p1)
{
Pixel start = pixelize(p0);
Pixel end = pixelize(p1);
if (inpassable.empty() || (start - end).cast<float>().norm() < 3.0) { return Polyline{p0, p1}; }
BoundingBox search_box({start,end,obstacle_max,obstacle_min});
search_box.max += Pixel(1,1);
search_box.min -= Pixel(1,1);
BoundingBox bounding_square(Points{start,end});
bounding_square.max += Pixel(5,5);
bounding_square.min -= Pixel(5,5);
coord_t bounding_square_size = 2*std::max(bounding_square.size().x(),bounding_square.size().y());
bounding_square.max.x() += (bounding_square_size - bounding_square.size().x()) / 2;
bounding_square.min.x() -= (bounding_square_size - bounding_square.size().x()) / 2;
bounding_square.max.y() += (bounding_square_size - bounding_square.size().y()) / 2;
bounding_square.min.y() -= (bounding_square_size - bounding_square.size().y()) / 2;
// Intersection - limit the search box to a square area around the start and end, to fasten the path searching
search_box.max = search_box.max.cwiseMin(bounding_square.max);
search_box.min = search_box.min.cwiseMax(bounding_square.min);
auto cell_query = [&](Pixel pixel) {
return search_box.contains(pixel) && (pixel == start || pixel == end || inpassable.find(pixel) == inpassable.end());
};
JPSTracer<Pixel, decltype(cell_query)> tracer(end, cell_query);
using QNode = astar::QNode<JPSTracer<Pixel, decltype(cell_query)>>;
std::unordered_map<size_t, QNode> astar_cache{};
std::vector<Pixel> out_path;
std::vector<decltype(tracer)::Node> out_nodes;
if (!astar::search_route(tracer, {start, {0, 0}}, std::back_inserter(out_nodes), astar_cache)) {
// path not found - just reconstruct the best path from astar cache.
// Note that astar_cache is NOT empty - at least the starting point should always be there
auto coordiante_func = [&astar_cache](size_t idx, size_t dim) { return float(astar_cache[idx].node.position[dim]); };
std::vector<size_t> keys;
keys.reserve(astar_cache.size());
for (const auto &pair : astar_cache) { keys.push_back(pair.first); }
KDTreeIndirect<2, float, decltype(coordiante_func)> kd_tree(coordiante_func, keys);
size_t closest_qnode = find_closest_point(kd_tree, end.cast<float>());
out_path.push_back(end);
while (closest_qnode != astar::Unassigned) {
out_path.push_back(astar_cache[closest_qnode].node.position);
closest_qnode = astar_cache[closest_qnode].parent;
}
} else {
for (const auto& node : out_nodes) {
out_path.push_back(node.position);
}
out_path.push_back(start);
}
#ifdef DEBUG_FILES
auto scaled_points = [](const Points &ps) {
Points r;
for (const Point &p : ps) { r.push_back(Point::new_scale(p.x(), p.y())); }
return r;
};
auto scaled_point = [](const Point &p) { return Point::new_scale(p.x(), p.y()); };
::Slic3r::SVG svg(debug_out_path(("path_jps" + std::to_string(print_z) + "_" + std::to_string(rand() % 1000)).c_str()).c_str(),
BoundingBox(scaled_point(search_box.min), scaled_point(search_box.max)));
for (const auto &p : inpassable) { svg.draw(scaled_point(p), "black", scale_(0.4)); }
for (const auto &qn : astar_cache) { svg.draw(scaled_point(qn.second.node.position), "blue", scale_(0.3)); }
svg.draw(Polyline(scaled_points(out_path)), "yellow", scale_(0.25));
svg.draw(scaled_point(end), "purple", scale_(0.4));
svg.draw(scaled_point(start), "green", scale_(0.4));
#endif
std::vector<Pixel> tmp_path;
tmp_path.reserve(out_path.size());
// Some path found, reverse and remove points that do not change direction
std::reverse(out_path.begin(), out_path.end());
{
tmp_path.push_back(out_path.front()); // first point
for (size_t i = 1; i < out_path.size() - 1; i++) {
if ((out_path[i] - out_path[i - 1]).cast<float>().normalized() != (out_path[i + 1] - out_path[i]).cast<float>().normalized()) {
tmp_path.push_back(out_path[i]);
}
}
tmp_path.push_back(out_path.back()); // last_point
out_path = tmp_path;
}
#ifdef DEBUG_FILES
svg.draw(Polyline(scaled_points(out_path)), "orange", scale_(0.20));
#endif
tmp_path.clear();
// remove redundant jump points - there are points that change direction but are not needed - this inefficiency arises from the
// usage of grid search The removal alg tries to find the longest Px Px+k path without obstacles. If Px Px+k+1 is blocked, it will
// insert the Px+k point to result and continue search from Px+k
{
tmp_path.push_back(out_path.front()); // first point
size_t index_of_last_stored_point = 0;
for (size_t i = 1; i < out_path.size(); i++) {
if (i - index_of_last_stored_point < 2) continue;
bool passable = true;
auto store_obstacle = [&](coord_t x, coord_t y) {
if (Pixel(x, y) != start && Pixel(x, y) != end && inpassable.find(Pixel(x, y)) != inpassable.end()) { passable = false; };
};
dda(tmp_path.back().x(), tmp_path.back().y(), out_path[i].x(), out_path[i].y(), store_obstacle);
if (!passable) {
tmp_path.push_back(out_path[i - 1]);
index_of_last_stored_point = i - 1;
}
}
tmp_path.push_back(out_path.back()); // last_point
out_path = tmp_path;
}
#ifdef DEBUG_FILES
svg.draw(Polyline(scaled_points(out_path)), "red", scale_(0.15));
svg.Close();
#endif
// before returing the path, transform it from pixels back to points.
// Also replace the first and last pixel by input points so that result path patches input params exactly.
for (Pixel &p : out_path) { p = unpixelize(p); }
out_path.front() = p0;
out_path.back() = p1;
return Polyline(out_path);
}
} // namespace Slic3r

View file

@ -0,0 +1,36 @@
#ifndef SRC_LIBSLIC3R_JUMPPOINTSEARCH_HPP_
#define SRC_LIBSLIC3R_JUMPPOINTSEARCH_HPP_
#include "BoundingBox.hpp"
#include "libslic3r/Layer.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/Polyline.hpp"
#include "libslic3r/libslic3r.h"
#include <unordered_map>
#include <unordered_set>
namespace Slic3r {
class JPSPathFinder
{
using Pixel = Point;
std::unordered_set<Pixel, PointHash> inpassable;
coordf_t print_z;
Pixel obstacle_min;
Pixel obstacle_max;
const coord_t resolution = scaled(1.5);
Pixel pixelize(const Point &p) { return p / resolution; }
Point unpixelize(const Pixel &p) { return p * resolution; }
public:
JPSPathFinder() { clear(); };
void clear();
void add_obstacles(const Lines &obstacles);
void add_obstacles(const Layer* layer, const Point& global_origin);
Polyline find_path(const Point &start, const Point &end);
};
} // namespace Slic3r
#endif /* SRC_LIBSLIC3R_JUMPPOINTSEARCH_HPP_ */

View file

@ -316,6 +316,9 @@ public:
coordf_t height; // layer height in unscaled coordinates
coordf_t bottom_z() const { return this->print_z - this->height; }
//Lines estimated to be seriously malformed, info from the IssueSearch algorithm. These lines should probably be avoided during fast travels.
Lines malformed_lines;
// Collection of expolygons generated by slicing the possibly multiple meshes of the source geometry
// (with possibly differing extruder ID and slicing parameters) and merged.
// For the first layer, if the Elephant foot compensation is applied, this lslice is uncompensated, therefore

View file

@ -1,3 +1,4 @@
#include "ExPolygon.hpp"
#include "Layer.hpp"
#include "BridgeDetector.hpp"
#include "ClipperUtils.hpp"
@ -314,6 +315,27 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
// would get merged into a single one while they need different directions
// also, supply the original expolygon instead of the grown one, because in case
// of very thin (but still working) anchors, the grown expolygon would go beyond them
double custom_angle = Geometry::deg2rad(this->region().config().bridge_angle.value);
if (custom_angle > 0.0) {
bridges[idx_last].bridge_angle = custom_angle;
} else {
auto [bridging_dir, unsupported_dist] = detect_bridging_direction(to_polygons(initial), to_polygons(lower_layer->lslices));
bridges[idx_last].bridge_angle = PI + std::atan2(bridging_dir.y(), bridging_dir.x());
// #if 1
// coordf_t stroke_width = scale_(0.06);
// BoundingBox bbox = get_extents(initial);
// bbox.offset(scale_(1.));
// ::Slic3r::SVG
// svg(debug_out_path(("bridge"+std::to_string(bridges[idx_last].bridge_angle)+"_"+std::to_string(this->layer()->bottom_z())).c_str()),
// bbox);
// svg.draw(initial, "cyan");
// svg.draw(to_lines(lower_layer->lslices), "green", stroke_width);
// #endif
}
/*
BridgeDetector bd(initial, lower_layer->lslices, this->bridging_flow(frInfill).scaled_width());
#ifdef SLIC3R_DEBUG
printf("Processing bridge at layer %zu:\n", this->layer()->id());
@ -330,6 +352,7 @@ void LayerRegion::process_external_surfaces(const Layer *lower_layer, const Poly
// using a bridging flow, therefore it makes sense to respect the custom bridging direction.
bridges[idx_last].bridge_angle = custom_angle;
}
*/
// without safety offset, artifacts are generated (GH #2494)
surfaces_append(bottom, union_safety_offset_ex(grown), bridges[idx_last]);
}

View file

@ -4,6 +4,7 @@
#include "libslic3r/Geometry/Circle.hpp"
#include "libslic3r/SurfaceMesh.hpp"
#include <numeric>
#include <numeric>
@ -12,7 +13,6 @@ namespace Measure {
constexpr double feature_hover_limit = 0.5; // how close to a feature the mouse must be to highlight it
constexpr double edge_endpoint_limit = 0.5; // how close to an edge endpoint the mouse ...
static std::pair<Vec3d, double> get_center_and_radius(const std::vector<Vec3d>& border, int start_idx, int end_idx, const Transform3d& trafo)
{
@ -341,32 +341,9 @@ void MeasuringImpl::extract_features()
}
circles_lengths.clear(); // no longer needed, make it obvious
// Some of the "circles" may actually be polygons (5-8 vertices). We want them
// detected as edges, but also to remember the center and save it into those edges.
// We will add all such edges manually and delete the detected circles, leaving it
// in circles_idxs so they are not picked again.
assert(circles.size() == circles_idxs.size());
for (int i=circles.size()-1; i>=0; --i) {
if (circles_idxs[i].first == 0 && circles_idxs[i].second == border.size()-1) {
int N = circles_idxs[i].second - circles_idxs[i].first;
if (N <= 8) {
if (N >= 5) { // polygon = 5,6,7,8 vertices
const Vec3d center = std::get<0>(circles[i].get_circle());
for (int j=(int)circles_idxs[i].first + 1; j<=(int)circles_idxs[i].second; ++j)
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge,
border[j - 1], border[j], std::make_optional(center)));
} else {
// This will be handled just like a regular edge (squares, triangles).
circles_idxs.erase(circles_idxs.begin() + i);
}
circles.erase(circles.begin() + i);
}
}
}
// Anything under 5 vertices shall not be considered a circle.
assert(circles_idxs.size() == circles.size());
for (int i=0; i<int(circles_idxs.size()); ++i) {
for (int i=int(circles_idxs.size())-1; i>=0; --i) {
const auto& [start, end] = circles_idxs[i];
int N = start >= 0
? end - start + (start == 0 && end == border.size()-1 ? 0 : 1) // last point is the same as first
@ -374,7 +351,15 @@ void MeasuringImpl::extract_features()
if (N < 5) {
circles.erase(circles.begin() + i);
circles_idxs.erase(circles_idxs.begin() + i);
--i;
} else if (N <= 8 && start == 0 && end == border.size()-1) {
// This is a regular 5-8 polygon. Add the edges as edges with a special
// point and remove the circle. Leave the indices in circles_idxs, so
// the edges are not picked up again later.
const Vec3d center = std::get<0>(circles[i].get_circle());
for (int j=1; j<=end; ++j)
edges.emplace_back(SurfaceFeature(SurfaceFeatureType::Edge,
border[j - 1], border[j], std::make_optional(center)));
circles.erase(circles.begin() + i);
}
}
@ -469,6 +454,8 @@ std::optional<SurfaceFeature> MeasuringImpl::get_feature(size_t face_idx, const
MeasurementResult res;
SurfaceFeature point_sf(point);
assert(plane.surface_features.empty() || plane.surface_features.back().get_type() == SurfaceFeatureType::Plane);
for (size_t i=0; i<plane.surface_features.size() - 1; ++i) {
// The -1 is there to prevent measuring distance to the plane itself,
// which is needless and relatively expensive.
@ -486,9 +473,12 @@ std::optional<SurfaceFeature> MeasuringImpl::get_feature(size_t face_idx, const
const SurfaceFeature& f = plane.surface_features[closest_feature_idx];
if (f.get_type() == SurfaceFeatureType::Edge) {
// If this is an edge, check if we are not close to the endpoint. If so,
// we will include the endpoint as well.
constexpr double limit_sq = edge_endpoint_limit * edge_endpoint_limit;
// we will include the endpoint as well. Close = 10% of the lenghth of
// the edge, clamped between 0.025 and 0.5 mm.
const auto& [sp, ep] = f.get_edge();
double len_sq = (ep-sp).squaredNorm();
double limit_sq = std::max(0.025*0.025, std::min(0.5*0.5, 0.1 * 0.1 * len_sq));
if ((point-sp).squaredNorm() < limit_sq)
return std::make_optional(SurfaceFeature(sp));
if ((point-ep).squaredNorm() < limit_sq)

View file

@ -1,24 +1,56 @@
#include "PerimeterGenerator.hpp"
#include "AABBTreeIndirect.hpp"
#include "AABBTreeLines.hpp"
#include "BoundingBox.hpp"
#include "BridgeDetector.hpp"
#include "ClipperUtils.hpp"
#include "ExPolygon.hpp"
#include "ExtrusionEntity.hpp"
#include "ExtrusionEntityCollection.hpp"
#include "Geometry/MedialAxis.hpp"
#include "KDTreeIndirect.hpp"
#include "MultiPoint.hpp"
#include "Point.hpp"
#include "Polygon.hpp"
#include "Polyline.hpp"
#include "PrintConfig.hpp"
#include "ShortestPath.hpp"
#include "Surface.hpp"
#include "Geometry/ConvexHull.hpp"
#include "SurfaceCollection.hpp"
#include "clipper/clipper_z.hpp"
#include "Arachne/WallToolPaths.hpp"
#include "Arachne/utils/ExtrusionLine.hpp"
#include "Arachne/utils/ExtrusionJunction.hpp"
#include "libslic3r.h"
#include <algorithm>
#include <cmath>
#include <cassert>
#include <cstdlib>
#include <functional>
#include <iterator>
#include <limits>
#include <math.h>
#include <ostream>
#include <stack>
#include <string>
#include <unordered_map>
#include <unordered_set>
#include <utility>
#include <vector>
//#define ARACHNE_DEBUG
// #define ARACHNE_DEBUG
#ifdef ARACHNE_DEBUG
#include "SVG.hpp"
#include "Utils.hpp"
#endif
#include "SVG.hpp"
namespace Slic3r {
ExtrusionMultiPath PerimeterGenerator::thick_polyline_to_multi_path(const ThickPolyline &thick_polyline, ExtrusionRole role, const Flow &flow, const float tolerance, const float merge_tolerance)
@ -610,6 +642,375 @@ static void export_perimeters_to_svg(const std::string &path, const Polygons &co
}
#endif
// find out if paths touch - at least one point of one path is within limit distance of second path
bool paths_touch(const ExtrusionPath &path_one, const ExtrusionPath &path_two, double limit_distance)
{
AABBTreeLines::LinesDistancer<Line> lines_one{path_one.as_polyline().lines()};
AABBTreeLines::LinesDistancer<Line> lines_two{path_two.as_polyline().lines()};
for (size_t pt_idx = 0; pt_idx < path_one.polyline.size(); pt_idx++) {
if (std::abs(lines_two.signed_distance_from_lines(path_one.polyline.points[pt_idx])) < limit_distance) { return true; }
}
for (size_t pt_idx = 0; pt_idx < path_two.polyline.size(); pt_idx++) {
if (std::abs(lines_one.signed_distance_from_lines(path_two.polyline.points[pt_idx])) < limit_distance) { return true; }
}
return false;
}
ExtrusionPaths reconnect_extrusion_paths(const ExtrusionPaths& paths, double limit_distance) {
if (paths.empty()) return paths;
ExtrusionPaths result;
result.push_back(paths.front());
for (size_t pidx = 1; pidx < paths.size(); pidx++) {
if ((result.back().last_point() - paths[pidx].first_point()).cast<double>().squaredNorm() < limit_distance * limit_distance) {
result.back().polyline.points.insert(result.back().polyline.points.end(), paths[pidx].polyline.points.begin(),
paths[pidx].polyline.points.end());
} else {
result.push_back(paths[pidx]);
}
}
return result;
}
ExtrusionPaths sort_and_connect_extra_perimeters(const std::vector<ExtrusionPaths> &extra_perims, double touch_distance)
{
std::vector<ExtrusionPaths> connected_shells;
for (const ExtrusionPaths& ps : extra_perims) {
connected_shells.push_back(reconnect_extrusion_paths(ps, touch_distance));
}
struct Pidx
{
size_t shell;
size_t path;
bool operator==(const Pidx &rhs) const { return shell == rhs.shell && path == rhs.path; }
};
struct PidxHash
{
size_t operator()(const Pidx &i) const { return std::hash<size_t>{}(i.shell) ^ std::hash<size_t>{}(i.path); }
};
auto get_path = [&](Pidx i) { return connected_shells[i.shell][i.path]; };
Point current_point{};
bool any_point_found = false;
std::vector<std::unordered_map<Pidx, std::unordered_set<Pidx, PidxHash>, PidxHash>> dependencies;
for (size_t shell = 0; shell < connected_shells.size(); shell++) {
dependencies.push_back({});
auto &current_shell = dependencies[shell];
for (size_t path = 0; path < connected_shells[shell].size(); path++) {
Pidx current_path{shell, path};
std::unordered_set<Pidx, PidxHash> current_dependencies{};
if (shell > 0) {
for (const auto &prev_path : dependencies[shell - 1]) {
if (paths_touch(get_path(current_path), get_path(prev_path.first), touch_distance)) {
current_dependencies.insert(prev_path.first);
};
}
current_shell[current_path] = current_dependencies;
if (!any_point_found) {
current_point = get_path(current_path).first_point();
any_point_found = true;
}
}
}
}
ExtrusionPaths sorted_paths{};
Pidx npidx = Pidx{size_t(-1), 0};
Pidx next_pidx = npidx;
bool reverse = false;
while (true) {
if (next_pidx == npidx) { // find next pidx to print
double dist = std::numeric_limits<double>::max();
for (size_t shell = 0; shell < dependencies.size(); shell++) {
for (const auto &p : dependencies[shell]) {
if (!p.second.empty()) continue;
const auto &path = get_path(p.first);
double dist_a = (path.first_point() - current_point).cast<double>().squaredNorm();
if (dist_a < dist) {
dist = dist_a;
next_pidx = p.first;
reverse = false;
}
double dist_b = (path.last_point() - current_point).cast<double>().squaredNorm();
if (dist_b < dist) {
dist = dist_b;
next_pidx = p.first;
reverse = true;
}
}
}
if (next_pidx == npidx) { break; }
} else { // we have valid next_pidx, add it to the sorted paths, update dependencies, update current point and potentialy set new next_pidx
ExtrusionPath path = get_path(next_pidx);
if (reverse) { path.reverse(); }
sorted_paths.push_back(path);
current_point = sorted_paths.back().last_point();
if (next_pidx.shell < dependencies.size() - 1) {
for (auto &p : dependencies[next_pidx.shell + 1]) { p.second.erase(next_pidx); }
}
dependencies[next_pidx.shell].erase(next_pidx);
// check current and next shell for next pidx
double dist = std::numeric_limits<double>::max();
size_t current_shell = next_pidx.shell;
next_pidx = npidx;
for (size_t shell = current_shell; shell < std::min(current_shell + 2, dependencies.size()); shell++) {
for (const auto &p : dependencies[shell]) {
if (!p.second.empty()) continue;
const ExtrusionPath &next_path = get_path(p.first);
double dist_a = (next_path.first_point() - current_point).cast<double>().squaredNorm();
if (dist_a < dist) {
dist = dist_a;
next_pidx = p.first;
reverse = false;
}
double dist_b = (next_path.last_point() - current_point).cast<double>().squaredNorm();
if (dist_b < dist) {
dist = dist_b;
next_pidx = p.first;
reverse = true;
}
}
}
if (dist > scaled(5.0)){
next_pidx = npidx;
}
}
}
ExtrusionPaths reconnected = reconnect_extrusion_paths(sorted_paths, touch_distance);
ExtrusionPaths filtered;
filtered.reserve(reconnected.size());
for (ExtrusionPath &p : reconnected) {
if (p.length() > touch_distance) { filtered.push_back(p); }
}
return filtered;
}
#define EXTRA_PERIMETER_OFFSET_PARAMETERS ClipperLib::jtSquare, 0.
// #define EXTRA_PERIM_DEBUG_FILES
// Function will generate extra perimeters clipped over nonbridgeable areas of the provided surface and returns both the new perimeters and
// Polygons filled by those clipped perimeters
std::tuple<std::vector<ExtrusionPaths>, Polygons> generate_extra_perimeters_over_overhangs(ExPolygons infill_area,
const Polygons &lower_slices_polygons,
const Flow &overhang_flow,
double scaled_resolution,
const PrintObjectConfig &object_config,
const PrintConfig &print_config)
{
coord_t anchors_size = scale_(EXTERNAL_INFILL_MARGIN);
Polygons anchors = intersection(infill_area, lower_slices_polygons);
Polygons overhangs = diff(infill_area, lower_slices_polygons);
if (overhangs.empty()) { return {}; }
Polygons inset_anchors; // anchored area inset by the anchor length
{
std::vector<double> deltas{anchors_size * 0.15 + 0.5 * overhang_flow.scaled_spacing(),
anchors_size * 0.33 + 0.5 * overhang_flow.scaled_spacing(),
anchors_size * 0.66 + 0.5 * overhang_flow.scaled_spacing(), anchors_size * 1.00};
std::vector<Polygons> anchor_areas_w_delta_anchor_size{};
for (double delta : deltas) {
anchor_areas_w_delta_anchor_size.push_back(diff(anchors, expand(overhangs, delta, EXTRA_PERIMETER_OFFSET_PARAMETERS)));
}
for (size_t i = 0; i < anchor_areas_w_delta_anchor_size.size() - 1; i++) {
Polygons clipped = diff(anchor_areas_w_delta_anchor_size[i], expand(anchor_areas_w_delta_anchor_size[i + 1],
deltas[i + 1], EXTRA_PERIMETER_OFFSET_PARAMETERS));
anchor_areas_w_delta_anchor_size[i] = intersection(anchor_areas_w_delta_anchor_size[i],
expand(clipped, deltas[i+1] + 0.1*overhang_flow.scaled_spacing(),
EXTRA_PERIMETER_OFFSET_PARAMETERS));
}
for (size_t i = 0; i < anchor_areas_w_delta_anchor_size.size(); i++) {
inset_anchors = union_(inset_anchors, anchor_areas_w_delta_anchor_size[i]);
}
inset_anchors = opening(inset_anchors, 0.8 * deltas[0], EXTRA_PERIMETER_OFFSET_PARAMETERS);
inset_anchors = closing(inset_anchors, 0.8 * deltas[0], EXTRA_PERIMETER_OFFSET_PARAMETERS);
#ifdef EXTRA_PERIM_DEBUG_FILES
{
std::vector<std::string> colors = {"blue", "purple", "orange", "red"};
BoundingBox bbox = get_extents(anchors);
bbox.offset(scale_(1.));
::Slic3r::SVG svg(debug_out_path("anchored").c_str(), bbox);
for (const Line &line : to_lines(inset_anchors)) svg.draw(line, "green", scale_(0.2));
for (size_t i = 0; i < anchor_areas_w_delta_anchor_size.size(); i++) {
for (const Line &line : to_lines(anchor_areas_w_delta_anchor_size[i])) svg.draw(line, colors[i], scale_(0.1));
}
svg.Close();
}
#endif
}
Polygons inset_overhang_area = diff(infill_area, inset_anchors);
#ifdef EXTRA_PERIM_DEBUG_FILES
{
BoundingBox bbox = get_extents(inset_overhang_area);
bbox.offset(scale_(1.));
::Slic3r::SVG svg(debug_out_path("inset_overhang_area").c_str(), bbox);
for (const Line &line : to_lines(inset_anchors)) svg.draw(line, "purple", scale_(0.25));
for (const Line &line : to_lines(inset_overhang_area)) svg.draw(line, "red", scale_(0.15));
svg.Close();
}
#endif
Polygons inset_overhang_area_left_unfilled;
std::vector<std::vector<ExtrusionPaths>> extra_perims; // overhang region -> shell -> shell parts
for (const ExPolygon &overhang : union_ex(to_expolygons(inset_overhang_area))) {
Polygons overhang_to_cover = to_polygons(overhang);
Polygons expanded_overhang_to_cover = expand(overhang_to_cover, 1.1 * overhang_flow.scaled_spacing());
Polygons shrinked_overhang_to_cover = shrink(overhang_to_cover, 0.1 * overhang_flow.scaled_spacing());
Polygons real_overhang = intersection(overhang_to_cover, overhangs);
if (real_overhang.empty()) {
inset_overhang_area_left_unfilled.insert(inset_overhang_area_left_unfilled.end(), overhang_to_cover.begin(),
overhang_to_cover.end());
continue;
}
extra_perims.emplace_back();
std::vector<ExtrusionPaths> &overhang_region = extra_perims.back();
Polygons anchoring = intersection(expanded_overhang_to_cover, inset_anchors);
Polygons perimeter_polygon = offset(union_(expand(overhang_to_cover, 0.1 * overhang_flow.scaled_spacing()), anchoring),
-overhang_flow.scaled_spacing() * 0.6);
Polygon anchoring_convex_hull = Geometry::convex_hull(anchoring);
double unbridgeable_area = area(diff(real_overhang, {anchoring_convex_hull}));
// penalize also holes
for (const Polygon &poly : perimeter_polygon) {
if (poly.is_clockwise()) { // hole, penalize bridges.
unbridgeable_area += std::abs(area(poly));
}
}
auto [dir, unsupp_dist] = detect_bridging_direction(real_overhang, anchors);
#ifdef EXTRA_PERIM_DEBUG_FILES
{
BoundingBox bbox = get_extents(anchoring_convex_hull);
bbox.offset(scale_(1.));
::Slic3r::SVG svg(debug_out_path("bridge_check").c_str(), bbox);
for (const Line &line : to_lines(perimeter_polygon)) svg.draw(line, "purple", scale_(0.25));
for (const Line &line : to_lines(real_overhang)) svg.draw(line, "red", scale_(0.20));
for (const Line &line : to_lines(anchoring_convex_hull)) svg.draw(line, "green", scale_(0.15));
for (const Line &line : to_lines(anchoring)) svg.draw(line, "yellow", scale_(0.10));
for (const Line &line : to_lines(diff_ex(perimeter_polygon, {anchoring_convex_hull}))) svg.draw(line, "black", scale_(0.10));
svg.Close();
}
#endif
if (unbridgeable_area < 0.2 * area(real_overhang) && unsupp_dist < total_length(real_overhang) * 0.125) {
inset_overhang_area_left_unfilled.insert(inset_overhang_area_left_unfilled.end(),overhang_to_cover.begin(),overhang_to_cover.end());
perimeter_polygon.clear();
} else {
// fill the overhang with perimeters
int continuation_loops = 2;
while (continuation_loops > 0) {
auto prev = perimeter_polygon;
// prepare next perimeter lines
Polylines perimeter = intersection_pl(to_polylines(perimeter_polygon), shrinked_overhang_to_cover);
// do not add the perimeter to result yet, first check if perimeter_polygon is not empty after shrinking - this would mean
// that the polygon was possibly too small for full perimeter loop and in that case try gap fill first
perimeter_polygon = union_(perimeter_polygon, anchoring);
perimeter_polygon = intersection(offset(perimeter_polygon, -overhang_flow.scaled_spacing()), expanded_overhang_to_cover);
if (perimeter_polygon.empty()) { // fill possible gaps of single extrusion width
Polygons shrinked = offset(prev, -0.4 * overhang_flow.scaled_spacing());
if (!shrinked.empty()) {
overhang_region.emplace_back();
extrusion_paths_append(overhang_region.back(), perimeter, erOverhangPerimeter, overhang_flow.mm3_per_mm(),
overhang_flow.width(), overhang_flow.height());
}
Polylines fills;
ExPolygons gap = shrinked.empty() ? offset_ex(prev, overhang_flow.scaled_spacing() * 0.5) :
offset_ex(prev, -overhang_flow.scaled_spacing() * 0.5);
//gap = expolygons_simplify(gap, overhang_flow.scaled_spacing());
for (const ExPolygon &ep : gap) {
ep.medial_axis(overhang_flow.scaled_spacing() * 2.0, 0.3 * overhang_flow.scaled_width(), &fills);
}
if (!fills.empty()) {
fills = intersection_pl(fills, inset_overhang_area);
overhang_region.emplace_back();
extrusion_paths_append(overhang_region.back(), fills, erOverhangPerimeter, overhang_flow.mm3_per_mm(),
overhang_flow.width(), overhang_flow.height());
}
break;
} else {
overhang_region.emplace_back();
extrusion_paths_append(overhang_region.back(), perimeter, erOverhangPerimeter, overhang_flow.mm3_per_mm(),
overhang_flow.width(), overhang_flow.height());
}
if (intersection(perimeter_polygon, real_overhang).empty()) { continuation_loops--; }
if (prev == perimeter_polygon) {
#ifdef EXTRA_PERIM_DEBUG_FILES
BoundingBox bbox = get_extents(perimeter_polygon);
bbox.offset(scale_(5.));
::Slic3r::SVG svg(debug_out_path("perimeter_polygon").c_str(), bbox);
for (const Line &line : to_lines(perimeter_polygon)) svg.draw(line, "blue", scale_(0.25));
for (const Line &line : to_lines(overhang_to_cover)) svg.draw(line, "red", scale_(0.20));
for (const Line &line : to_lines(real_overhang)) svg.draw(line, "green", scale_(0.15));
for (const Line &line : to_lines(anchoring)) svg.draw(line, "yellow", scale_(0.10));
svg.Close();
#endif
break;
}
}
Polylines perimeter = intersection_pl(to_polylines(perimeter_polygon), shrinked_overhang_to_cover);
overhang_region.emplace_back();
extrusion_paths_append(overhang_region.back(), perimeter, erOverhangPerimeter, overhang_flow.mm3_per_mm(),
overhang_flow.width(), overhang_flow.height());
perimeter_polygon = expand(perimeter_polygon, 0.5 * overhang_flow.scaled_spacing());
perimeter_polygon = union_(perimeter_polygon, anchoring);
inset_overhang_area_left_unfilled.insert(inset_overhang_area_left_unfilled.end(), perimeter_polygon.begin(),perimeter_polygon.end());
#ifdef EXTRA_PERIM_DEBUG_FILES
BoundingBox bbox = get_extents(inset_overhang_area);
bbox.offset(scale_(2.));
::Slic3r::SVG svg(debug_out_path("pre_final").c_str(), bbox);
for (const Line &line : to_lines(perimeter_polygon)) svg.draw(line, "blue", scale_(0.05));
for (const Line &line : to_lines(anchoring)) svg.draw(line, "green", scale_(0.05));
for (const Line &line : to_lines(overhang_to_cover)) svg.draw(line, "yellow", scale_(0.05));
for (const Line &line : to_lines(inset_overhang_area_left_unfilled)) svg.draw(line, "red", scale_(0.05));
svg.Close();
#endif
std::reverse(overhang_region.begin(), overhang_region.end()); // reverse the order, It shall be printed from inside out
}
}
std::vector<ExtrusionPaths> result{};
for (const std::vector<ExtrusionPaths> &paths : extra_perims) {
result.push_back(sort_and_connect_extra_perimeters(paths, 2.0 * overhang_flow.scaled_spacing()));
}
#ifdef EXTRA_PERIM_DEBUG_FILES
BoundingBox bbox = get_extents(inset_overhang_area);
bbox.offset(scale_(2.));
::Slic3r::SVG svg(debug_out_path(("final" + std::to_string(rand())).c_str()).c_str(), bbox);
for (const Line &line : to_lines(inset_overhang_area_left_unfilled)) svg.draw(line, "blue", scale_(0.05));
for (const Line &line : to_lines(inset_overhang_area)) svg.draw(line, "green", scale_(0.05));
for (const Line &line : to_lines(diff(inset_overhang_area, inset_overhang_area_left_unfilled))) svg.draw(line, "yellow", scale_(0.05));
svg.Close();
#endif
inset_overhang_area_left_unfilled = union_(inset_overhang_area_left_unfilled);
return {result, diff(inset_overhang_area, inset_overhang_area_left_unfilled)};
}
// Thanks, Cura developers, for implementing an algorithm for generating perimeters with variable width (Arachne) that is based on the paper
// "A framework for adaptive width control of dense contour-parallel toolpaths in fused deposition modeling"
void PerimeterGenerator::process_arachne(
@ -830,11 +1231,31 @@ void PerimeterGenerator::process_arachne(
// collapse too narrow infill areas
const auto min_perimeter_infill_spacing = coord_t(solid_infill_spacing * (1. - INSET_OVERLAP_TOLERANCE));
// append infill areas to fill_surfaces
append(out_fill_expolygons,
ExPolygons infill_areas =
offset2_ex(
union_ex(pp),
float(- min_perimeter_infill_spacing / 2.),
float(inset + min_perimeter_infill_spacing / 2.)));
float(inset + min_perimeter_infill_spacing / 2.));
if (lower_slices != nullptr && params.config.overhangs && params.config.extra_perimeters_on_overhangs &&
params.config.perimeters > 0 && params.layer_id > params.object_config.raft_layers) {
// Generate extra perimeters on overhang areas, and cut them to these parts only, to save print time and material
auto [extra_perimeters, filled_area] = generate_extra_perimeters_over_overhangs(infill_areas,
lower_slices_polygons_cache,
params.overhang_flow, params.scaled_resolution,
params.object_config, params.print_config);
if (!extra_perimeters.empty()) {
ExtrusionEntityCollection &this_islands_perimeters = static_cast<ExtrusionEntityCollection&>(*out_loops.entities.back());
ExtrusionEntitiesPtr old_entities;
old_entities.swap(this_islands_perimeters.entities);
for (ExtrusionPaths &paths : extra_perimeters)
this_islands_perimeters.append(std::move(paths));
append(this_islands_perimeters.entities, old_entities);
infill_areas = diff_ex(infill_areas, filled_area);
}
}
append(out_fill_expolygons, std::move(infill_areas));
}
void PerimeterGenerator::process_classic(
@ -1104,11 +1525,31 @@ void PerimeterGenerator::process_classic(
// collapse too narrow infill areas
coord_t min_perimeter_infill_spacing = coord_t(solid_infill_spacing * (1. - INSET_OVERLAP_TOLERANCE));
// append infill areas to fill_surfaces
append(out_fill_expolygons,
ExPolygons infill_areas =
offset2_ex(
union_ex(pp),
float(- inset - min_perimeter_infill_spacing / 2.),
float(min_perimeter_infill_spacing / 2.)));
float(min_perimeter_infill_spacing / 2.));
if (lower_slices != nullptr && params.config.overhangs && params.config.extra_perimeters_on_overhangs &&
params.config.perimeters > 0 && params.layer_id > params.object_config.raft_layers) {
// Generate extra perimeters on overhang areas, and cut them to these parts only, to save print time and material
auto [extra_perimeters, filled_area] = generate_extra_perimeters_over_overhangs(infill_areas,
lower_slices_polygons_cache,
params.overhang_flow, params.scaled_resolution,
params.object_config, params.print_config);
if (!extra_perimeters.empty()) {
ExtrusionEntityCollection &this_islands_perimeters = static_cast<ExtrusionEntityCollection&>(*out_loops.entities.back());
ExtrusionEntitiesPtr old_entities;
old_entities.swap(this_islands_perimeters.entities);
for (ExtrusionPaths &paths : extra_perimeters)
this_islands_perimeters.append(std::move(paths));
append(this_islands_perimeters.entities, old_entities);
infill_areas = diff_ex(infill_areas, filled_area);
}
}
append(out_fill_expolygons, std::move(infill_areas));
}
}

View file

@ -420,7 +420,7 @@ void Preset::set_visible_from_appconfig(const AppConfig &app_config)
static std::vector<std::string> s_Preset_print_options {
"layer_height", "first_layer_height", "perimeters", "spiral_vase", "slice_closing_radius", "slicing_mode",
"top_solid_layers", "top_solid_min_thickness", "bottom_solid_layers", "bottom_solid_min_thickness",
"extra_perimeters", "ensure_vertical_shell_thickness", "avoid_crossing_perimeters", "thin_walls", "overhangs",
"extra_perimeters", "extra_perimeters_on_overhangs", "ensure_vertical_shell_thickness", "avoid_curled_filament_during_travels", "avoid_crossing_perimeters", "thin_walls", "overhangs",
"seam_position","staggered_inner_seams", "external_perimeters_first", "fill_density", "fill_pattern", "top_fill_pattern", "bottom_fill_pattern",
"infill_every_layers", "infill_only_where_needed", "solid_infill_every_layers", "fill_angle", "bridge_angle",
"solid_infill_below_area", "only_retract_when_crossing_perimeters", "infill_first",

View file

@ -0,0 +1,96 @@
#include "PrincipalComponents2D.hpp"
#include "Point.hpp"
namespace Slic3r {
// returns two eigenvectors of the area covered by given polygons. The vectors are sorted by their corresponding eigenvalue, largest first
std::tuple<Vec2d, Vec2d> compute_principal_components(const Polygons &polys, const double unscaled_resolution)
{
// USING UNSCALED VALUES
const Vec2d pixel_size = Vec2d(unscaled_resolution, unscaled_resolution);
const auto bb = get_extents(polys);
const Vec2i pixel_count = unscaled(bb.size()).cwiseQuotient(pixel_size).cast<int>() + Vec2i::Ones();
std::vector<Linef> lines{};
for (Line l : to_lines(polys)) { lines.emplace_back(unscaled(l.a), unscaled(l.b)); }
AABBTreeIndirect::Tree<2, double> tree = AABBTreeLines::build_aabb_tree_over_indexed_lines(lines);
auto is_inside = [&](const Vec2d &point) {
size_t nearest_line_index_out = 0;
Vec2d nearest_point_out = Vec2d::Zero();
auto distance = AABBTreeLines::squared_distance_to_indexed_lines(lines, tree, point, nearest_line_index_out, nearest_point_out);
if (distance < 0) return false;
const Linef &line = lines[nearest_line_index_out];
Vec2d v1 = line.b - line.a;
Vec2d v2 = point - line.a;
if ((v1.x() * v2.y()) - (v1.y() * v2.x()) > 0.0) { return true; }
return false;
};
double pixel_area = pixel_size.x() * pixel_size.y();
Vec2d centroid_accumulator = Vec2d::Zero();
Vec2d second_moment_of_area_accumulator = Vec2d::Zero();
double second_moment_of_area_covariance_accumulator = 0.0;
double area = 0.0;
for (int x = 0; x < pixel_count.x(); x++) {
for (int y = 0; y < pixel_count.y(); y++) {
Vec2d position = unscaled(bb.min) + pixel_size.cwiseProduct(Vec2d{x, y});
if (is_inside(position)) {
area += pixel_area;
centroid_accumulator += pixel_area * position;
second_moment_of_area_accumulator += pixel_area * position.cwiseProduct(position);
second_moment_of_area_covariance_accumulator += pixel_area * position.x() * position.y();
}
}
}
if (area <= 0.0) {
return {Vec2d::Zero(), Vec2d::Zero()};
}
Vec2d centroid = centroid_accumulator / area;
Vec2d variance = second_moment_of_area_accumulator / area - centroid.cwiseProduct(centroid);
double covariance = second_moment_of_area_covariance_accumulator / area - centroid.x() * centroid.y();
#if 0
std::cout << "area : " << area << std::endl;
std::cout << "variancex : " << variance.x() << std::endl;
std::cout << "variancey : " << variance.y() << std::endl;
std::cout << "covariance : " << covariance << std::endl;
#endif
if (abs(covariance) < EPSILON) {
std::tuple<Vec2d, Vec2d> result{Vec2d{variance.x(), 0.0}, Vec2d{0.0, variance.y()}};
if (variance.y() > variance.x()) {
return {std::get<1>(result), std::get<0>(result)};
} else
return result;
}
// now we find the first principal component of the covered area by computing max eigenvalue and the correspoding eigenvector of
// covariance matrix
// covaraince matrix C is : | VarX Cov |
// | Cov VarY |
// Eigenvalues are solutions to det(C - lI) = 0, where l is the eigenvalue and I unit matrix
// Eigenvector for eigenvalue l is any vector v such that Cv = lv
double eigenvalue_a = 0.5 * (variance.x() + variance.y() +
sqrt((variance.x() - variance.y()) * (variance.x() - variance.y()) + 4 * covariance * covariance));
double eigenvalue_b = 0.5 * (variance.x() + variance.y() -
sqrt((variance.x() - variance.y()) * (variance.x() - variance.y()) + 4 * covariance * covariance));
Vec2d eigenvector_a{(eigenvalue_a - variance.y()) / covariance, 1.0};
Vec2d eigenvector_b{(eigenvalue_b - variance.y()) / covariance, 1.0};
#if 0
std::cout << "eigenvalue_a: " << eigenvalue_a << std::endl;
std::cout << "eigenvalue_b: " << eigenvalue_b << std::endl;
std::cout << "eigenvectorA: " << eigenvector_a.x() << " " << eigenvector_a.y() << std::endl;
std::cout << "eigenvectorB: " << eigenvector_b.x() << " " << eigenvector_b.y() << std::endl;
#endif
if (eigenvalue_a > eigenvalue_b) {
return {eigenvector_a, eigenvector_b};
} else {
return {eigenvector_b, eigenvector_a};
}
}
}

View file

@ -0,0 +1,17 @@
#ifndef slic3r_PrincipalComponents2D_hpp_
#define slic3r_PrincipalComponents2D_hpp_
#include "AABBTreeLines.hpp"
#include "BoundingBox.hpp"
#include "libslic3r.h"
#include <vector>
#include "Polygon.hpp"
namespace Slic3r {
// returns two eigenvectors of the area covered by given polygons. The vectors are sorted by their corresponding eigenvalue, largest first
std::tuple<Vec2d, Vec2d> compute_principal_components(const Polygons &polys, const double unscaled_resolution);
}
#endif

View file

@ -58,6 +58,7 @@ bool Print::invalidate_state_by_config_options(const ConfigOptionResolver & /* n
// Cache the plenty of parameters, which influence the G-code generator only,
// or they are only notes not influencing the generated G-code.
static std::unordered_set<std::string> steps_gcode = {
"avoid_curled_filament_during_travels",
"avoid_crossing_perimeters",
"avoid_crossing_perimeters_max_detour",
"bed_shape",
@ -829,6 +830,8 @@ void Print::process()
obj->generate_support_spots();
for (PrintObject *obj : m_objects)
obj->generate_support_material();
for (PrintObject *obj : m_objects)
obj->estimate_curled_extrusions();
if (this->set_started(psWipeTower)) {
m_wipe_tower_data.clear();
m_tool_ordering.clear();

View file

@ -62,7 +62,7 @@ enum PrintStep : unsigned int {
enum PrintObjectStep : unsigned int {
posSlice, posPerimeters, posPrepareInfill,
posInfill, posIroning, posSupportSpotsSearch, posSupportMaterial, posCount,
posInfill, posIroning, posSupportSpotsSearch, posSupportMaterial, posEstimateCurledExtrusions, posCount,
};
// A PrintRegion object represents a group of volumes to print
@ -358,6 +358,7 @@ private:
void ironing();
void generate_support_spots();
void generate_support_material();
void estimate_curled_extrusions();
void slice_volumes();
// Has any support (not counting the raft).

View file

@ -399,6 +399,13 @@ void PrintConfigDef::init_fff_params()
// Maximum extruder temperature, bumped to 1500 to support printing of glass.
const int max_temp = 1500;
def = this->add("avoid_curled_filament_during_travels", coBool);
def->label = L("Avoid curled filament during travels");
def->tooltip = L("Plan travel moves such that the extruder avoids areas where filament may be curled up. "
"This is mostly happening on steeper rounded overhangs and may cause crash or borken print. "
"This feature slows down both the print and the G-code generation.");
def->mode = comExpert;
def->set_default_value(new ConfigOptionBool(false));
def = this->add("avoid_crossing_perimeters", coBool);
def->label = L("Avoid crossing perimeters");
@ -796,6 +803,13 @@ void PrintConfigDef::init_fff_params()
def->mode = comExpert;
def->set_default_value(new ConfigOptionBool(true));
def = this->add("extra_perimeters_on_overhangs", coBool);
def->label = L("Extra perimeters on overhangs");
def->category = L("Layers and Perimeters");
def->tooltip = L("Create additional perimeter paths over steep overhangs and areas where bridges cannot be anchored. ");
def->mode = comExpert;
def->set_default_value(new ConfigOptionBool(false));
def = this->add("extruder", coInt);
def->gui_type = ConfigOptionDef::GUIType::i_enum_open;
def->label = L("Extruder");

View file

@ -566,6 +566,7 @@ PRINT_CONFIG_CLASS_DEFINE(
((ConfigOptionFloatOrPercent, external_perimeter_speed))
((ConfigOptionBool, external_perimeters_first))
((ConfigOptionBool, extra_perimeters))
((ConfigOptionBool, extra_perimeters_on_overhangs))
((ConfigOptionFloat, fill_angle))
((ConfigOptionPercent, fill_density))
((ConfigOptionEnum<InfillPattern>, fill_pattern))
@ -728,6 +729,7 @@ PRINT_CONFIG_CLASS_DERIVED_DEFINE(
PrintConfig,
(MachineEnvelopeConfig, GCodeConfig),
((ConfigOptionBool, avoid_curled_filament_during_travels))
((ConfigOptionBool, avoid_crossing_perimeters))
((ConfigOptionFloatOrPercent, avoid_crossing_perimeters_max_detour))
((ConfigOptionPoints, bed_shape))

View file

@ -424,7 +424,8 @@ void PrintObject::generate_support_spots()
[](const ModelVolume* mv){return mv->supported_facets.empty();})
) {
SupportSpotsGenerator::Params params{this->print()->m_config.filament_type.values};
SupportSpotsGenerator::Issues issues = SupportSpotsGenerator::full_search(this, params);
auto [issues, malformations] = SupportSpotsGenerator::full_search(this, params);
auto obj_transform = this->trafo_centered();
for (ModelVolume *model_volume : this->model_object()->volumes) {
if (model_volume->is_model_part()) {
@ -478,6 +479,26 @@ void PrintObject::generate_support_material()
}
}
void PrintObject::estimate_curled_extrusions()
{
if (this->set_started(posEstimateCurledExtrusions)) {
if (this->print()->config().avoid_curled_filament_during_travels) {
BOOST_LOG_TRIVIAL(debug) << "Estimating areas with curled extrusions - start";
m_print->set_status(88, L("Estimating curled extrusions"));
// Estimate curling of support material and add it to the malformaition lines of each layer
float support_flow_width = support_material_flow(this, this->config().layer_height).width();
SupportSpotsGenerator::Params params{this->print()->m_config.filament_type.values};
SupportSpotsGenerator::estimate_supports_malformations(this->support_layers(), support_flow_width, params);
SupportSpotsGenerator::estimate_malformations(this->layers(), params);
m_print->throw_if_canceled();
BOOST_LOG_TRIVIAL(debug) << "Estimating areas with curled extrusions - end";
}
this->set_done(posEstimateCurledExtrusions);
}
}
std::pair<FillAdaptive::OctreePtr, FillAdaptive::OctreePtr> PrintObject::prepare_adaptive_infill_data()
{
using namespace FillAdaptive;
@ -585,6 +606,7 @@ bool PrintObject::invalidate_state_by_config_options(
} else if (
opt_key == "perimeters"
|| opt_key == "extra_perimeters"
|| opt_key == "extra_perimeters_on_overhangs"
|| opt_key == "first_layer_extrusion_width"
|| opt_key == "perimeter_extrusion_width"
|| opt_key == "infill_overlap"
@ -785,7 +807,7 @@ bool PrintObject::invalidate_step(PrintObjectStep step)
// propagate to dependent steps
if (step == posPerimeters) {
invalidated |= this->invalidate_steps({ posPrepareInfill, posInfill, posIroning });
invalidated |= this->invalidate_steps({ posPrepareInfill, posInfill, posIroning, posEstimateCurledExtrusions });
invalidated |= m_print->invalidate_steps({ psSkirtBrim });
} else if (step == posPrepareInfill) {
invalidated |= this->invalidate_steps({ posInfill, posIroning });
@ -793,11 +815,12 @@ bool PrintObject::invalidate_step(PrintObjectStep step)
invalidated |= this->invalidate_steps({ posIroning });
invalidated |= m_print->invalidate_steps({ psSkirtBrim });
} else if (step == posSlice) {
invalidated |= this->invalidate_steps({ posPerimeters, posPrepareInfill, posInfill, posIroning, posSupportMaterial });
invalidated |= this->invalidate_steps({ posPerimeters, posPrepareInfill, posInfill, posIroning, posSupportMaterial, posEstimateCurledExtrusions });
invalidated |= m_print->invalidate_steps({ psSkirtBrim });
m_slicing_params.valid = false;
} else if (step == posSupportMaterial) {
invalidated |= m_print->invalidate_steps({ psSkirtBrim });
invalidated |= m_print->invalidate_steps({ psSkirtBrim, });
invalidated |= this->invalidate_steps({ posEstimateCurledExtrusions });
m_slicing_params.valid = false;
}

View file

@ -1322,7 +1322,7 @@ namespace SupportMaterialInternal {
// remove the entire bridges and only support the unsupported edges
//FIXME the brided regions are already collected as layerm.bridged. Use it?
for (const Surface &surface : layerm.fill_surfaces())
if (surface.surface_type == stBottomBridge && surface.bridge_angle != -1)
if (surface.surface_type == stBottomBridge && surface.bridge_angle < 0.0)
polygons_append(bridges, surface.expolygon);
//FIXME add the gap filled areas. Extrude the gaps with a bridge flow?
// Remove the unsupported ends of the bridges from the bridged areas.

View file

@ -2,14 +2,20 @@
#include "ExPolygon.hpp"
#include "ExtrusionEntity.hpp"
#include "ExtrusionEntityCollection.hpp"
#include "Line.hpp"
#include "Point.hpp"
#include "Polygon.hpp"
#include "libslic3r.h"
#include "tbb/parallel_for.h"
#include "tbb/blocked_range.h"
#include "tbb/blocked_range2d.h"
#include "tbb/parallel_reduce.h"
#include <boost/log/trivial.hpp>
#include <cmath>
#include <cstdio>
#include <functional>
#include <unordered_map>
#include <unordered_set>
#include <stack>
@ -20,7 +26,7 @@
#include "Geometry/ConvexHull.hpp"
// #define DETAILED_DEBUG_LOGS
// #define DEBUG_FILES
//#define DEBUG_FILES
#ifdef DEBUG_FILES
#include <boost/nowide/cstdio.hpp>
@ -333,7 +339,7 @@ std::vector<ExtrusionLine> to_short_lines(const ExtrusionEntity *e, float length
std::vector<ExtrusionLine> lines;
lines.reserve(pl.points.size() * 1.5f);
lines.emplace_back(unscaled(pl.points[0]).cast<float>(), unscaled(pl.points[0]).cast<float>(), e);
for (int point_idx = 0; point_idx < int(pl.points.size() - 1); ++point_idx) {
for (int point_idx = 0; point_idx < int(pl.points.size()) - 1; ++point_idx) {
Vec2f start = unscaled(pl.points[point_idx]).cast<float>();
Vec2f next = unscaled(pl.points[point_idx + 1]).cast<float>();
Vec2f v = next - start; // vector from next to current
@ -367,12 +373,6 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
const auto to_vec3f = [layer_z](const Vec2f &point) {
return Vec3f(point.x(), point.y(), layer_z);
};
float overhang_dist = tan(params.overhang_angle_deg * PI / 180.0f) * layer_region->layer()->height;
float min_malformation_dist = tan(params.malformation_angle_span_deg.first * PI / 180.0f)
* layer_region->layer()->height;
float max_malformation_dist = tan(params.malformation_angle_span_deg.second * PI / 180.0f)
* layer_region->layer()->height;
std::vector<ExtrusionLine> lines = to_short_lines(entity, params.bridge_distance);
if (lines.empty()) return;
@ -380,6 +380,9 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
ExtrusionPropertiesAccumulator malformation_acc { };
bridging_acc.add_distance(params.bridge_distance + 1.0f);
const float flow_width = get_flow_width(layer_region, entity->role());
float min_malformation_dist = flow_width - params.malformation_overlap_factor.first * flow_width;
float max_malformation_dist = flow_width - params.malformation_overlap_factor.second * flow_width;
for (size_t line_idx = 0; line_idx < lines.size(); ++line_idx) {
ExtrusionLine &current_line = lines[line_idx];
@ -395,9 +398,12 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
bridging_acc.add_angle(curr_angle);
// malformation in concave angles does not happen
malformation_acc.add_angle(std::max(0.0f, curr_angle));
if (curr_angle < -20.0 * PI / 180.0) {
malformation_acc.reset();
}
auto [dist_from_prev_layer, nearest_line_idx, nearest_point] = prev_layer_lines.signed_distance_from_lines_extra(current_line.b);
if (fabs(dist_from_prev_layer) < overhang_dist) {
if (fabs(dist_from_prev_layer) < flow_width) {
bridging_acc.reset();
} else {
bridging_acc.add_distance(current_line.len);
@ -416,15 +422,16 @@ void check_extrusion_entity_stability(const ExtrusionEntity *entity,
}
//malformation
if (fabs(dist_from_prev_layer) < 3.0f * flow_width) {
if (fabs(dist_from_prev_layer) < 2.0f * flow_width) {
const ExtrusionLine &nearest_line = prev_layer_lines.get_line(nearest_line_idx);
current_line.malformation += 0.9 * nearest_line.malformation;
current_line.malformation += 0.85 * nearest_line.malformation;
}
if (dist_from_prev_layer > min_malformation_dist && dist_from_prev_layer < max_malformation_dist) {
float factor = std::abs(dist_from_prev_layer - (max_malformation_dist + min_malformation_dist) * 0.5) /
(max_malformation_dist - min_malformation_dist);
malformation_acc.add_distance(current_line.len);
current_line.malformation += layer_region->layer()->height *
(0.5f + 1.5f * (malformation_acc.max_curvature / PI) *
gauss(malformation_acc.distance, 5.0f, 1.0f, 0.2f));
current_line.malformation += layer_region->layer()->height * factor * (2.0f + 3.0f * (malformation_acc.max_curvature / PI));
current_line.malformation = std::min(current_line.malformation, float(layer_region->layer()->height * params.max_malformation_factor));
} else {
malformation_acc.reset();
}
@ -1023,7 +1030,7 @@ Issues check_global_stability(SupportGridFilter supports_presence_grid,
return issues;
}
std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(const PrintObject *po,
std::tuple<Issues, Malformations, std::vector<LayerIslands>> check_extrusions_and_build_graph(const PrintObject *po,
const Params &params) {
#ifdef DEBUG_FILES
FILE *segmentation_f = boost::nowide::fopen(debug_out_path("segmentation.obj").c_str(), "w");
@ -1031,6 +1038,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
#endif
Issues issues { };
Malformations malformations{};
std::vector<LayerIslands> islands_graph;
std::vector<ExtrusionLine> layer_lines;
float flow_width = get_flow_width(po->layers()[po->layer_count() - 1]->regions()[0], erExternalPerimeter);
@ -1038,6 +1046,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
// PREPARE BASE LAYER
const Layer *layer = po->layers()[0];
malformations.layers.push_back({}); // no malformations to be expected at first layer
for (const LayerRegion *layer_region : layer->regions()) {
for (const ExtrusionEntity *ex_entity : layer_region->perimeters()) {
for (const ExtrusionEntity *perimeter : static_cast<const ExtrusionEntityCollection*>(ex_entity)->entities) {
@ -1106,6 +1115,12 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
layer_lines, params);
islands_graph.push_back(std::move(layer_islands));
Lines malformed_lines{};
for (const auto &line : layer_lines) {
if (line.malformation > 0.3f) { malformed_lines.push_back(Line{Point::new_scale(line.a), Point::new_scale(line.b)}); }
}
malformations.layers.push_back(malformed_lines);
#ifdef DEBUG_FILES
for (size_t x = 0; x < size_t(layer_grid.get_pixel_count().x()); ++x) {
for (size_t y = 0; y < size_t(layer_grid.get_pixel_count().y()); ++y) {
@ -1122,7 +1137,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
}
for (const auto &line : layer_lines) {
if (line.malformation > 0.0f) {
Vec3f color = value_to_rgbf(0, 1.0f, line.malformation);
Vec3f color = value_to_rgbf(-EPSILON, layer->height*params.max_malformation_factor, line.malformation);
fprintf(malform_f, "v %f %f %f %f %f %f\n", line.b[0],
line.b[1], layer->slice_z, color[0], color[1], color[2]);
}
@ -1138,7 +1153,7 @@ std::tuple<Issues, std::vector<LayerIslands>> check_extrusions_and_build_graph(c
fclose(malform_f);
#endif
return {issues, islands_graph};
return {issues, malformations, islands_graph};
}
#ifdef DEBUG_FILES
@ -1167,8 +1182,8 @@ void debug_export(Issues issues, std::string file_name) {
// return {};
// }
Issues full_search(const PrintObject *po, const Params &params) {
auto [local_issues, graph] = check_extrusions_and_build_graph(po, params);
std::tuple<Issues, Malformations> full_search(const PrintObject *po, const Params &params) {
auto [local_issues, malformations, graph] = check_extrusions_and_build_graph(po, params);
Issues global_issues = check_global_stability( { po, params.min_distance_between_support_points }, graph, params);
#ifdef DEBUG_FILES
debug_export(local_issues, "local_issues");
@ -1178,7 +1193,156 @@ Issues full_search(const PrintObject *po, const Params &params) {
global_issues.support_points.insert(global_issues.support_points.end(),
local_issues.support_points.begin(), local_issues.support_points.end());
return global_issues;
return {global_issues, malformations};
}
struct LayerCurlingEstimator
{
LD prev_layer_lines = LD({});
Params params;
std::function<float(const ExtrusionLine &)> flow_width_getter;
LayerCurlingEstimator(std::function<float(const ExtrusionLine &)> flow_width_getter, const Params &params)
: flow_width_getter(flow_width_getter), params(params)
{}
void estimate_curling(std::vector<ExtrusionLine> &extrusion_lines, Layer *l)
{
ExtrusionPropertiesAccumulator malformation_acc{};
for (size_t line_idx = 0; line_idx < extrusion_lines.size(); ++line_idx) {
ExtrusionLine &current_line = extrusion_lines[line_idx];
float flow_width = flow_width_getter(current_line);
float min_malformation_dist = flow_width - params.malformation_overlap_factor.first * flow_width;
float max_malformation_dist = flow_width - params.malformation_overlap_factor.second * flow_width;
float curr_angle = 0;
if (line_idx + 1 < extrusion_lines.size()) {
const Vec2f v1 = current_line.b - current_line.a;
const Vec2f v2 = extrusion_lines[line_idx + 1].b - extrusion_lines[line_idx + 1].a;
curr_angle = angle(v1, v2);
}
// malformation in concave angles does not happen
malformation_acc.add_angle(std::max(0.0f, curr_angle));
if (curr_angle < -20.0 * PI / 180.0) { malformation_acc.reset(); }
auto [dist_from_prev_layer, nearest_line_idx, nearest_point] = prev_layer_lines.signed_distance_from_lines_extra(current_line.b);
if (fabs(dist_from_prev_layer) < 2.0f * flow_width) {
const ExtrusionLine &nearest_line = prev_layer_lines.get_line(nearest_line_idx);
current_line.malformation += 0.9 * nearest_line.malformation;
}
if (dist_from_prev_layer > min_malformation_dist && dist_from_prev_layer < max_malformation_dist) {
float factor = 0.5f + 0.5f * std::abs(dist_from_prev_layer - (max_malformation_dist + min_malformation_dist) * 0.5) /
(max_malformation_dist - min_malformation_dist);
malformation_acc.add_distance(current_line.len);
current_line.malformation += l->height * factor * (1.5f + 3.0f * (malformation_acc.max_curvature / PI));
current_line.malformation = std::min(current_line.malformation, float(l->height * params.max_malformation_factor));
} else {
malformation_acc.reset();
}
}
for (const ExtrusionLine &line : extrusion_lines) {
if (line.malformation > 0.3f) { l->malformed_lines.push_back(Line{Point::new_scale(line.a), Point::new_scale(line.b)}); }
}
prev_layer_lines = LD(extrusion_lines);
}
};
void estimate_supports_malformations(SupportLayerPtrs &layers, float supports_flow_width, const Params &params)
{
#ifdef DEBUG_FILES
FILE *debug_file = boost::nowide::fopen(debug_out_path("supports_malformations.obj").c_str(), "w");
#endif
auto flow_width_getter = [=](const ExtrusionLine& l) {
return supports_flow_width;
};
LayerCurlingEstimator lce{flow_width_getter, params};
for (SupportLayer *l : layers) {
std::vector<ExtrusionLine> extrusion_lines;
for (const ExtrusionEntity *extrusion : l->support_fills.flatten().entities) {
Polyline pl = extrusion->as_polyline();
Polygon pol(pl.points);
pol.make_counter_clockwise();
pl = pol.split_at_first_point();
for (int point_idx = 0; point_idx < int(pl.points.size() - 1); ++point_idx) {
Vec2f start = unscaled(pl.points[point_idx]).cast<float>();
Vec2f next = unscaled(pl.points[point_idx + 1]).cast<float>();
ExtrusionLine line{start, next, extrusion};
extrusion_lines.push_back(line);
}
}
lce.estimate_curling(extrusion_lines, l);
#ifdef DEBUG_FILES
for (const ExtrusionLine &line : extrusion_lines) {
if (line.malformation > 0.3f) {
Vec3f color = value_to_rgbf(-EPSILON, l->height * params.max_malformation_factor, line.malformation);
fprintf(debug_file, "v %f %f %f %f %f %f\n", line.b[0], line.b[1], l->print_z, color[0], color[1], color[2]);
}
}
#endif
}
#ifdef DEBUG_FILES
fclose(debug_file);
#endif
}
void estimate_malformations(LayerPtrs &layers, const Params &params)
{
#ifdef DEBUG_FILES
FILE *debug_file = boost::nowide::fopen(debug_out_path("object_malformations.obj").c_str(), "w");
#endif
auto flow_width_getter = [](const ExtrusionLine &l) { return 0.0; };
LayerCurlingEstimator lce{flow_width_getter, params};
for (Layer *l : layers) {
if (l->regions().empty()) {
continue;
}
struct Visitor {
Visitor(const Params &params) : params(params) {}
void recursive_do(const ExtrusionEntityCollection &collection, const LayerRegion *region) {
for (const ExtrusionEntity* entity : collection.entities)
if (entity->is_collection())
this->recursive_do(*static_cast<const ExtrusionEntityCollection*>(entity), region);
else {
append(extrusion_lines, to_short_lines(entity, params.bridge_distance));
extrusions_widths.emplace(entity, get_flow_width(region, entity->role()));
}
}
const Params &params;
std::unordered_map<const ExtrusionEntity*, float> extrusions_widths;
std::vector<ExtrusionLine> extrusion_lines;
} visitor(params);
for (const LayerRegion *region : l->regions())
visitor.recursive_do(region->perimeters(), region);
lce.flow_width_getter = [&](const ExtrusionLine &l) { return visitor.extrusions_widths[l.origin_entity]; };
lce.estimate_curling(visitor.extrusion_lines, l);
#ifdef DEBUG_FILES
for (const ExtrusionLine &line : extrusion_lines) {
if (line.malformation > 0.3f) {
Vec3f color = value_to_rgbf(-EPSILON, l->height * params.max_malformation_factor, line.malformation);
fprintf(debug_file, "v %f %f %f %f %f %f\n", line.b[0], line.b[1], l->print_z, color[0], color[1], color[2]);
}
}
#endif
}
#ifdef DEBUG_FILES
fclose(debug_file);
#endif
}
} //SupportableIssues End

View file

@ -26,8 +26,8 @@ struct Params {
// the algorithm should use the following units for all computations: distance [mm], mass [g], time [s], force [g*mm/s^2]
const float bridge_distance = 12.0f; //mm
const float bridge_distance_decrease_by_curvature_factor = 5.0f; // allowed bridge distance = bridge_distance / (1 + this factor * (curvature / PI) )
const float overhang_angle_deg = 80.0f;
const std::pair<float,float> malformation_angle_span_deg = std::pair<float, float> { 45.0f, 80.0f };
const std::pair<float,float> malformation_overlap_factor = std::pair<float, float> { 0.50, -0.1 };
const float max_malformation_factor = 10.0f;
const float min_distance_between_support_points = 3.0f; //mm
const float support_points_interface_radius = 1.5f; // mm
@ -72,11 +72,17 @@ struct Issues {
std::vector<SupportPoint> support_points;
};
struct Malformations {
std::vector<Lines> layers; //for each layer
};
// std::vector<size_t> quick_search(const PrintObject *po, const Params &params);
Issues full_search(const PrintObject *po, const Params &params);
std::tuple<Issues, Malformations> full_search(const PrintObject *po, const Params &params);
}
void estimate_supports_malformations(SupportLayerPtrs &layers, float supports_flow_width, const Params &params);
void estimate_malformations(LayerPtrs &layers, const Params &params);
} // namespace SupportSpotsGenerator
}
#endif /* SRC_LIBSLIC3R_SUPPORTABLEISSUESSEARCH_HPP_ */

View file

@ -55,8 +55,6 @@
#define ENABLE_RELOAD_FROM_DISK_REWORK (1 && ENABLE_2_5_0_ALPHA1)
// Enable editing volumes transformation in world coordinates and instances in local coordinates
#define ENABLE_WORLD_COORDINATE (1 && ENABLE_2_5_0_ALPHA1)
// Enable modified camera control using mouse
#define ENABLE_NEW_CAMERA_MOVEMENTS (1 && ENABLE_2_5_0_ALPHA1)
// Enable alternative version of file_wildcards()
#define ENABLE_ALTERNATIVE_FILE_WILDCARDS_GENERATOR (1 && ENABLE_2_5_0_ALPHA1)
// Enable processing of gcode G2 and G3 lines

View file

@ -218,7 +218,7 @@ void ConfigManipulation::update_print_fff_config(DynamicPrintConfig* config, con
void ConfigManipulation::toggle_print_fff_options(DynamicPrintConfig* config)
{
bool have_perimeters = config->opt_int("perimeters") > 0;
for (auto el : { "extra_perimeters", "ensure_vertical_shell_thickness", "thin_walls", "overhangs",
for (auto el : { "extra_perimeters","extra_perimeters_on_overhangs", "ensure_vertical_shell_thickness", "thin_walls", "overhangs",
"seam_position","staggered_inner_seams", "external_perimeters_first", "external_perimeter_extrusion_width",
"perimeter_speed", "small_perimeter_speed", "external_perimeter_speed" })
toggle_field(el, have_perimeters);

View file

@ -2997,7 +2997,6 @@ void GLCanvas3D::on_key(wxKeyEvent& evt)
// set_cursor(Standard);
}
else if (keyCode == WXK_CONTROL) {
#if ENABLE_NEW_CAMERA_MOVEMENTS
#if ENABLE_RAYCAST_PICKING
if (m_mouse.dragging && !m_moving) {
#else
@ -3008,7 +3007,6 @@ void GLCanvas3D::on_key(wxKeyEvent& evt)
m_mouse.drag.move_volume_idx = -1;
m_mouse.set_start_position_3D_as_invalid();
}
#endif // ENABLE_NEW_CAMERA_MOVEMENTS
m_ctrl_kar_filter.reset_count();
m_dirty = true;
}
@ -3515,10 +3513,8 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
m_volumes.volumes[volume_idx]->hover = GLVolume::HS_None;
// The dragging operation is initiated.
m_mouse.drag.move_volume_idx = volume_idx;
#if ENABLE_NEW_CAMERA_MOVEMENTS
m_selection.setup_cache();
if (!evt.CmdDown())
#endif // ENABLE_NEW_CAMERA_MOVEMENTS
m_mouse.drag.start_position_3D = m_mouse.scene_position;
m_sequential_print_clearance_first_displacement = true;
#if !ENABLE_RAYCAST_PICKING
@ -3529,12 +3525,8 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
}
}
}
#if ENABLE_NEW_CAMERA_MOVEMENTS
else if (evt.Dragging() && evt.LeftIsDown() && !evt.CmdDown() && m_layers_editing.state == LayersEditing::Unknown &&
m_mouse.drag.move_volume_idx != -1 && m_mouse.is_start_position_3D_defined()) {
#else
else if (evt.Dragging() && evt.LeftIsDown() && m_layers_editing.state == LayersEditing::Unknown && m_mouse.drag.move_volume_idx != -1) {
#endif // ENABLE_NEW_CAMERA_MOVEMENTS
if (!m_mouse.drag.move_requires_threshold) {
m_mouse.dragging = true;
Vec3d cur_pos = m_mouse.drag.start_position_3D;
@ -3602,18 +3594,12 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
}
}
// do not process the dragging if the left mouse was set down in another canvas
#if ENABLE_NEW_CAMERA_MOVEMENTS
else if (evt.LeftIsDown()) {
// if dragging over blank area with left button, rotate
#if ENABLE_RAYCAST_PICKING
if (!m_moving) {
#endif // ENABLE_RAYCAST_PICKING
if ((any_gizmo_active || evt.CmdDown() || m_hover_volume_idxs.empty()) && m_mouse.is_start_position_3D_defined()) {
#else
// if dragging over blank area with left button, rotate
else if (evt.LeftIsDown()) {
if ((any_gizmo_active || m_hover_volume_idxs.empty()) && m_mouse.is_start_position_3D_defined()) {
#endif // ENABLE_NEW_CAMERA_MOVEMENTS
const Vec3d rot = (Vec3d(pos.x(), pos.y(), 0.0) - m_mouse.drag.start_position_3D) * (PI * TRACKBALLSIZE / 180.0);
if (wxGetApp().app_config->get("use_free_camera") == "1")
// Virtual track ball (similar to the 3DConnexion mouse).
@ -5162,6 +5148,8 @@ bool GLCanvas3D::_init_main_toolbar()
item.left.toggable = true;
item.left.render_callback = [this](float left, float right, float, float) {
if (m_canvas != nullptr) {
if (!m_canvas->HasFocus())
m_canvas->SetFocus();
if (_render_search_list(0.5f * (left + right)))
_deactivate_search_toolbar_item();
}
@ -6719,6 +6707,10 @@ void GLCanvas3D::_render_selection_sidebar_hints()
void GLCanvas3D::_update_volumes_hover_state()
{
// skip update if the Gizmo Measure is active
if (m_gizmos.get_current_type() == GLGizmosManager::Measure)
return;
for (GLVolume* v : m_volumes.volumes) {
v->hover = GLVolume::HS_None;
}
@ -6726,9 +6718,9 @@ void GLCanvas3D::_update_volumes_hover_state()
if (m_hover_volume_idxs.empty())
return;
bool ctrl_pressed = wxGetKeyState(WXK_CONTROL); // additive select/deselect
bool shift_pressed = wxGetKeyState(WXK_SHIFT); // select by rectangle
bool alt_pressed = wxGetKeyState(WXK_ALT); // deselect by rectangle
const bool ctrl_pressed = wxGetKeyState(WXK_CONTROL);
const bool shift_pressed = wxGetKeyState(WXK_SHIFT);
const bool alt_pressed = wxGetKeyState(WXK_ALT);
if (alt_pressed && (shift_pressed || ctrl_pressed)) {
// illegal combinations of keys
@ -6763,22 +6755,22 @@ void GLCanvas3D::_update_volumes_hover_state()
if (volume.hover != GLVolume::HS_None)
continue;
bool deselect = volume.selected && ((shift_pressed && m_rectangle_selection.is_empty()) || (alt_pressed && !m_rectangle_selection.is_empty()));
bool select = !volume.selected && (m_rectangle_selection.is_empty() || (shift_pressed && !m_rectangle_selection.is_empty()));
const bool deselect = volume.selected && ((shift_pressed && m_rectangle_selection.is_empty()) || (alt_pressed && !m_rectangle_selection.is_empty()));
const bool select = !volume.selected && (m_rectangle_selection.is_empty() || (shift_pressed && !m_rectangle_selection.is_empty()));
if (select || deselect) {
bool as_volume =
const bool as_volume =
volume.is_modifier && hover_from_single_instance && !ctrl_pressed &&
(
(!deselect) ||
(deselect && !m_selection.is_single_full_instance() && (volume.object_idx() == m_selection.get_object_idx()) && (volume.instance_idx() == m_selection.get_instance_idx()))
!deselect ||
(deselect && !m_selection.is_single_full_instance() && volume.object_idx() == m_selection.get_object_idx() && volume.instance_idx() == m_selection.get_instance_idx())
);
if (as_volume)
volume.hover = deselect ? GLVolume::HS_Deselect : GLVolume::HS_Select;
else {
int object_idx = volume.object_idx();
int instance_idx = volume.instance_idx();
const int object_idx = volume.object_idx();
const int instance_idx = volume.instance_idx();
for (GLVolume* v : m_volumes.volumes) {
if (v->object_idx() == object_idx && v->instance_idx() == instance_idx)

View file

@ -216,9 +216,7 @@ ObjectList::ObjectList(wxWindow* parent) :
Bind(wxEVT_DATAVIEW_ITEM_DROP_POSSIBLE, &ObjectList::OnDropPossible, this);
Bind(wxEVT_DATAVIEW_ITEM_DROP, &ObjectList::OnDrop, this);
#ifdef __WXMSW__
Bind(wxEVT_DATAVIEW_ITEM_EDITING_STARTED, &ObjectList::OnEditingStarted, this);
#endif /* __WXMSW__ */
Bind(wxEVT_DATAVIEW_ITEM_EDITING_DONE, &ObjectList::OnEditingDone, this);
Bind(wxEVT_DATAVIEW_ITEM_VALUE_CHANGED, &ObjectList::ItemValueChanged, this);
@ -1866,12 +1864,10 @@ bool ObjectList::del_subobject_item(wxDataViewItem& item)
// If last volume item with warning was deleted, unmark object item
if (type & itVolume) {
add_volumes_to_object_in_list(obj_idx);
const std::string& icon_name = get_warning_icon_name(object(obj_idx)->get_object_stl_stats());
m_objects_model->UpdateWarningIcon(parent, icon_name);
}
else
m_objects_model->Delete(item);
m_objects_model->Delete(item);
update_info_items(obj_idx);
@ -3033,7 +3029,7 @@ bool ObjectList::delete_from_model_and_list(const std::vector<ItemForDelete>& it
if (!del_subobject_from_object(item->obj_idx, item->sub_obj_idx, item->type))
continue;
if (item->type&itVolume) {
add_volumes_to_object_in_list(item->obj_idx);
m_objects_model->Delete(m_objects_model->GetItemByVolumeId(item->obj_idx, item->sub_obj_idx));
ModelObject* obj = object(item->obj_idx);
if (obj->volumes.size() == 1) {
wxDataViewItem parent = m_objects_model->GetItemById(item->obj_idx);
@ -4621,17 +4617,19 @@ void ObjectList::ItemValueChanged(wxDataViewEvent &event)
}
}
void ObjectList::OnEditingStarted(wxDataViewEvent &event)
{
m_is_editing_started = true;
#ifdef __WXMSW__
// Workaround for entering the column editing mode on Windows. Simulate keyboard enter when another column of the active line is selected.
// Here the last active column is forgotten, so when leaving the editing mode, the next mouse click will not enter the editing mode of the newly selected column.
void ObjectList::OnEditingStarted(wxDataViewEvent &event)
{
m_last_selected_column = -1;
}
#endif //__WXMSW__
}
void ObjectList::OnEditingDone(wxDataViewEvent &event)
{
m_is_editing_started = false;
if (event.GetColumn() != colName)
return;

View file

@ -175,6 +175,7 @@ private:
// Workaround for entering the column editing mode on Windows. Simulate keyboard enter when another column of the active line is selected.
int m_last_selected_column = -1;
#endif /* __MSW__ */
bool m_is_editing_started{ false };
#if 0
SettingsFactory::Bundle m_freq_settings_fff;
@ -404,6 +405,8 @@ public:
void apply_volumes_order();
bool has_paint_on_segmentation();
bool is_editing() const { return m_is_editing_started; }
private:
#ifdef __WXOSX__
// void OnChar(wxKeyEvent& event);
@ -417,10 +420,8 @@ private:
bool can_drop(const wxDataViewItem& item) const ;
void ItemValueChanged(wxDataViewEvent &event);
#ifdef __WXMSW__
// Workaround for entering the column editing mode on Windows. Simulate keyboard enter when another column of the active line is selected.
void OnEditingStarted(wxDataViewEvent &event);
#endif /* __WXMSW__ */
void OnEditingDone(wxDataViewEvent &event);
};

View file

@ -75,10 +75,21 @@ static std::string point_on_feature_type_as_string(Measure::SurfaceFeatureType t
std::string ret;
switch (type) {
case Measure::SurfaceFeatureType::Point: { ret = _u8L("Vertex"); break; }
case Measure::SurfaceFeatureType::Edge: { ret = (hover_id == POINT_ID) ? _u8L("Center of edge") : _u8L("Point on edge"); break; }
case Measure::SurfaceFeatureType::Circle: { ret = (hover_id == POINT_ID) ? _u8L("Center of circle") : _u8L("Point on circle"); break; }
case Measure::SurfaceFeatureType::Edge: { ret = _u8L("Point on edge"); break; }
case Measure::SurfaceFeatureType::Circle: { ret = _u8L("Point on circle"); break; }
case Measure::SurfaceFeatureType::Plane: { ret = _u8L("Point on plane"); break; }
default: { assert(false); break; }
default: { assert(false); break; }
}
return ret;
}
static std::string center_on_feature_type_as_string(Measure::SurfaceFeatureType type)
{
std::string ret;
switch (type) {
case Measure::SurfaceFeatureType::Edge: { ret = _u8L("Center of edge"); break; }
case Measure::SurfaceFeatureType::Circle: { ret = _u8L("Center of circle"); break; }
default: { assert(false); break; }
}
return ret;
}
@ -251,7 +262,21 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
m_mouse_left_down = false;
return false;
}
else if (mouse_event.Dragging()) {
// Enable/Disable panning/rotating the 3D scene
// Ctrl is pressed or the mouse is not hovering a selected volume
bool unlock_dragging = mouse_event.CmdDown() || (m_hover_id == -1 && !m_parent.get_selection().contains_volume(m_parent.get_first_hover_volume_idx()));
// mode is not center selection or mouse is not hovering a center
unlock_dragging &= !mouse_event.ShiftDown() || (m_hover_id != SELECTION_1_ID && m_hover_id != SELECTION_2_ID && m_hover_id != POINT_ID);
return !unlock_dragging;
}
else if (mouse_event.LeftDown()) {
// let the event pass through to allow panning/rotating the 3D scene
if ((m_mode != EMode::CenterSelection && mouse_event.CmdDown()) ||
(m_mode == EMode::CenterSelection && m_hover_id != SELECTION_1_ID && m_hover_id != SELECTION_2_ID && m_hover_id != POINT_ID)) {
return false;
}
if (m_hover_id != -1) {
SelectedFeatures selected_features_old = m_selected_features;
m_mouse_left_down = true;
@ -263,10 +288,41 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
else if (m_hover_id == SELECTION_2_ID && m_selected_features.second.feature.has_value())
item = m_selected_features.second;
else {
item = {
(m_mode == EMode::ExtendedSelection) ? point_on_feature_type_as_string(m_curr_feature->get_type(), m_hover_id) : surface_feature_type_as_string(m_curr_feature->get_type()),
(m_mode == EMode::ExtendedSelection) ? Measure::SurfaceFeature(*m_curr_point_on_feature_position) : m_curr_feature
};
switch (m_mode)
{
case EMode::FeatureSelection:
{
item = { surface_feature_type_as_string(m_curr_feature->get_type()), m_curr_feature };
break;
}
case EMode::PointSelection:
{
item = { point_on_feature_type_as_string(m_curr_feature->get_type(), m_hover_id), Measure::SurfaceFeature(*m_curr_point_on_feature_position) };
break;
}
case EMode::CenterSelection:
{
Vec3d position;
switch (m_curr_feature->get_type())
{
case Measure::SurfaceFeatureType::Circle:
{
position = std::get<0>(m_curr_feature->get_circle());
break;
}
case Measure::SurfaceFeatureType::Edge:
{
assert(m_curr_feature->get_extra_point().has_value());
position = *m_curr_feature->get_extra_point();
break;
}
default: { assert(false); break; }
}
item = { center_on_feature_type_as_string(m_curr_feature->get_type()), Measure::SurfaceFeature(position) };
break;
}
}
}
return item;
};
@ -284,8 +340,14 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
m_selected_features.second.reset();
else {
m_selected_features.second = item;
if (m_mode == EMode::ExtendedSelection)
if (m_mode == EMode::PointSelection || m_mode == EMode::CenterSelection)
m_selection_raycasters.push_back(m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, SELECTION_2_ID, *m_sphere.mesh_raycaster));
if (m_mode == EMode::CenterSelection) {
// Fake ctrl up event to exit the center selection mode
gizmo_event(SLAGizmoEventType::CtrlUp, Vec2d::Zero(), true, false, false);
// increase counter to avoid that keeping the ctrl key pressed triggers a ctrl down event
m_ctrl_kar_filter.increase_count();
}
}
}
else {
@ -296,8 +358,14 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
else {
const SelectedFeatures::Item item = item_from_feature();
m_selected_features.first = item;
if (m_mode == EMode::ExtendedSelection)
if (m_mode == EMode::PointSelection || m_mode == EMode::CenterSelection)
m_selection_raycasters.push_back(m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, SELECTION_1_ID, *m_sphere.mesh_raycaster));
if (m_mode == EMode::CenterSelection) {
// Fake ctrl up event to exit the center selection mode
gizmo_event(SLAGizmoEventType::CtrlUp, Vec2d::Zero(), true, false, false);
// increase counter to avoid that keeping the ctrl key pressed triggers a ctrl down event
m_ctrl_kar_filter.increase_count();
}
}
if (m_selected_features != selected_features_old && m_selected_features.second.feature.has_value()) {
@ -310,6 +378,10 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
return true;
}
else
// if the mouse pointer is on any volume, filter out the event to prevent the user to move it
// equivalent tp: return (m_parent.get_first_hover_volume_idx() != -1);
return m_curr_feature.has_value();
// fix: prevent restart gizmo when reselect object
// take responsibility for left up
@ -326,10 +398,18 @@ bool GLGizmoMeasure::on_mouse(const wxMouseEvent &mouse_event)
// avoid closing the gizmo if the user clicks outside of any volume
return true;
}
else if (mouse_event.RightDown() && mouse_event.CmdDown()) {
m_selected_features.reset();
m_selection_raycasters.clear();
m_parent.request_extra_frame();
else if (mouse_event.RightDown()) {
// let the event pass through to allow panning/rotating the 3D scene
if ((m_mode != EMode::CenterSelection && mouse_event.CmdDown()) || (m_mode == EMode::CenterSelection && m_hover_id != SELECTION_1_ID && m_hover_id != SELECTION_2_ID)) {
std::cout << "RightDown -> false\n";
return false;
}
if (mouse_event.ShiftDown()) {
m_selected_features.reset();
m_selection_raycasters.clear();
m_parent.request_extra_frame();
}
}
else if (mouse_event.Leaving())
m_mouse_left_down = false;
@ -365,21 +445,50 @@ void GLGizmoMeasure::data_changed()
m_is_editing_distance_first_frame = true;
}
static bool feature_has_center(std::optional<Measure::SurfaceFeature> feature)
{
return feature.has_value() ?
(feature->get_type() == Measure::SurfaceFeatureType::Circle || (feature->get_type() == Measure::SurfaceFeatureType::Edge && feature->get_extra_point().has_value()))
: false;
}
bool GLGizmoMeasure::gizmo_event(SLAGizmoEventType action, const Vec2d& mouse_position, bool shift_down, bool alt_down, bool control_down)
{
if (action == SLAGizmoEventType::CtrlDown) {
auto activate_center_selection = [this, shift_down, control_down](SLAGizmoEventType action) {
bool ret = false;
switch (action)
{
case SLAGizmoEventType::CtrlDown: { ret = shift_down && feature_has_center(m_curr_feature); break; }
case SLAGizmoEventType::ShiftDown: { ret = control_down && feature_has_center(m_curr_feature); break; }
default: { break; }
}
return ret;
};
if (action == SLAGizmoEventType::ShiftDown) {
if (m_shift_kar_filter.is_first()) {
m_mode = activate_center_selection(SLAGizmoEventType::ShiftDown) ? EMode::CenterSelection : EMode::PointSelection;
disable_scene_raycasters();
}
m_shift_kar_filter.increase_count();
}
else if (action == SLAGizmoEventType::ShiftUp) {
m_shift_kar_filter.reset_count();
m_mode = EMode::FeatureSelection;
restore_scene_raycasters_state();
}
else if (action == SLAGizmoEventType::CtrlDown) {
if (m_ctrl_kar_filter.is_first()) {
if (m_curr_feature.has_value()) {
m_mode = EMode::ExtendedSelection;
if (activate_center_selection(SLAGizmoEventType::CtrlDown)) {
m_mode = EMode::CenterSelection;
disable_scene_raycasters();
}
}
m_ctrl_kar_filter.increase_count();
}
else if (action == SLAGizmoEventType::CtrlUp) {
m_ctrl_kar_filter.reset_count();
m_mode = EMode::BasicSelection;
m_mode = control_down ? EMode::PointSelection : EMode::FeatureSelection;
restore_scene_raycasters_state();
}
@ -396,14 +505,16 @@ void GLGizmoMeasure::on_set_state()
{
if (m_state == Off) {
m_ctrl_kar_filter.reset_count();
m_shift_kar_filter.reset_count();
m_curr_feature.reset();
m_curr_point_on_feature_position.reset();
restore_scene_raycasters_state();
m_editing_distance = false;
m_is_editing_distance_first_frame = true;
m_measuring.reset();
}
else {
m_mode = EMode::BasicSelection;
m_mode = EMode::FeatureSelection;
// store current state of scene raycaster for later use
m_scene_raycasters.clear();
auto scene_raycasters = m_parent.get_raycasters_for_picking(SceneRaycaster::EType::Volume);
@ -462,7 +573,7 @@ void GLGizmoMeasure::on_render()
Vec3f normal_on_model;
size_t model_facet_idx;
const bool mouse_on_object = m_c->raycaster()->raycasters().front()->unproject_on_mesh(m_mouse_pos, m_volume_matrix, camera, position_on_model, normal_on_model, nullptr, &model_facet_idx);
const bool is_hovering_on_locked_feature = m_mode == EMode::ExtendedSelection && m_hover_id != -1;
const bool is_hovering_on_feature = (m_mode == EMode::PointSelection || m_mode == EMode::CenterSelection) && m_hover_id != -1;
auto update_circle = [this, inv_zoom]() {
if (m_last_inv_zoom != inv_zoom || m_last_circle != m_curr_feature) {
@ -478,61 +589,75 @@ void GLGizmoMeasure::on_render()
return false;
};
if (m_mode == EMode::BasicSelection) {
std::optional<Measure::SurfaceFeature> curr_feature = mouse_on_object ? m_measuring->get_feature(model_facet_idx, position_on_model.cast<double>()) : std::nullopt;
m_curr_point_on_feature_position.reset();
if (m_curr_feature != curr_feature ||
(curr_feature.has_value() && curr_feature->get_type() == Measure::SurfaceFeatureType::Circle && (m_curr_feature != curr_feature || m_last_inv_zoom != inv_zoom))) {
if (m_mode == EMode::FeatureSelection || m_mode == EMode::PointSelection) {
if ((m_hover_id == SELECTION_1_ID && boost::algorithm::istarts_with(m_selected_features.first.source, _u8L("Center"))) ||
(m_hover_id == SELECTION_2_ID && boost::algorithm::istarts_with(m_selected_features.second.source, _u8L("Center")))) {
// Skip feature detection if hovering on a selected center
m_curr_feature.reset();
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, EDGE_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, PLANE_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, CIRCLE_ID);
m_raycasters.clear();
m_curr_feature = curr_feature;
if (!m_curr_feature.has_value())
return;
m_curr_point_on_feature_position.reset();
}
else {
std::optional<Measure::SurfaceFeature> curr_feature = mouse_on_object ? m_measuring->get_feature(model_facet_idx, position_on_model.cast<double>()) : std::nullopt;
if (m_curr_feature != curr_feature ||
(curr_feature.has_value() && curr_feature->get_type() == Measure::SurfaceFeatureType::Circle && (m_curr_feature != curr_feature || m_last_inv_zoom != inv_zoom))) {
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, EDGE_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, PLANE_ID);
m_parent.remove_raycasters_for_picking(SceneRaycaster::EType::Gizmo, CIRCLE_ID);
m_raycasters.clear();
m_curr_feature = curr_feature;
if (!m_curr_feature.has_value())
return;
switch (m_curr_feature->get_type()) {
default: { assert(false); break; }
case Measure::SurfaceFeatureType::Point:
{
m_raycasters.insert({ POINT_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID, *m_sphere.mesh_raycaster) });
break;
}
case Measure::SurfaceFeatureType::Edge:
{
m_raycasters.insert({ EDGE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, EDGE_ID, *m_cylinder.mesh_raycaster) });
if (m_curr_feature->get_extra_point().has_value())
switch (m_curr_feature->get_type()) {
default: { assert(false); break; }
case Measure::SurfaceFeatureType::Point:
{
m_raycasters.insert({ POINT_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID, *m_sphere.mesh_raycaster) });
break;
}
case Measure::SurfaceFeatureType::Circle:
{
update_circle();
m_raycasters.insert({ CIRCLE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, CIRCLE_ID, *m_circle.mesh_raycaster) });
m_raycasters.insert({ POINT_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID, *m_sphere.mesh_raycaster) });
break;
}
case Measure::SurfaceFeatureType::Plane:
{
const auto [idx, normal, point] = m_curr_feature->get_plane();
if (m_last_plane_idx != idx) {
m_last_plane_idx = idx;
const indexed_triangle_set its = (m_old_model_volume != nullptr) ? m_old_model_volume->mesh().its : m_old_model_object->volumes.front()->mesh().its;
const std::vector<std::vector<int>> planes_triangles = m_measuring->get_planes_triangle_indices();
GLModel::Geometry init_data = init_plane_data(its, planes_triangles, idx);
m_plane.reset();
m_plane.mesh_raycaster = std::make_unique<MeshRaycaster>(std::make_shared<const TriangleMesh>(init_data.get_as_indexed_triangle_set()));
m_plane.model.init_from(std::move(init_data));
break;
}
case Measure::SurfaceFeatureType::Edge:
{
m_raycasters.insert({ EDGE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, EDGE_ID, *m_cylinder.mesh_raycaster) });
if (m_curr_feature->get_extra_point().has_value())
m_raycasters.insert({ POINT_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID, *m_sphere.mesh_raycaster) });
break;
}
case Measure::SurfaceFeatureType::Circle:
{
update_circle();
m_raycasters.insert({ CIRCLE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, CIRCLE_ID, *m_circle.mesh_raycaster) });
m_raycasters.insert({ POINT_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, POINT_ID, *m_sphere.mesh_raycaster) });
break;
}
case Measure::SurfaceFeatureType::Plane:
{
const auto [idx, normal, point] = m_curr_feature->get_plane();
if (m_last_plane_idx != idx) {
m_last_plane_idx = idx;
const indexed_triangle_set its = (m_old_model_volume != nullptr) ? m_old_model_volume->mesh().its : m_old_model_object->volumes.front()->mesh().its;
const std::vector<std::vector<int>> planes_triangles = m_measuring->get_planes_triangle_indices();
GLModel::Geometry init_data = init_plane_data(its, planes_triangles, idx);
m_plane.reset();
m_plane.mesh_raycaster = std::make_unique<MeshRaycaster>(std::make_shared<const TriangleMesh>(init_data.get_as_indexed_triangle_set()));
m_plane.model.init_from(std::move(init_data));
}
m_raycasters.insert({ PLANE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, PLANE_ID, *m_plane.mesh_raycaster) });
break;
}
m_raycasters.insert({ PLANE_ID, m_parent.add_raycaster_for_picking(SceneRaycaster::EType::Gizmo, PLANE_ID, *m_plane.mesh_raycaster) });
break;
}
}
}
}
}
else if (is_hovering_on_locked_feature) {
if (m_mode != EMode::PointSelection)
m_curr_point_on_feature_position.reset();
else if (is_hovering_on_feature) {
auto position_on_feature = [this](int feature_type_id, const Camera& camera, std::function<Vec3f(const Vec3f&)> callback = nullptr) -> Vec3d {
auto it = m_raycasters.find(feature_type_id);
if (it != m_raycasters.end() && it->second != nullptr) {
@ -549,47 +674,49 @@ void GLGizmoMeasure::on_render()
return Vec3d::Zero();
};
switch (m_curr_feature->get_type())
{
default: { assert(false); break; }
case Measure::SurfaceFeatureType::Point:
{
m_curr_point_on_feature_position = m_curr_feature->get_point();
break;
}
case Measure::SurfaceFeatureType::Edge:
{
const std::optional<Vec3d> extra = m_curr_feature->get_extra_point();
if (extra.has_value() && m_hover_id == POINT_ID)
m_curr_point_on_feature_position = *extra;
else
m_curr_point_on_feature_position = m_volume_matrix.inverse() * position_on_feature(EDGE_ID, camera, [](const Vec3f& v) { return Vec3f(0.0f, 0.0f, v.z()); });
break;
}
case Measure::SurfaceFeatureType::Plane:
{
m_curr_point_on_feature_position = m_volume_matrix.inverse() * position_on_feature(PLANE_ID, camera);
break;
}
case Measure::SurfaceFeatureType::Circle:
{
const auto [center, radius, normal] = m_curr_feature->get_circle();
if (m_hover_id == POINT_ID)
m_curr_point_on_feature_position = center;
else {
const Vec3d world_pof = position_on_feature(CIRCLE_ID, camera, [](const Vec3f& v) { return v; });
const Eigen::Hyperplane<double, 3> plane(m_volume_matrix.matrix().block(0, 0, 3, 3).inverse().transpose()* normal, m_volume_matrix * center);
const Transform3d local_to_model_matrix = Geometry::translation_transform(center) * Eigen::Quaternion<double>::FromTwoVectors(Vec3d::UnitZ(), normal);
const Vec3d local_proj = local_to_model_matrix.inverse() * m_volume_matrix.inverse() * plane.projection(world_pof);
double angle = std::atan2(local_proj.y(), local_proj.x());
if (angle < 0.0)
angle += 2.0 * double(M_PI);
const Vec3d local_pos = radius * Vec3d(std::cos(angle), std::sin(angle), 0.0);
m_curr_point_on_feature_position = local_to_model_matrix * local_pos;
if (m_curr_feature.has_value()) {
switch (m_curr_feature->get_type())
{
default: { assert(false); break; }
case Measure::SurfaceFeatureType::Point:
{
m_curr_point_on_feature_position = m_curr_feature->get_point();
break;
}
case Measure::SurfaceFeatureType::Edge:
{
const std::optional<Vec3d> extra = m_curr_feature->get_extra_point();
if (extra.has_value() && m_hover_id == POINT_ID)
m_curr_point_on_feature_position = *extra;
else
m_curr_point_on_feature_position = m_volume_matrix.inverse() * position_on_feature(EDGE_ID, camera, [](const Vec3f& v) { return Vec3f(0.0f, 0.0f, v.z()); });
break;
}
case Measure::SurfaceFeatureType::Plane:
{
m_curr_point_on_feature_position = m_volume_matrix.inverse() * position_on_feature(PLANE_ID, camera);
break;
}
case Measure::SurfaceFeatureType::Circle:
{
const auto [center, radius, normal] = m_curr_feature->get_circle();
if (m_hover_id == POINT_ID)
m_curr_point_on_feature_position = center;
else {
const Vec3d world_pof = position_on_feature(CIRCLE_ID, camera, [](const Vec3f& v) { return v; });
const Eigen::Hyperplane<double, 3> plane(m_volume_matrix.matrix().block(0, 0, 3, 3).inverse().transpose() * normal, m_volume_matrix * center);
const Transform3d local_to_model_matrix = Geometry::translation_transform(center) * Eigen::Quaternion<double>::FromTwoVectors(Vec3d::UnitZ(), normal);
const Vec3d local_proj = local_to_model_matrix.inverse() * m_volume_matrix.inverse() * plane.projection(world_pof);
double angle = std::atan2(local_proj.y(), local_proj.x());
if (angle < 0.0)
angle += 2.0 * double(M_PI);
const Vec3d local_pos = radius * Vec3d(std::cos(angle), std::sin(angle), 0.0);
m_curr_point_on_feature_position = local_to_model_matrix * local_pos;
}
break;
}
}
break;
}
}
}
else {
@ -612,7 +739,6 @@ void GLGizmoMeasure::on_render()
return;
shader->start_using();
shader->set_uniform("emission_factor", 0.25f);
shader->set_uniform("projection_matrix", camera.get_projection_matrix());
glsafe(::glClear(GL_DEPTH_BUFFER_BIT));
@ -629,8 +755,13 @@ void GLGizmoMeasure::on_render()
shader->set_uniform("view_normal_matrix", view_normal_matrix);
};
auto render_feature = [this, set_matrix_uniforms](const Measure::SurfaceFeature& feature, const std::vector<ColorRGBA>& colors,
float inv_zoom, bool update_raycasters_transform) {
auto set_emission_uniform = [this, shader](const ColorRGBA& color, bool hover) {
shader->set_uniform("emission_factor", (color == m_parent.get_selection().get_first_volume()->render_color) ? 0.0f :
hover ? 0.5f : 0.25f);
};
auto render_feature = [this, set_matrix_uniforms, set_emission_uniform](const Measure::SurfaceFeature& feature, const std::vector<ColorRGBA>& colors,
float inv_zoom, bool hover, bool update_raycasters_transform) {
switch (feature.get_type())
{
default: { assert(false); break; }
@ -639,6 +770,7 @@ void GLGizmoMeasure::on_render()
const Vec3d position = TransformHelper::model_to_world(feature.get_point(), m_volume_matrix);
const Transform3d feature_matrix = Geometry::translation_transform(position) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(feature_matrix);
set_emission_uniform(colors.front(), hover);
m_sphere.model.set_color(colors.front());
m_sphere.model.render();
if (update_raycasters_transform) {
@ -652,32 +784,37 @@ void GLGizmoMeasure::on_render()
{
const auto& [center, radius, normal] = feature.get_circle();
// render center
const Vec3d center_world = TransformHelper::model_to_world(center, m_volume_matrix);
const Transform3d center_matrix = Geometry::translation_transform(center_world) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(center_matrix);
m_sphere.model.set_color(colors.front());
m_sphere.model.render();
if (update_raycasters_transform) {
const Vec3d center_world = TransformHelper::model_to_world(center, m_volume_matrix);
const Transform3d center_matrix = Geometry::translation_transform(center_world) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(center_matrix);
set_emission_uniform(colors.front(), hover);
m_sphere.model.set_color(colors.front());
m_sphere.model.render();
auto it = m_raycasters.find(POINT_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(center_matrix);
}
// render circle
const Transform3d circle_matrix = Transform3d::Identity();
set_matrix_uniforms(circle_matrix);
if (update_raycasters_transform) {
m_circle.model.set_color(colors.back());
m_circle.model.render();
auto it = m_raycasters.find(CIRCLE_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(circle_matrix);
}
else {
GLModel circle;
GLModel::Geometry circle_geometry = init_torus_data(64, 16, center.cast<float>(), float(radius), 5.0f * inv_zoom, normal.cast<float>(), m_volume_matrix.cast<float>());
circle.init_from(std::move(circle_geometry));
circle.set_color(colors.back());
circle.render();
if (m_mode != EMode::CenterSelection) {
const Transform3d circle_matrix = Transform3d::Identity();
set_matrix_uniforms(circle_matrix);
if (update_raycasters_transform) {
set_emission_uniform(colors.back(), hover);
m_circle.model.set_color(colors.back());
m_circle.model.render();
auto it = m_raycasters.find(CIRCLE_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(circle_matrix);
}
else {
GLModel circle;
GLModel::Geometry circle_geometry = init_torus_data(64, 16, center.cast<float>(), float(radius), 5.0f * inv_zoom, normal.cast<float>(), m_volume_matrix.cast<float>());
circle.init_from(std::move(circle_geometry));
set_emission_uniform(colors.back(), hover);
circle.set_color(colors.back());
circle.render();
}
}
break;
}
@ -685,32 +822,36 @@ void GLGizmoMeasure::on_render()
{
const auto& [from, to] = feature.get_edge();
// render extra point
const std::optional<Vec3d> extra = feature.get_extra_point();
if (extra.has_value()) {
const Vec3d extra_world = TransformHelper::model_to_world(*extra, m_volume_matrix);
const Transform3d point_matrix = Geometry::translation_transform(extra_world) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(point_matrix);
m_sphere.model.set_color(colors.front());
m_sphere.model.render();
if (update_raycasters_transform) {
if (update_raycasters_transform) {
const std::optional<Vec3d> extra = feature.get_extra_point();
if (extra.has_value()) {
const Vec3d extra_world = TransformHelper::model_to_world(*extra, m_volume_matrix);
const Transform3d point_matrix = Geometry::translation_transform(extra_world) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(point_matrix);
set_emission_uniform(colors.front(), hover);
m_sphere.model.set_color(colors.front());
m_sphere.model.render();
auto it = m_raycasters.find(POINT_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(point_matrix);
}
}
// render edge
const Vec3d from_world = TransformHelper::model_to_world(from, m_volume_matrix);
const Vec3d to_world = TransformHelper::model_to_world(to, m_volume_matrix);
const Transform3d edge_matrix = Geometry::translation_transform(from_world) *
Eigen::Quaternion<double>::FromTwoVectors(Vec3d::UnitZ(), to_world - from_world) *
Geometry::scale_transform({ (double)inv_zoom, (double)inv_zoom, (to_world - from_world).norm() });
set_matrix_uniforms(edge_matrix);
m_cylinder.model.set_color(colors.back());
m_cylinder.model.render();
if (update_raycasters_transform) {
auto it = m_raycasters.find(EDGE_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(edge_matrix);
if (m_mode != EMode::CenterSelection) {
const Vec3d from_world = TransformHelper::model_to_world(from, m_volume_matrix);
const Vec3d to_world = TransformHelper::model_to_world(to, m_volume_matrix);
const Transform3d edge_matrix = Geometry::translation_transform(from_world) *
Eigen::Quaternion<double>::FromTwoVectors(Vec3d::UnitZ(), to_world - from_world) *
Geometry::scale_transform({ (double)inv_zoom, (double)inv_zoom, (to_world - from_world).norm() });
set_matrix_uniforms(edge_matrix);
set_emission_uniform(colors.back(), hover);
m_cylinder.model.set_color(colors.back());
m_cylinder.model.render();
if (update_raycasters_transform) {
auto it = m_raycasters.find(EDGE_ID);
if (it != m_raycasters.end() && it->second != nullptr)
it->second->set_transform(edge_matrix);
}
}
break;
}
@ -719,6 +860,7 @@ void GLGizmoMeasure::on_render()
const auto& [idx, normal, pt] = feature.get_plane();
assert(idx < m_plane_models_cache.size());
set_matrix_uniforms(m_volume_matrix);
set_emission_uniform(colors.front(), hover);
m_plane_models_cache[idx].set_color(colors.front());
m_plane_models_cache[idx].render();
if (update_raycasters_transform) {
@ -732,19 +874,19 @@ void GLGizmoMeasure::on_render()
};
auto hover_selection_color = [this]() {
return saturate(!m_selected_features.first.feature.has_value() ? SELECTED_1ST_COLOR : SELECTED_2ND_COLOR, 1.5f);
return !m_selected_features.first.feature.has_value() ? SELECTED_1ST_COLOR : SELECTED_2ND_COLOR;
};
auto hovering_color = [this, hover_selection_color, &selection]() {
return (m_mode == EMode::ExtendedSelection) ? selection.get_first_volume()->render_color : hover_selection_color();
return (m_mode == EMode::PointSelection) ? selection.get_first_volume()->render_color : hover_selection_color();
};
if (m_curr_feature.has_value()) {
std::vector<ColorRGBA> colors;
if (m_selected_features.first.feature.has_value() && *m_curr_feature == *m_selected_features.first.feature)
colors.emplace_back(SELECTED_1ST_COLOR);
colors.emplace_back(hovering_color());
else if (m_selected_features.second.feature.has_value() && *m_curr_feature == *m_selected_features.second.feature)
colors.emplace_back(SELECTED_2ND_COLOR);
colors.emplace_back(hovering_color());
else {
switch (m_curr_feature->get_type())
{
@ -769,12 +911,12 @@ void GLGizmoMeasure::on_render()
}
}
render_feature(*m_curr_feature, colors, inv_zoom, true);
render_feature(*m_curr_feature, colors, inv_zoom, true, true);
}
if (m_selected_features.first.feature.has_value() && (!m_curr_feature.has_value() || *m_curr_feature != *m_selected_features.first.feature)) {
const std::vector<ColorRGBA> colors = { SELECTED_1ST_COLOR };
render_feature(*m_selected_features.first.feature, colors, inv_zoom, false);
render_feature(*m_selected_features.first.feature, colors, inv_zoom, m_hover_id == SELECTION_1_ID, false);
if (m_selected_features.first.feature->get_type() == Measure::SurfaceFeatureType::Point) {
auto it = std::find_if(m_selection_raycasters.begin(), m_selection_raycasters.end(),
[](std::shared_ptr<SceneRaycasterItem> item) { return SceneRaycaster::decode_id(SceneRaycaster::EType::Gizmo, item->get_id()) == SELECTION_1_ID; });
@ -784,7 +926,7 @@ void GLGizmoMeasure::on_render()
}
if (m_selected_features.second.feature.has_value() && (!m_curr_feature.has_value() || *m_curr_feature != *m_selected_features.second.feature)) {
const std::vector<ColorRGBA> colors = { SELECTED_2ND_COLOR };
render_feature(*m_selected_features.second.feature, colors, inv_zoom, false);
render_feature(*m_selected_features.second.feature, colors, inv_zoom, m_hover_id == SELECTION_2_ID, false);
if (m_selected_features.second.feature->get_type() == Measure::SurfaceFeatureType::Point) {
auto it = std::find_if(m_selection_raycasters.begin(), m_selection_raycasters.end(),
[](std::shared_ptr<SceneRaycasterItem> item) { return SceneRaycaster::decode_id(SceneRaycaster::EType::Gizmo, item->get_id()) == SELECTION_2_ID; });
@ -793,12 +935,14 @@ void GLGizmoMeasure::on_render()
}
}
if (is_hovering_on_locked_feature && m_curr_point_on_feature_position.has_value()) {
if (is_hovering_on_feature && m_curr_point_on_feature_position.has_value()) {
if (m_hover_id != POINT_ID) {
const Vec3d position = TransformHelper::model_to_world(*m_curr_point_on_feature_position, m_volume_matrix);
const Transform3d matrix = Geometry::translation_transform(position) * Geometry::scale_transform(inv_zoom);
set_matrix_uniforms(matrix);
m_sphere.model.set_color(hover_selection_color());
const ColorRGBA color = hover_selection_color();
set_emission_uniform(color, true);
m_sphere.model.set_color(color);
m_sphere.model.render();
}
}
@ -1338,12 +1482,15 @@ void GLGizmoMeasure::render_debug_dialog()
{
case Measure::SurfaceFeatureType::Point:
{
add_strings_row_to_table(*m_imgui, "m_pt1", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(item.feature->get_point()), ImGui::GetStyleColorVec4(ImGuiCol_Text));
const Vec3d position = m_volume_matrix * item.feature->get_point();
add_strings_row_to_table(*m_imgui, "m_pt1", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(position), ImGui::GetStyleColorVec4(ImGuiCol_Text));
break;
}
case Measure::SurfaceFeatureType::Edge:
{
auto [from, to] = item.feature->get_edge();
from = m_volume_matrix * from;
to = m_volume_matrix * to;
add_strings_row_to_table(*m_imgui, "m_pt1", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(from), ImGui::GetStyleColorVec4(ImGuiCol_Text));
add_strings_row_to_table(*m_imgui, "m_pt2", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(to), ImGui::GetStyleColorVec4(ImGuiCol_Text));
break;
@ -1351,6 +1498,8 @@ void GLGizmoMeasure::render_debug_dialog()
case Measure::SurfaceFeatureType::Plane:
{
auto [idx, normal, origin] = item.feature->get_plane();
origin = m_volume_matrix * origin;
normal = m_volume_matrix.matrix().block(0, 0, 3, 3).inverse().transpose() * normal;
add_strings_row_to_table(*m_imgui, "m_pt1", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(normal), ImGui::GetStyleColorVec4(ImGuiCol_Text));
add_strings_row_to_table(*m_imgui, "m_pt2", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(origin), ImGui::GetStyleColorVec4(ImGuiCol_Text));
add_strings_row_to_table(*m_imgui, "m_value", ImGuiWrapper::COL_ORANGE_LIGHT, format_double(idx), ImGui::GetStyleColorVec4(ImGuiCol_Text));
@ -1359,6 +1508,10 @@ void GLGizmoMeasure::render_debug_dialog()
case Measure::SurfaceFeatureType::Circle:
{
auto [center, radius, normal] = item.feature->get_circle();
const Vec3d on_circle = m_volume_matrix * (center + radius * Measure::get_orthogonal(normal, true));
center = m_volume_matrix * center;
normal = (m_volume_matrix.matrix().block(0, 0, 3, 3).inverse().transpose() * normal).normalized();
radius = (on_circle - center).norm();
add_strings_row_to_table(*m_imgui, "m_pt1", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(center), ImGui::GetStyleColorVec4(ImGuiCol_Text));
add_strings_row_to_table(*m_imgui, "m_pt2", ImGuiWrapper::COL_ORANGE_LIGHT, format_vec3(normal), ImGui::GetStyleColorVec4(ImGuiCol_Text));
add_strings_row_to_table(*m_imgui, "m_value", ImGuiWrapper::COL_ORANGE_LIGHT, format_double(radius), ImGui::GetStyleColorVec4(ImGuiCol_Text));
@ -1371,6 +1524,28 @@ void GLGizmoMeasure::render_debug_dialog()
};
m_imgui->begin(_L("Measure tool debug"), ImGuiWindowFlags_AlwaysAutoResize | ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoCollapse);
if (ImGui::BeginTable("Mode", 2)) {
std::string txt;
switch (m_mode)
{
case EMode::FeatureSelection: { txt = "Feature selection"; break; }
case EMode::PointSelection: { txt = "Point selection"; break; }
case EMode::CenterSelection: { txt = "Center selection"; break; }
default: { assert(false); break; }
}
add_strings_row_to_table(*m_imgui, "Mode", ImGuiWrapper::COL_ORANGE_LIGHT, txt, ImGui::GetStyleColorVec4(ImGuiCol_Text));
ImGui::EndTable();
}
ImGui::Separator();
if (ImGui::BeginTable("Hover", 2)) {
add_strings_row_to_table(*m_imgui, "Hover id", ImGuiWrapper::COL_ORANGE_LIGHT, std::to_string(m_hover_id), ImGui::GetStyleColorVec4(ImGuiCol_Text));
const std::string txt = m_curr_feature.has_value() ? surface_feature_type_as_string(m_curr_feature->get_type()) : "None";
add_strings_row_to_table(*m_imgui, "Current feature", ImGuiWrapper::COL_ORANGE_LIGHT, txt, ImGui::GetStyleColorVec4(ImGuiCol_Text));
ImGui::EndTable();
}
ImGui::Separator();
if (!m_selected_features.first.feature.has_value() && !m_selected_features.second.feature.has_value())
m_imgui->text("Empty selection");
else {
@ -1397,7 +1572,7 @@ void GLGizmoMeasure::render_debug_dialog()
void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit)
{
static std::optional<Measure::SurfaceFeature> last_feature;
static EMode last_mode = EMode::BasicSelection;
static EMode last_mode = EMode::FeatureSelection;
static SelectedFeatures last_selected_features;
static float last_y = 0.0f;
@ -1431,12 +1606,13 @@ void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit
std::string text;
ColorRGBA color;
if (m_selected_features.second.feature.has_value()) {
if (m_selected_features.second.feature == m_curr_feature && m_mode == EMode::BasicSelection)
if (m_selected_features.second.feature == m_curr_feature && m_mode == EMode::FeatureSelection)
text = _u8L("Unselect feature");
else if (m_hover_id == SELECTION_2_ID)
text = _u8L("Unselect point");
text = (m_mode == EMode::CenterSelection) ? _u8L("Unselect center") : _u8L("Unselect point");
else
text = (m_mode == EMode::BasicSelection) ? _u8L("Select feature") : _u8L("Select point");
text = (m_mode == EMode::PointSelection) ? _u8L("Select point") :
(m_mode == EMode::CenterSelection) ? _u8L("Select center") : _u8L("Select feature");
color = SELECTED_2ND_COLOR;
}
else {
@ -1444,11 +1620,12 @@ void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit
if (m_selected_features.first.feature == m_curr_feature)
text = _u8L("Unselect feature");
else if (m_hover_id == SELECTION_1_ID)
text = _u8L("Unselect point");
text = (m_mode == EMode::CenterSelection) ? _u8L("Unselect center") : _u8L("Unselect point");
color = SELECTED_1ST_COLOR;
}
if (text.empty()) {
text = (m_mode == EMode::BasicSelection) ? _u8L("Select feature") : _u8L("Select point");
text = (m_mode == EMode::PointSelection) ? _u8L("Select point") :
(m_mode == EMode::CenterSelection) ? _u8L("Select center") : _u8L("Select feature");
color = m_selected_features.first.feature.has_value() ? SELECTED_2ND_COLOR : SELECTED_1ST_COLOR;
}
}
@ -1462,18 +1639,23 @@ void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit
}
);
if (m_selected_features.first.feature.has_value()) {
add_strings_row_to_table(*m_imgui, CTRL_STR + "+" + _u8L("Right mouse button"), ImGuiWrapper::COL_ORANGE_LIGHT, _u8L("Restart selection"), ImGui::GetStyleColorVec4(ImGuiCol_Text));
if (m_mode == EMode::FeatureSelection && m_hover_id != -1) {
add_strings_row_to_table(*m_imgui, _u8L("Shift"), ImGuiWrapper::COL_ORANGE_LIGHT, _u8L("Enable point selection"), ImGui::GetStyleColorVec4(ImGuiCol_Text));
++row_count;
}
if (m_mode == EMode::BasicSelection && m_hover_id != -1) {
add_strings_row_to_table(*m_imgui, CTRL_STR, ImGuiWrapper::COL_ORANGE_LIGHT, _u8L("Enable point selection"), ImGui::GetStyleColorVec4(ImGuiCol_Text));
if (m_mode != EMode::CenterSelection && feature_has_center(m_curr_feature)) {
add_strings_row_to_table(*m_imgui, _u8L("Shift") + "+" + CTRL_STR, ImGuiWrapper::COL_ORANGE_LIGHT, _u8L("Enable center selection"), ImGui::GetStyleColorVec4(ImGuiCol_Text));
++row_count;
}
if (m_selected_features.first.feature.has_value()) {
add_strings_row_to_table(*m_imgui, _u8L("Shift") + "+" + _u8L("Right mouse button"), ImGuiWrapper::COL_ORANGE_LIGHT, _u8L("Restart selection"), ImGui::GetStyleColorVec4(ImGuiCol_Text));
++row_count;
}
// add dummy rows to keep dialog size fixed
for (unsigned int i = row_count; i < 3; ++i) {
for (unsigned int i = row_count; i < 4; ++i) {
add_strings_row_to_table(*m_imgui, " ", ImGuiWrapper::COL_ORANGE_LIGHT, " ", ImGui::GetStyleColorVec4(ImGuiCol_Text));
}
@ -1487,16 +1669,22 @@ void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit
//bool data_text_set = false;
//ImGui::Separator();
//if (feature_type != Measure::SurfaceFeatureType::Undef) {
// if (m_mode == EMode::BasicSelection) {
// if (m_mode == EMode::FeatureSelection) {
// m_imgui->text(surface_feature_type_as_string(feature_type));
// data_text_set = true;
// }
// else if (m_mode == EMode::ExtendedSelection) {
// else if (m_mode == EMode::PointSelection) {
// if (m_hover_id != -1 && m_curr_point_on_feature_position.has_value()) {
// m_imgui->text(point_on_feature_type_as_string(feature_type, m_hover_id));
// data_text_set = true;
// }
// }
// else if (m_mode == EMode::CenterSelection) {
// if (m_hover_id != -1 && m_curr_point_on_feature_position.has_value()) {
// m_imgui->text(center_on_feature_type_as_string(feature_type));
// data_text_set = true;
// }
// }
//}
//if (!data_text_set)
// m_imgui->text(_u8L("No feature"));
@ -1504,7 +1692,7 @@ void GLGizmoMeasure::on_render_input_window(float x, float y, float bottom_limit
//const unsigned int max_data_row_count = 3;
//unsigned int data_row_count = 0;
//if (ImGui::BeginTable("Data", 2)) {
// if (m_mode == EMode::BasicSelection) {
// if (m_mode == EMode::FeatureSelection) {
// switch (feature_type)
// {
// default: { break; }

View file

@ -23,8 +23,9 @@ class GLGizmoMeasure : public GLGizmoBase
{
enum class EMode : unsigned char
{
BasicSelection,
ExtendedSelection
FeatureSelection,
PointSelection,
CenterSelection
};
struct SelectedFeatures
@ -67,7 +68,7 @@ class GLGizmoMeasure : public GLGizmoBase
}
};
EMode m_mode{ EMode::BasicSelection };
EMode m_mode{ EMode::FeatureSelection };
Measure::MeasurementResult m_measurement_result;
std::unique_ptr<Measure::Measuring> m_measuring; // PIMPL
@ -114,6 +115,7 @@ class GLGizmoMeasure : public GLGizmoBase
Vec2d m_mouse_pos{ Vec2d::Zero() };
KeyAutoRepeatFilter m_ctrl_kar_filter;
KeyAutoRepeatFilter m_shift_kar_filter;
SelectedFeatures m_selected_features;
bool m_pending_scale{ false };

View file

@ -1284,7 +1284,8 @@ void GLGizmoSlaSupports::reslice_SLA_supports(bool postpone_error_messages) cons
bool GLGizmoSlaSupports::on_mouse(const wxMouseEvent &mouse_event){
if (mouse_event.Moving()) return false;
if (use_grabbers(mouse_event)) return true;
if (!mouse_event.ShiftDown() && !mouse_event.AltDown()
&& use_grabbers(mouse_event)) return true;
// wxCoord == int --> wx/types.h
Vec2i mouse_coord(mouse_event.GetX(), mouse_event.GetY());

View file

@ -26,6 +26,7 @@ enum class SLAGizmoEventType : unsigned char {
SelectAll,
CtrlDown,
CtrlUp,
ShiftDown,
ShiftUp,
AltUp,
ApplyChanges,

View file

@ -606,10 +606,8 @@ bool GLGizmosManager::on_key(wxKeyEvent& evt)
const int keyCode = evt.GetKeyCode();
bool processed = false;
if (evt.GetEventType() == wxEVT_KEY_UP)
{
if (m_current == SlaSupports || m_current == Hollow || m_current == Cut)
{
if (evt.GetEventType() == wxEVT_KEY_UP) {
if (m_current == SlaSupports || m_current == Hollow || m_current == Cut) {
GLGizmoBase* gizmo = get_current();
const bool is_editing = m_current == Hollow ? true : gizmo->is_in_editing_mode();
const bool is_rectangle_dragging = gizmo->is_selection_rectangle_dragging();
@ -625,18 +623,19 @@ bool GLGizmosManager::on_key(wxKeyEvent& evt)
processed = true;
}
}
else if (m_current == Measure && keyCode == WXK_CONTROL) {
gizmo_event(SLAGizmoEventType::CtrlUp, Vec2d::Zero(), false);
else if (m_current == Measure) {
if (keyCode == WXK_CONTROL)
gizmo_event(SLAGizmoEventType::CtrlUp, Vec2d::Zero(), evt.ShiftDown(), evt.AltDown(), evt.CmdDown());
else if (keyCode == WXK_SHIFT)
gizmo_event(SLAGizmoEventType::ShiftUp, Vec2d::Zero(), evt.ShiftDown(), evt.AltDown(), evt.CmdDown());
}
// if (processed)
// m_parent.set_cursor(GLCanvas3D::Standard);
}
else if (evt.GetEventType() == wxEVT_KEY_DOWN)
{
if ((m_current == SlaSupports) && ((keyCode == WXK_SHIFT) || (keyCode == WXK_ALT))
&& get_current()->is_in_editing_mode())
{
else if (evt.GetEventType() == wxEVT_KEY_DOWN) {
if (m_current == SlaSupports && (keyCode == WXK_SHIFT || keyCode == WXK_ALT)
&& get_current()->is_in_editing_mode()) {
// m_parent.set_cursor(GLCanvas3D::Cross);
processed = true;
}
@ -662,8 +661,11 @@ bool GLGizmosManager::on_key(wxKeyEvent& evt)
if (simplify != nullptr)
processed = simplify->on_esc_key_down();
}
else if (m_current == Measure && keyCode == WXK_CONTROL) {
gizmo_event(SLAGizmoEventType::CtrlDown, Vec2d::Zero(), true);
else if (m_current == Measure) {
if (keyCode == WXK_CONTROL)
gizmo_event(SLAGizmoEventType::CtrlDown, Vec2d::Zero(), evt.ShiftDown(), evt.AltDown(), evt.CmdDown());
else if (keyCode == WXK_SHIFT)
gizmo_event(SLAGizmoEventType::ShiftDown, Vec2d::Zero(), evt.ShiftDown(), evt.AltDown(), evt.CmdDown());
}
}

View file

@ -86,7 +86,7 @@ void read_used_binary(std::vector<std::string>& ids)
BOOST_LOG_TRIVIAL(warning) << "Failed to load to hints.cereal. File does not exists. " << path.string();
return;
}
boost::nowide::ifstream file(path.string());
boost::nowide::ifstream file(path.string(), std::ios::binary);
cereal::BinaryInputArchive archive(file);
HintsCerealData cd;
try

View file

@ -4880,12 +4880,12 @@ void Plater::priv::set_bed_shape(const Pointfs& shape, const double max_print_he
bool Plater::priv::can_delete() const
{
return !get_selection().is_empty() && !get_selection().is_wipe_tower();
return !get_selection().is_empty() && !get_selection().is_wipe_tower() && !sidebar->obj_list()->is_editing();
}
bool Plater::priv::can_delete_all() const
{
return !model.objects.empty();
return !model.objects.empty() && !sidebar->obj_list()->is_editing();
}
bool Plater::priv::can_fix_through_netfabb() const

View file

@ -228,35 +228,6 @@ int SceneRaycaster::base_id(EType type)
return -1;
}
#if ENABLE_RAYCAST_PICKING_DEBUG
size_t SceneRaycaster::active_beds_count() const
{
size_t count = 0;
for (const auto& item : m_bed) {
if (item->is_active()) ++count;
}
return count;
}
size_t SceneRaycaster::active_volumes_count() const
{
size_t count = 0;
for (const auto& item : m_volumes) {
if (item->is_active()) ++count;
}
return count;
}
size_t SceneRaycaster::active_gizmos_count() const
{
size_t count = 0;
for (const auto& item : m_gizmos) {
if (item->is_active()) ++count;
}
return count;
}
#endif // ENABLE_RAYCAST_PICKING_DEBUG
int SceneRaycaster::encode_id(EType type, int id) { return base_id(type) + id; }
int SceneRaycaster::decode_id(EType type, int id) { return id - base_id(type); }

View file

@ -1436,7 +1436,9 @@ void TabPrint::build()
optgroup = page->new_optgroup(L("Quality (slower slicing)"));
optgroup->append_single_option_line("extra_perimeters", category_path + "extra-perimeters-if-needed");
optgroup->append_single_option_line("extra_perimeters_on_overhangs", category_path + "extra-perimeters-on-overhangs");
optgroup->append_single_option_line("ensure_vertical_shell_thickness", category_path + "ensure-vertical-shell-thickness");
optgroup->append_single_option_line("avoid_curled_filament_during_travels", category_path + "avoid-curled-filament-during-travels");
optgroup->append_single_option_line("avoid_crossing_perimeters", category_path + "avoid-crossing-perimeters");
optgroup->append_single_option_line("avoid_crossing_perimeters_max_detour", category_path + "avoid_crossing_perimeters_max_detour");
optgroup->append_single_option_line("thin_walls", category_path + "detect-thin-walls");

View file

@ -31,6 +31,7 @@ add_executable(${_TEST_NAME}_tests
test_timeutils.cpp
test_indexed_triangle_set.cpp
test_astar.cpp
test_jump_point_search.cpp
../libnest2d/printer_parts.cpp
)

View file

@ -0,0 +1,35 @@
#include <catch2/catch.hpp>
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/JumpPointSearch.hpp"
using namespace Slic3r;
TEST_CASE("Test jump point search path finding", "[JumpPointSearch]")
{
Lines obstacles{};
obstacles.push_back(Line(Point::new_scale(0, 0), Point::new_scale(50, 50)));
obstacles.push_back(Line(Point::new_scale(0, 100), Point::new_scale(50, 50)));
obstacles.push_back(Line(Point::new_scale(0, 0), Point::new_scale(100, 0)));
obstacles.push_back(Line(Point::new_scale(0, 100), Point::new_scale(100, 100)));
obstacles.push_back(Line(Point::new_scale(25, -25), Point::new_scale(25, 125)));
JPSPathFinder jps;
jps.add_obstacles(obstacles);
Polyline path = jps.find_path(Point::new_scale(5, 50), Point::new_scale(100, 50));
path = jps.find_path(Point::new_scale(5, 50), Point::new_scale(150, 50));
path = jps.find_path(Point::new_scale(5, 50), Point::new_scale(25, 15));
path = jps.find_path(Point::new_scale(25, 25), Point::new_scale(125, 125));
// SECTION("Output is empty when source is also the destination") {
// bool found = astar::search_route(DummyTracer{}, 0, std::back_inserter(out));
// REQUIRE(out.empty());
// REQUIRE(found);
// }
// SECTION("Return false when there is no route to destination") {
// bool found = astar::search_route(DummyTracer{}, 1, std::back_inserter(out));
// REQUIRE(!found);
// REQUIRE(out.empty());
// }
}