Merge branch 'acp-voronoi'
Conflicts: xs/xsp/my.map
This commit is contained in:
commit
3ff613d166
18 changed files with 509 additions and 18 deletions
|
@ -75,8 +75,8 @@ sub change_layer {
|
||||||
$self->_layer_islands($layer->islands);
|
$self->_layer_islands($layer->islands);
|
||||||
$self->_upper_layer_islands($layer->upper_layer ? $layer->upper_layer->islands : []);
|
$self->_upper_layer_islands($layer->upper_layer ? $layer->upper_layer->islands : []);
|
||||||
if ($self->config->avoid_crossing_perimeters) {
|
if ($self->config->avoid_crossing_perimeters) {
|
||||||
$self->layer_mp(Slic3r::GCode::MotionPlanner->new(
|
$self->layer_mp(Slic3r::MotionPlanner->new(
|
||||||
islands => union_ex([ map @$_, @{$layer->slices} ], 1),
|
union_ex([ map @$_, @{$layer->slices} ], 1),
|
||||||
));
|
));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -158,11 +158,6 @@ sub _arrange {
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
sub has_objects_with_no_instances {
|
|
||||||
my ($self) = @_;
|
|
||||||
return (first { !defined $_->instances } @{$self->objects}) ? 1 : 0;
|
|
||||||
}
|
|
||||||
|
|
||||||
# makes sure all objects have at least one instance
|
# makes sure all objects have at least one instance
|
||||||
sub add_default_instances {
|
sub add_default_instances {
|
||||||
my ($self) = @_;
|
my ($self) = @_;
|
||||||
|
|
|
@ -883,10 +883,7 @@ sub write_gcode {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
$gcodegen->external_mp(Slic3r::GCode::MotionPlanner->new(
|
$gcodegen->external_mp(Slic3r::MotionPlanner->new(union_ex([ map @$_, @islands ])));
|
||||||
islands => union_ex([ map @$_, @islands ]),
|
|
||||||
internal => 0,
|
|
||||||
));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
# calculate wiping points if needed
|
# calculate wiping points if needed
|
||||||
|
|
|
@ -1677,6 +1677,8 @@ src/Line.cpp
|
||||||
src/Line.hpp
|
src/Line.hpp
|
||||||
src/Model.cpp
|
src/Model.cpp
|
||||||
src/Model.hpp
|
src/Model.hpp
|
||||||
|
src/MotionPlanner.cpp
|
||||||
|
src/MotionPlanner.hpp
|
||||||
src/MultiPoint.cpp
|
src/MultiPoint.cpp
|
||||||
src/MultiPoint.hpp
|
src/MultiPoint.hpp
|
||||||
src/myinit.h
|
src/myinit.h
|
||||||
|
@ -1735,6 +1737,7 @@ t/14_geometry.t
|
||||||
t/15_config.t
|
t/15_config.t
|
||||||
t/16_flow.t
|
t/16_flow.t
|
||||||
t/17_boundingbox.t
|
t/17_boundingbox.t
|
||||||
|
t/18_motionplanner.t
|
||||||
t/19_model.t
|
t/19_model.t
|
||||||
t/20_print.t
|
t/20_print.t
|
||||||
xsp/BoundingBox.xsp
|
xsp/BoundingBox.xsp
|
||||||
|
@ -1751,6 +1754,7 @@ xsp/Geometry.xsp
|
||||||
xsp/Layer.xsp
|
xsp/Layer.xsp
|
||||||
xsp/Line.xsp
|
xsp/Line.xsp
|
||||||
xsp/Model.xsp
|
xsp/Model.xsp
|
||||||
|
xsp/MotionPlanner.xsp
|
||||||
xsp/my.map
|
xsp/my.map
|
||||||
xsp/mytype.map
|
xsp/mytype.map
|
||||||
xsp/PlaceholderParser.xsp
|
xsp/PlaceholderParser.xsp
|
||||||
|
|
|
@ -59,6 +59,14 @@ BoundingBox::polygon(Polygon* polygon) const
|
||||||
polygon->points[3].y = this->max.y;
|
polygon->points[3].y = this->max.y;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Polygon
|
||||||
|
BoundingBox::polygon() const
|
||||||
|
{
|
||||||
|
Polygon p;
|
||||||
|
this->polygon(&p);
|
||||||
|
return p;
|
||||||
|
}
|
||||||
|
|
||||||
template <class PointClass> void
|
template <class PointClass> void
|
||||||
BoundingBoxBase<PointClass>::scale(double factor)
|
BoundingBoxBase<PointClass>::scale(double factor)
|
||||||
{
|
{
|
||||||
|
|
|
@ -48,6 +48,7 @@ class BoundingBox : public BoundingBoxBase<Point>
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
void polygon(Polygon* polygon) const;
|
void polygon(Polygon* polygon) const;
|
||||||
|
Polygon polygon() const;
|
||||||
|
|
||||||
BoundingBox() {};
|
BoundingBox() {};
|
||||||
BoundingBox(const Points &points) : BoundingBoxBase<Point>(points) {};
|
BoundingBox(const Points &points) : BoundingBoxBase<Point>(points) {};
|
||||||
|
|
|
@ -84,11 +84,14 @@ ExPolygon::is_valid() const
|
||||||
bool
|
bool
|
||||||
ExPolygon::contains_line(const Line &line) const
|
ExPolygon::contains_line(const Line &line) const
|
||||||
{
|
{
|
||||||
Polylines pl;
|
return this->contains_polyline(line);
|
||||||
pl.push_back(line);
|
}
|
||||||
|
|
||||||
|
bool
|
||||||
|
ExPolygon::contains_polyline(const Polyline &polyline) const
|
||||||
|
{
|
||||||
Polylines pl_out;
|
Polylines pl_out;
|
||||||
diff(pl, *this, pl_out);
|
diff((Polylines)polyline, *this, pl_out);
|
||||||
return pl_out.empty();
|
return pl_out.empty();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -2,6 +2,7 @@
|
||||||
#define slic3r_ExPolygon_hpp_
|
#define slic3r_ExPolygon_hpp_
|
||||||
|
|
||||||
#include "Polygon.hpp"
|
#include "Polygon.hpp"
|
||||||
|
#include "Polyline.hpp"
|
||||||
#include <vector>
|
#include <vector>
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
|
@ -22,6 +23,7 @@ class ExPolygon
|
||||||
double area() const;
|
double area() const;
|
||||||
bool is_valid() const;
|
bool is_valid() const;
|
||||||
bool contains_line(const Line &line) const;
|
bool contains_line(const Line &line) const;
|
||||||
|
bool contains_polyline(const Polyline &polyline) const;
|
||||||
bool contains_point(const Point &point) const;
|
bool contains_point(const Point &point) const;
|
||||||
Polygons simplify_p(double tolerance) const;
|
Polygons simplify_p(double tolerance) const;
|
||||||
ExPolygons simplify(double tolerance) const;
|
ExPolygons simplify(double tolerance) const;
|
||||||
|
|
|
@ -3,6 +3,17 @@
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
|
|
||||||
|
ExPolygonCollection::operator Points() const
|
||||||
|
{
|
||||||
|
Points points;
|
||||||
|
Polygons pp = *this;
|
||||||
|
for (Polygons::const_iterator poly = pp.begin(); poly != pp.end(); ++poly) {
|
||||||
|
for (Points::const_iterator point = poly->points.begin(); point != poly->points.end(); ++point)
|
||||||
|
points.push_back(*point);
|
||||||
|
}
|
||||||
|
return points;
|
||||||
|
}
|
||||||
|
|
||||||
ExPolygonCollection::operator Polygons() const
|
ExPolygonCollection::operator Polygons() const
|
||||||
{
|
{
|
||||||
Polygons polygons;
|
Polygons polygons;
|
||||||
|
@ -15,6 +26,11 @@ ExPolygonCollection::operator Polygons() const
|
||||||
return polygons;
|
return polygons;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
ExPolygonCollection::operator ExPolygons&()
|
||||||
|
{
|
||||||
|
return this->expolygons;
|
||||||
|
}
|
||||||
|
|
||||||
void
|
void
|
||||||
ExPolygonCollection::scale(double factor)
|
ExPolygonCollection::scale(double factor)
|
||||||
{
|
{
|
||||||
|
|
|
@ -6,11 +6,19 @@
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
|
|
||||||
|
class ExPolygonCollection;
|
||||||
|
typedef std::vector<ExPolygonCollection> ExPolygonCollections;
|
||||||
|
|
||||||
class ExPolygonCollection
|
class ExPolygonCollection
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
ExPolygons expolygons;
|
ExPolygons expolygons;
|
||||||
|
|
||||||
|
ExPolygonCollection() {};
|
||||||
|
ExPolygonCollection(const ExPolygons &expolygons) : expolygons(expolygons) {};
|
||||||
|
operator Points() const;
|
||||||
operator Polygons() const;
|
operator Polygons() const;
|
||||||
|
operator ExPolygons&();
|
||||||
void scale(double factor);
|
void scale(double factor);
|
||||||
void translate(double x, double y);
|
void translate(double x, double y);
|
||||||
void rotate(double angle, const Point ¢er);
|
void rotate(double angle, const Point ¢er);
|
||||||
|
|
278
xs/src/MotionPlanner.cpp
Normal file
278
xs/src/MotionPlanner.cpp
Normal file
|
@ -0,0 +1,278 @@
|
||||||
|
#include "BoundingBox.hpp"
|
||||||
|
#include "MotionPlanner.hpp"
|
||||||
|
#include <limits> // for numeric_limits
|
||||||
|
|
||||||
|
#include "boost/polygon/voronoi.hpp"
|
||||||
|
using boost::polygon::voronoi_builder;
|
||||||
|
using boost::polygon::voronoi_diagram;
|
||||||
|
|
||||||
|
namespace Slic3r {
|
||||||
|
|
||||||
|
MotionPlanner::MotionPlanner(const ExPolygons &islands)
|
||||||
|
: islands(islands), initialized(false)
|
||||||
|
{}
|
||||||
|
|
||||||
|
MotionPlanner::~MotionPlanner()
|
||||||
|
{
|
||||||
|
for (std::vector<MotionPlannerGraph*>::iterator graph = this->graphs.begin(); graph != this->graphs.end(); ++graph)
|
||||||
|
delete *graph;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
MotionPlanner::initialize()
|
||||||
|
{
|
||||||
|
if (this->initialized) return;
|
||||||
|
|
||||||
|
ExPolygons expp;
|
||||||
|
for (ExPolygons::const_iterator island = this->islands.begin(); island != this->islands.end(); ++island) {
|
||||||
|
island->simplify(SCALED_EPSILON, expp);
|
||||||
|
}
|
||||||
|
this->islands = expp;
|
||||||
|
|
||||||
|
// loop through islands in order to create inner expolygons and collect their contours
|
||||||
|
this->inner.reserve(this->islands.size());
|
||||||
|
Polygons outer_holes;
|
||||||
|
for (ExPolygons::const_iterator island = this->islands.begin(); island != this->islands.end(); ++island) {
|
||||||
|
this->inner.push_back(ExPolygonCollection());
|
||||||
|
offset_ex(*island, this->inner.back(), -MP_INNER_MARGIN);
|
||||||
|
|
||||||
|
outer_holes.push_back(island->contour);
|
||||||
|
}
|
||||||
|
|
||||||
|
// grow island contours in order to prepare holes of the outer environment
|
||||||
|
// This is actually wrong because it might merge contours that are close,
|
||||||
|
// thus confusing the island check in shortest_path() below
|
||||||
|
//offset(outer_holes, outer_holes, +MP_OUTER_MARGIN);
|
||||||
|
|
||||||
|
// generate outer contour as bounding box of everything
|
||||||
|
Points points;
|
||||||
|
for (Polygons::const_iterator contour = outer_holes.begin(); contour != outer_holes.end(); ++contour)
|
||||||
|
points.insert(points.end(), contour->points.begin(), contour->points.end());
|
||||||
|
BoundingBox bb(points);
|
||||||
|
|
||||||
|
// grow outer contour
|
||||||
|
Polygons contour;
|
||||||
|
offset(bb.polygon(), contour, +MP_OUTER_MARGIN);
|
||||||
|
assert(contour.size() == 1);
|
||||||
|
|
||||||
|
// make expolygon for outer environment
|
||||||
|
ExPolygons outer;
|
||||||
|
diff(contour, outer_holes, outer);
|
||||||
|
assert(outer.size() == 1);
|
||||||
|
this->outer = outer.front();
|
||||||
|
|
||||||
|
this->graphs.resize(this->islands.size() + 1, NULL);
|
||||||
|
this->initialized = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
MotionPlanner::shortest_path(const Point &from, const Point &to, Polyline* polyline)
|
||||||
|
{
|
||||||
|
if (!this->initialized) this->initialize();
|
||||||
|
|
||||||
|
// Are both points in the same island?
|
||||||
|
int island_idx = -1;
|
||||||
|
for (ExPolygons::const_iterator island = this->islands.begin(); island != this->islands.end(); ++island) {
|
||||||
|
if (island->contains_point(from) && island->contains_point(to)) {
|
||||||
|
// since both points are in the same island, is a direct move possible?
|
||||||
|
// if so, we avoid generating the visibility environment
|
||||||
|
if (island->contains_line(Line(from, to))) {
|
||||||
|
polyline->points.push_back(from);
|
||||||
|
polyline->points.push_back(to);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
island_idx = island - this->islands.begin();
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Now check whether points are inside the environment.
|
||||||
|
Point inner_from = from;
|
||||||
|
Point inner_to = to;
|
||||||
|
bool from_is_inside, to_is_inside;
|
||||||
|
if (island_idx == -1) {
|
||||||
|
if (!(from_is_inside = this->outer.contains_point(from))) {
|
||||||
|
// Find the closest inner point to start from.
|
||||||
|
from.nearest_point(this->outer, &inner_from);
|
||||||
|
}
|
||||||
|
if (!(to_is_inside = this->outer.contains_point(to))) {
|
||||||
|
// Find the closest inner point to start from.
|
||||||
|
to.nearest_point(this->outer, &inner_to);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (!(from_is_inside = this->inner[island_idx].contains_point(from))) {
|
||||||
|
// Find the closest inner point to start from.
|
||||||
|
from.nearest_point(this->inner[island_idx], &inner_from);
|
||||||
|
}
|
||||||
|
if (!(to_is_inside = this->inner[island_idx].contains_point(to))) {
|
||||||
|
// Find the closest inner point to start from.
|
||||||
|
to.nearest_point(this->inner[island_idx], &inner_to);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// perform actual path search
|
||||||
|
MotionPlannerGraph* graph = this->init_graph(island_idx);
|
||||||
|
graph->shortest_path(graph->find_node(inner_from), graph->find_node(inner_to), polyline);
|
||||||
|
|
||||||
|
polyline->points.insert(polyline->points.begin(), from);
|
||||||
|
polyline->points.push_back(to);
|
||||||
|
}
|
||||||
|
|
||||||
|
MotionPlannerGraph*
|
||||||
|
MotionPlanner::init_graph(int island_idx)
|
||||||
|
{
|
||||||
|
if (this->graphs[island_idx + 1] == NULL) {
|
||||||
|
Polygons pp;
|
||||||
|
if (island_idx == -1) {
|
||||||
|
pp = this->outer;
|
||||||
|
} else {
|
||||||
|
pp = this->inner[island_idx];
|
||||||
|
}
|
||||||
|
|
||||||
|
MotionPlannerGraph* graph = this->graphs[island_idx + 1] = new MotionPlannerGraph();
|
||||||
|
|
||||||
|
// add polygon boundaries as edges
|
||||||
|
size_t node_idx = 0;
|
||||||
|
Lines lines;
|
||||||
|
for (Polygons::const_iterator polygon = pp.begin(); polygon != pp.end(); ++polygon) {
|
||||||
|
graph->nodes.push_back(polygon->points.back());
|
||||||
|
node_idx++;
|
||||||
|
for (Points::const_iterator p = polygon->points.begin(); p != polygon->points.end(); ++p) {
|
||||||
|
graph->nodes.push_back(*p);
|
||||||
|
double dist = graph->nodes[node_idx-1].distance_to(*p);
|
||||||
|
graph->add_edge(node_idx-1, node_idx, dist);
|
||||||
|
graph->add_edge(node_idx, node_idx-1, dist);
|
||||||
|
node_idx++;
|
||||||
|
}
|
||||||
|
polygon->lines(&lines);
|
||||||
|
}
|
||||||
|
|
||||||
|
// add Voronoi edges as internal edges
|
||||||
|
{
|
||||||
|
typedef voronoi_diagram<double> VD;
|
||||||
|
typedef std::map<const VD::vertex_type*,size_t> t_vd_vertices;
|
||||||
|
VD vd;
|
||||||
|
t_vd_vertices vd_vertices;
|
||||||
|
|
||||||
|
boost::polygon::construct_voronoi(lines.begin(), lines.end(), &vd);
|
||||||
|
for (VD::const_edge_iterator edge = vd.edges().begin(); edge != vd.edges().end(); ++edge) {
|
||||||
|
if (edge->is_infinite()) continue;
|
||||||
|
|
||||||
|
const VD::vertex_type* v0 = edge->vertex0();
|
||||||
|
const VD::vertex_type* v1 = edge->vertex1();
|
||||||
|
Point p0 = Point(v0->x(), v0->y());
|
||||||
|
Point p1 = Point(v1->x(), v1->y());
|
||||||
|
// contains_point() should probably be faster than contains_line(),
|
||||||
|
// and should it fail on any boundary points it's not a big problem
|
||||||
|
if (island_idx == -1) {
|
||||||
|
if (!this->outer.contains_point(p0) || !this->outer.contains_point(p1)) continue;
|
||||||
|
} else {
|
||||||
|
if (!this->inner[island_idx].contains_point(p0) || !this->inner[island_idx].contains_point(p1)) continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
t_vd_vertices::const_iterator i_v0 = vd_vertices.find(v0);
|
||||||
|
size_t v0_idx;
|
||||||
|
if (i_v0 == vd_vertices.end()) {
|
||||||
|
graph->nodes.push_back(p0);
|
||||||
|
v0_idx = node_idx;
|
||||||
|
vd_vertices[v0] = node_idx;
|
||||||
|
node_idx++;
|
||||||
|
} else {
|
||||||
|
v0_idx = i_v0->second;
|
||||||
|
}
|
||||||
|
|
||||||
|
t_vd_vertices::const_iterator i_v1 = vd_vertices.find(v1);
|
||||||
|
size_t v1_idx;
|
||||||
|
if (i_v1 == vd_vertices.end()) {
|
||||||
|
graph->nodes.push_back(p1);
|
||||||
|
v1_idx = node_idx;
|
||||||
|
vd_vertices[v1] = node_idx;
|
||||||
|
node_idx++;
|
||||||
|
} else {
|
||||||
|
v1_idx = i_v1->second;
|
||||||
|
}
|
||||||
|
|
||||||
|
double dist = graph->nodes[v0_idx].distance_to(graph->nodes[v1_idx]);
|
||||||
|
graph->add_edge(v0_idx, v1_idx, dist);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return graph;
|
||||||
|
}
|
||||||
|
return this->graphs[island_idx + 1];
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
MotionPlannerGraph::add_edge(size_t from, size_t to, double weight)
|
||||||
|
{
|
||||||
|
// extend adjacency list until this start node
|
||||||
|
if (this->adjacency_list.size() < from+1)
|
||||||
|
this->adjacency_list.resize(from+1);
|
||||||
|
|
||||||
|
this->adjacency_list[from].push_back(neighbor(to, weight));
|
||||||
|
}
|
||||||
|
|
||||||
|
size_t
|
||||||
|
MotionPlannerGraph::find_node(const Point &point) const
|
||||||
|
{
|
||||||
|
/*
|
||||||
|
for (Points::const_iterator p = this->nodes.begin(); p != this->nodes.end(); ++p) {
|
||||||
|
if (p->coincides_with(point)) return p - this->nodes.begin();
|
||||||
|
}
|
||||||
|
*/
|
||||||
|
return point.nearest_point_index(this->nodes);
|
||||||
|
}
|
||||||
|
|
||||||
|
void
|
||||||
|
MotionPlannerGraph::shortest_path(size_t from, size_t to, Polyline* polyline)
|
||||||
|
{
|
||||||
|
const weight_t max_weight = std::numeric_limits<weight_t>::infinity();
|
||||||
|
|
||||||
|
std::vector<weight_t> min_distance;
|
||||||
|
std::vector<node_t> previous;
|
||||||
|
{
|
||||||
|
int n = this->adjacency_list.size();
|
||||||
|
min_distance.clear();
|
||||||
|
min_distance.resize(n, max_weight);
|
||||||
|
min_distance[from] = 0;
|
||||||
|
previous.clear();
|
||||||
|
previous.resize(n, -1);
|
||||||
|
std::set<std::pair<weight_t, node_t> > vertex_queue;
|
||||||
|
vertex_queue.insert(std::make_pair(min_distance[from], from));
|
||||||
|
|
||||||
|
while (!vertex_queue.empty())
|
||||||
|
{
|
||||||
|
weight_t dist = vertex_queue.begin()->first;
|
||||||
|
node_t u = vertex_queue.begin()->second;
|
||||||
|
vertex_queue.erase(vertex_queue.begin());
|
||||||
|
|
||||||
|
// Visit each edge exiting u
|
||||||
|
const std::vector<neighbor> &neighbors = this->adjacency_list[u];
|
||||||
|
for (std::vector<neighbor>::const_iterator neighbor_iter = neighbors.begin();
|
||||||
|
neighbor_iter != neighbors.end();
|
||||||
|
neighbor_iter++)
|
||||||
|
{
|
||||||
|
node_t v = neighbor_iter->target;
|
||||||
|
weight_t weight = neighbor_iter->weight;
|
||||||
|
weight_t distance_through_u = dist + weight;
|
||||||
|
if (distance_through_u < min_distance[v]) {
|
||||||
|
vertex_queue.erase(std::make_pair(min_distance[v], v));
|
||||||
|
min_distance[v] = distance_through_u;
|
||||||
|
previous[v] = u;
|
||||||
|
vertex_queue.insert(std::make_pair(min_distance[v], v));
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (node_t vertex = to; vertex != -1; vertex = previous[vertex])
|
||||||
|
polyline->points.push_back(this->nodes[vertex]);
|
||||||
|
polyline->reverse();
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SLIC3RXS
|
||||||
|
REGISTER_CLASS(MotionPlanner, "MotionPlanner");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
}
|
61
xs/src/MotionPlanner.hpp
Normal file
61
xs/src/MotionPlanner.hpp
Normal file
|
@ -0,0 +1,61 @@
|
||||||
|
#ifndef slic3r_MotionPlanner_hpp_
|
||||||
|
#define slic3r_MotionPlanner_hpp_
|
||||||
|
|
||||||
|
#include <myinit.h>
|
||||||
|
#include "ClipperUtils.hpp"
|
||||||
|
#include "ExPolygonCollection.hpp"
|
||||||
|
#include "Polyline.hpp"
|
||||||
|
#include <map>
|
||||||
|
#include <utility>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
#define MP_INNER_MARGIN scale_(1.0)
|
||||||
|
#define MP_OUTER_MARGIN scale_(2.0)
|
||||||
|
|
||||||
|
namespace Slic3r {
|
||||||
|
|
||||||
|
class MotionPlannerGraph;
|
||||||
|
|
||||||
|
class MotionPlanner
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
MotionPlanner(const ExPolygons &islands);
|
||||||
|
~MotionPlanner();
|
||||||
|
void shortest_path(const Point &from, const Point &to, Polyline* polyline);
|
||||||
|
|
||||||
|
private:
|
||||||
|
ExPolygons islands;
|
||||||
|
bool initialized;
|
||||||
|
ExPolygon outer;
|
||||||
|
ExPolygonCollections inner;
|
||||||
|
std::vector<MotionPlannerGraph*> graphs;
|
||||||
|
|
||||||
|
void initialize();
|
||||||
|
MotionPlannerGraph* init_graph(int island_idx);
|
||||||
|
};
|
||||||
|
|
||||||
|
class MotionPlannerGraph
|
||||||
|
{
|
||||||
|
private:
|
||||||
|
typedef size_t node_t;
|
||||||
|
typedef double weight_t;
|
||||||
|
struct neighbor {
|
||||||
|
node_t target;
|
||||||
|
weight_t weight;
|
||||||
|
neighbor(node_t arg_target, weight_t arg_weight)
|
||||||
|
: target(arg_target), weight(arg_weight) { }
|
||||||
|
};
|
||||||
|
typedef std::vector< std::vector<neighbor> > adjacency_list_t;
|
||||||
|
adjacency_list_t adjacency_list;
|
||||||
|
|
||||||
|
public:
|
||||||
|
Points nodes;
|
||||||
|
//std::map<std::pair<size_t,size_t>, double> edges;
|
||||||
|
void add_edge(size_t from, size_t to, double weight);
|
||||||
|
size_t find_node(const Point &point) const;
|
||||||
|
void shortest_path(size_t from, size_t to, Polyline* polyline);
|
||||||
|
};
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
|
@ -30,9 +30,11 @@ Lines
|
||||||
Polyline::lines() const
|
Polyline::lines() const
|
||||||
{
|
{
|
||||||
Lines lines;
|
Lines lines;
|
||||||
lines.reserve(this->points.size() - 1);
|
if (this->points.size() >= 2) {
|
||||||
for (Points::const_iterator it = this->points.begin(); it != this->points.end()-1; ++it) {
|
lines.reserve(this->points.size() - 1);
|
||||||
lines.push_back(Line(*it, *(it + 1)));
|
for (Points::const_iterator it = this->points.begin(); it != this->points.end()-1; ++it) {
|
||||||
|
lines.push_back(Line(*it, *(it + 1)));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return lines;
|
return lines;
|
||||||
}
|
}
|
||||||
|
|
94
xs/t/18_motionplanner.t
Normal file
94
xs/t/18_motionplanner.t
Normal file
|
@ -0,0 +1,94 @@
|
||||||
|
#!/usr/bin/perl
|
||||||
|
|
||||||
|
use strict;
|
||||||
|
use warnings;
|
||||||
|
|
||||||
|
BEGIN {
|
||||||
|
use FindBin;
|
||||||
|
use lib "$FindBin::Bin/../../lib";
|
||||||
|
}
|
||||||
|
|
||||||
|
use Slic3r::XS;
|
||||||
|
use Test::More tests => 22;
|
||||||
|
|
||||||
|
my $square = Slic3r::Polygon->new( # ccw
|
||||||
|
[100, 100],
|
||||||
|
[200, 100],
|
||||||
|
[200, 200],
|
||||||
|
[100, 200],
|
||||||
|
);
|
||||||
|
my $hole_in_square = Slic3r::Polygon->new( # cw
|
||||||
|
[140, 140],
|
||||||
|
[140, 160],
|
||||||
|
[160, 160],
|
||||||
|
[160, 140],
|
||||||
|
);
|
||||||
|
$_->scale(1/0.000001) for $square, $hole_in_square;
|
||||||
|
|
||||||
|
my $expolygon = Slic3r::ExPolygon->new($square, $hole_in_square);
|
||||||
|
|
||||||
|
{
|
||||||
|
my $mp = Slic3r::MotionPlanner->new([ $expolygon ]);
|
||||||
|
isa_ok $mp, 'Slic3r::MotionPlanner';
|
||||||
|
|
||||||
|
my $from = Slic3r::Point->new(120, 120);
|
||||||
|
my $to = Slic3r::Point->new(180,180);
|
||||||
|
$_->scale(1/0.000001) for $from, $to;
|
||||||
|
my $path = $mp->shortest_path($from, $to);
|
||||||
|
ok $path->is_valid(), 'return path is valid';
|
||||||
|
ok $path->length > Slic3r::Line->new($from, $to)->length, 'path length is greater than straight line';
|
||||||
|
ok $path->first_point->coincides_with($from), 'first path point coincides with initial point';
|
||||||
|
ok $path->last_point->coincides_with($to), 'last path point coincides with destination point';
|
||||||
|
ok $expolygon->contains_polyline($path), 'path is fully contained in expolygon';
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
my $mp = Slic3r::MotionPlanner->new([ $expolygon ]);
|
||||||
|
isa_ok $mp, 'Slic3r::MotionPlanner';
|
||||||
|
|
||||||
|
my $from = Slic3r::Point->new(80, 100);
|
||||||
|
my $to = Slic3r::Point->new(220,200);
|
||||||
|
$_->scale(1/0.000001) for $from, $to;
|
||||||
|
|
||||||
|
my $path = $mp->shortest_path($from, $to);
|
||||||
|
ok $path->is_valid(), 'return path is valid';
|
||||||
|
ok $path->length > Slic3r::Line->new($from, $to)->length, 'path length is greater than straight line';
|
||||||
|
ok $path->first_point->coincides_with($from), 'first path point coincides with initial point';
|
||||||
|
ok $path->last_point->coincides_with($to), 'last path point coincides with destination point';
|
||||||
|
is scalar(@{ Slic3r::Geometry::Clipper::intersection_pl([$path], [@$expolygon]) }), 0, 'path has no intersection with expolygon';
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
my $expolygon2 = $expolygon->clone;
|
||||||
|
$expolygon2->translate(300/0.000001, 0);
|
||||||
|
my $mp = Slic3r::MotionPlanner->new([ $expolygon, $expolygon2 ]);
|
||||||
|
isa_ok $mp, 'Slic3r::MotionPlanner';
|
||||||
|
|
||||||
|
my $from = Slic3r::Point->new(120, 120);
|
||||||
|
my $to = Slic3r::Point->new(120 + 300, 120);
|
||||||
|
$_->scale(1/0.000001) for $from, $to;
|
||||||
|
ok $expolygon->contains_point($from), 'start point is contained in first expolygon';
|
||||||
|
ok $expolygon2->contains_point($to), 'end point is contained in second expolygon';
|
||||||
|
my $path = $mp->shortest_path($from, $to);
|
||||||
|
ok $path->is_valid(), 'return path is valid';
|
||||||
|
ok $path->length > Slic3r::Line->new($from, $to)->length, 'path length is greater than straight line';
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
my $expolygons = [
|
||||||
|
Slic3r::ExPolygon->new([[123800962,89330311],[123959159,89699438],[124000004,89898430],[124000012,110116427],[123946510,110343065],[123767391,110701303],[123284087,111000001],[102585791,111000009],[102000004,110414223],[102000004,89585787],[102585790,89000000],[123300022,88999993]]),
|
||||||
|
Slic3r::ExPolygon->new([[97800954,89330311],[97959151,89699438],[97999996,89898430],[98000004,110116427],[97946502,110343065],[97767383,110701303],[97284079,111000001],[76585783,111000009],[75999996,110414223],[75999996,89585787],[76585782,89000000],[97300014,88999993]]),
|
||||||
|
];
|
||||||
|
my $mp = Slic3r::MotionPlanner->new($expolygons);
|
||||||
|
isa_ok $mp, 'Slic3r::MotionPlanner';
|
||||||
|
|
||||||
|
my $from = Slic3r::Point->new(79120520, 107839491);
|
||||||
|
my $to = Slic3r::Point->new(104664164, 108335852);
|
||||||
|
ok $expolygons->[1]->contains_point($from), 'start point is contained in second expolygon';
|
||||||
|
ok $expolygons->[0]->contains_point($to), 'end point is contained in first expolygon';
|
||||||
|
my $path = $mp->shortest_path($from, $to);
|
||||||
|
ok $path->is_valid(), 'return path is valid';
|
||||||
|
ok $path->length > Slic3r::Line->new($from, $to)->length, 'path length is greater than straight line';
|
||||||
|
}
|
||||||
|
|
||||||
|
__END__
|
|
@ -23,6 +23,8 @@
|
||||||
bool is_valid();
|
bool is_valid();
|
||||||
bool contains_line(Line* line)
|
bool contains_line(Line* line)
|
||||||
%code{% RETVAL = THIS->contains_line(*line); %};
|
%code{% RETVAL = THIS->contains_line(*line); %};
|
||||||
|
bool contains_polyline(Polyline* polyline)
|
||||||
|
%code{% RETVAL = THIS->contains_polyline(*polyline); %};
|
||||||
bool contains_point(Point* point)
|
bool contains_point(Point* point)
|
||||||
%code{% RETVAL = THIS->contains_point(*point); %};
|
%code{% RETVAL = THIS->contains_point(*point); %};
|
||||||
ExPolygons simplify(double tolerance);
|
ExPolygons simplify(double tolerance);
|
||||||
|
|
14
xs/xsp/MotionPlanner.xsp
Normal file
14
xs/xsp/MotionPlanner.xsp
Normal file
|
@ -0,0 +1,14 @@
|
||||||
|
%module{Slic3r::XS};
|
||||||
|
|
||||||
|
%{
|
||||||
|
#include <myinit.h>
|
||||||
|
#include "MotionPlanner.hpp"
|
||||||
|
%}
|
||||||
|
|
||||||
|
%name{Slic3r::MotionPlanner} class MotionPlanner {
|
||||||
|
MotionPlanner(ExPolygons islands);
|
||||||
|
~MotionPlanner();
|
||||||
|
|
||||||
|
Polyline* shortest_path(Point* from, Point* to)
|
||||||
|
%code%{ RETVAL = new Polyline(); THIS->shortest_path(*from, *to, RETVAL); %};
|
||||||
|
};
|
|
@ -152,6 +152,9 @@ PlaceholderParser* O_OBJECT_SLIC3R
|
||||||
Ref<PlaceholderParser> O_OBJECT_SLIC3R_T
|
Ref<PlaceholderParser> O_OBJECT_SLIC3R_T
|
||||||
Clone<PlaceholderParser> O_OBJECT_SLIC3R_T
|
Clone<PlaceholderParser> O_OBJECT_SLIC3R_T
|
||||||
|
|
||||||
|
MotionPlanner* O_OBJECT_SLIC3R
|
||||||
|
Ref<MotionPlanner> O_OBJECT_SLIC3R_T
|
||||||
|
Clone<MotionPlanner> O_OBJECT_SLIC3R_T
|
||||||
|
|
||||||
ExtrusionLoopRole T_UV
|
ExtrusionLoopRole T_UV
|
||||||
ExtrusionRole T_UV
|
ExtrusionRole T_UV
|
||||||
|
|
|
@ -77,6 +77,9 @@
|
||||||
%typemap{PolylineCollection*};
|
%typemap{PolylineCollection*};
|
||||||
%typemap{Ref<PolylineCollection>}{simple};
|
%typemap{Ref<PolylineCollection>}{simple};
|
||||||
%typemap{Clone<PolylineCollection>}{simple};
|
%typemap{Clone<PolylineCollection>}{simple};
|
||||||
|
%typemap{MotionPlanner*};
|
||||||
|
%typemap{Ref<MotionPlanner>}{simple};
|
||||||
|
%typemap{Clone<MotionPlanner>}{simple};
|
||||||
|
|
||||||
%typemap{PrintState*};
|
%typemap{PrintState*};
|
||||||
%typemap{Ref<PrintState>}{simple};
|
%typemap{Ref<PrintState>}{simple};
|
||||||
|
|
Loading…
Reference in a new issue