mirror of
https://git.mirrors.martin98.com/https://github.com/bambulab/BambuStudio.git
synced 2025-09-29 06:13:16 +08:00
ENH: Use the real prime tower model after slicing.
1. set wipe tower real height 2. fix wipe tower small arc error 3. add rib_width constraint to ensure that the rib wall of the wipetower are attached to the infill. jira: STUDIO-10540 Change-Id: Idfdc809f0236121d98587ac2a09a2ebbf5caf945
This commit is contained in:
parent
cd3b96c7f5
commit
3a7dcfd232
@ -584,9 +584,9 @@ static std::vector<Vec2d> get_path_of_change_filament(const Print& print)
|
|||||||
// We want to rotate and shift all extrusions (gcode postprocessing) and starting and ending position
|
// We want to rotate and shift all extrusions (gcode postprocessing) and starting and ending position
|
||||||
float alpha = m_wipe_tower_rotation / 180.f * float(M_PI);
|
float alpha = m_wipe_tower_rotation / 180.f * float(M_PI);
|
||||||
|
|
||||||
auto transform_wt_pt = [&alpha, this](const Vec2f& pt,bool rib_offset=true) -> Vec2f {
|
auto transform_wt_pt = [&alpha, this](const Vec2f& pt) -> Vec2f {
|
||||||
Vec2f out = Eigen::Rotation2Df(alpha) * pt;
|
Vec2f out = Eigen::Rotation2Df(alpha) * pt;
|
||||||
out += m_wipe_tower_pos + (rib_offset? m_rib_offset:Vec2f(0.f,0.f));
|
out += m_wipe_tower_pos + m_rib_offset;
|
||||||
return out;
|
return out;
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -825,7 +825,7 @@ static std::vector<Vec2d> get_path_of_change_filament(const Print& print)
|
|||||||
avoid_bbx = scaled(m_wipe_tower_bbx);
|
avoid_bbx = scaled(m_wipe_tower_bbx);
|
||||||
Polygon avoid_points = avoid_bbx.polygon();
|
Polygon avoid_points = avoid_bbx.polygon();
|
||||||
for (auto& p : avoid_points.points) {
|
for (auto& p : avoid_points.points) {
|
||||||
Vec2f pp = transform_wt_pt(unscale(p).cast<float>(),false);
|
Vec2f pp = transform_wt_pt(unscale(p).cast<float>());
|
||||||
p = wipe_tower_point_to_object_point(gcodegen, pp + plate_origin_2d);
|
p = wipe_tower_point_to_object_point(gcodegen, pp + plate_origin_2d);
|
||||||
}
|
}
|
||||||
avoid_bbx = BoundingBox(avoid_points.points);
|
avoid_bbx = BoundingBox(avoid_points.points);
|
||||||
|
@ -10,6 +10,7 @@
|
|||||||
#include "GCodeProcessor.hpp"
|
#include "GCodeProcessor.hpp"
|
||||||
#include "BoundingBox.hpp"
|
#include "BoundingBox.hpp"
|
||||||
#include "LocalesUtils.hpp"
|
#include "LocalesUtils.hpp"
|
||||||
|
#include "Triangulation.hpp"
|
||||||
|
|
||||||
|
|
||||||
namespace Slic3r
|
namespace Slic3r
|
||||||
@ -18,7 +19,9 @@ bool flat_ironing = true; // Whether to ena
|
|||||||
float flat_iron_area = 4.f;
|
float flat_iron_area = 4.f;
|
||||||
constexpr float flat_iron_speed = 10.f * 60.f;
|
constexpr float flat_iron_speed = 10.f * 60.f;
|
||||||
static const double wipe_tower_wall_infill_overlap = 0.0;
|
static const double wipe_tower_wall_infill_overlap = 0.0;
|
||||||
static constexpr double WIPE_TOWER_RESOLUTION = 0.0375;
|
static constexpr double WIPE_TOWER_RESOLUTION = 0.1;
|
||||||
|
static constexpr double WT_SIMPLIFY_TOLERANCE_SCALED = 0.001 / SCALING_FACTOR;
|
||||||
|
static constexpr int arc_fit_size = 20;
|
||||||
#define SCALED_WIPE_TOWER_RESOLUTION (WIPE_TOWER_RESOLUTION / SCALING_FACTOR)
|
#define SCALED_WIPE_TOWER_RESOLUTION (WIPE_TOWER_RESOLUTION / SCALING_FACTOR)
|
||||||
inline float align_round(float value, float base)
|
inline float align_round(float value, float base)
|
||||||
{
|
{
|
||||||
@ -98,7 +101,7 @@ Polygon chamfer_polygon(Polygon &polygon, double chamfer_dis = 2., double angle_
|
|||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
|
|
||||||
Polygon rounding_polygon(Polygon &polygon, double rounding = 2., double angle_tol = 30. / 180. * PI)
|
Polygon WipeTower::rounding_polygon(Polygon &polygon, double rounding /*= 2.*/, double angle_tol/* = 30. / 180. * PI*/)
|
||||||
{
|
{
|
||||||
if (polygon.points.size() < 3) return polygon;
|
if (polygon.points.size() < 3) return polygon;
|
||||||
Polygon res;
|
Polygon res;
|
||||||
@ -140,8 +143,7 @@ Polygon rounding_polygon(Polygon &polygon, double rounding = 2., double angle_to
|
|||||||
Vec2d center = b + dir * dis;
|
Vec2d center = b + dir * dis;
|
||||||
double radius = (left - center).norm();
|
double radius = (left - center).norm();
|
||||||
ArcSegment arc(scaled(center), scaled(radius), scaled(left), scaled(right), is_ccw ? ArcDirection::Arc_Dir_CCW : ArcDirection::Arc_Dir_CW);
|
ArcSegment arc(scaled(center), scaled(radius), scaled(left), scaled(right), is_ccw ? ArcDirection::Arc_Dir_CCW : ArcDirection::Arc_Dir_CW);
|
||||||
float sample_angle = 5.f / 180.f * PI;
|
int n = arc_fit_size;
|
||||||
int n = std::ceil(abs(arc.angle_radians) / sample_angle);
|
|
||||||
//std::cout << "start " << arc.start_point[0] << " " << arc.start_point[1] << std::endl;
|
//std::cout << "start " << arc.start_point[0] << " " << arc.start_point[1] << std::endl;
|
||||||
//std::cout << "end " << arc.end_point[0] << " " << arc.end_point[1] << std::endl;
|
//std::cout << "end " << arc.end_point[0] << " " << arc.end_point[1] << std::endl;
|
||||||
//std::cout << "start angle " << arc.polar_start_theta << " end angle " << arc.polar_end_theta << std::endl;
|
//std::cout << "start angle " << arc.polar_start_theta << " end angle " << arc.polar_end_theta << std::endl;
|
||||||
@ -162,6 +164,7 @@ Polygon rounding_polygon(Polygon &polygon, double rounding = 2., double angle_to
|
|||||||
} else
|
} else
|
||||||
res.points.push_back(polygon.points[i]);
|
res.points.push_back(polygon.points[i]);
|
||||||
}
|
}
|
||||||
|
res.remove_duplicate_points();
|
||||||
res.points.shrink_to_fit();
|
res.points.shrink_to_fit();
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
@ -198,8 +201,7 @@ Polygon rounding_rectangle(Polygon &polygon, double rounding = 2., double angle_
|
|||||||
Vec2d center = b;
|
Vec2d center = b;
|
||||||
double radius = real_rounding_dis;
|
double radius = real_rounding_dis;
|
||||||
ArcSegment arc(scaled(center), scaled(radius), scaled(left), scaled(right), is_ccw ? ArcDirection::Arc_Dir_CCW : ArcDirection::Arc_Dir_CW);
|
ArcSegment arc(scaled(center), scaled(radius), scaled(left), scaled(right), is_ccw ? ArcDirection::Arc_Dir_CCW : ArcDirection::Arc_Dir_CW);
|
||||||
float sample_angle = 5.f / 180.f * PI;
|
int n = arc_fit_size;
|
||||||
int n = std::ceil(abs(arc.angle_radians) / sample_angle);
|
|
||||||
// std::cout << "start " << arc.start_point[0] << " " << arc.start_point[1] << std::endl;
|
// std::cout << "start " << arc.start_point[0] << " " << arc.start_point[1] << std::endl;
|
||||||
// std::cout << "end " << arc.end_point[0] << " " << arc.end_point[1] << std::endl;
|
// std::cout << "end " << arc.end_point[0] << " " << arc.end_point[1] << std::endl;
|
||||||
// std::cout << "start angle " << arc.polar_start_theta << " end angle " << arc.polar_end_theta << std::endl;
|
// std::cout << "start angle " << arc.polar_start_theta << " end angle " << arc.polar_end_theta << std::endl;
|
||||||
@ -721,9 +723,7 @@ public:
|
|||||||
width += m_layer_height * float(1. - M_PI / 4.);
|
width += m_layer_height * float(1. - M_PI / 4.);
|
||||||
if (m_extrusions.empty() || m_extrusions.back().pos != rotated_current_pos) m_extrusions.emplace_back(WipeTower::Extrusion(rotated_current_pos, 0, m_current_tool));
|
if (m_extrusions.empty() || m_extrusions.back().pos != rotated_current_pos) m_extrusions.emplace_back(WipeTower::Extrusion(rotated_current_pos, 0, m_current_tool));
|
||||||
{
|
{
|
||||||
|
int n = arc_fit_size;
|
||||||
float sample_angle = 5.f / 180.f * PI;
|
|
||||||
int n = std::ceil(abs(arc.angle_radians) / sample_angle);
|
|
||||||
for (int j = 0; j < n; j++) {
|
for (int j = 0; j < n; j++) {
|
||||||
float cur_angle = arc.polar_start_theta + (float) j / n * arc.angle_radians;
|
float cur_angle = arc.polar_start_theta + (float) j / n * arc.angle_radians;
|
||||||
if (cur_angle > 2 * PI)
|
if (cur_angle > 2 * PI)
|
||||||
@ -896,6 +896,7 @@ public:
|
|||||||
WipeTowerWriter &polygon(const Polygon &wall_polygon, const float f = 0.f)
|
WipeTowerWriter &polygon(const Polygon &wall_polygon, const float f = 0.f)
|
||||||
{
|
{
|
||||||
Polyline pl = to_polyline(wall_polygon);
|
Polyline pl = to_polyline(wall_polygon);
|
||||||
|
pl.simplify(WT_SIMPLIFY_TOLERANCE_SCALED);
|
||||||
pl.simplify_by_fitting_arc(SCALED_WIPE_TOWER_RESOLUTION);
|
pl.simplify_by_fitting_arc(SCALED_WIPE_TOWER_RESOLUTION);
|
||||||
|
|
||||||
auto get_closet_idx = [this](std::vector<Segment> &corners) -> int {
|
auto get_closet_idx = [this](std::vector<Segment> &corners) -> int {
|
||||||
@ -1364,6 +1365,122 @@ float WipeTower::get_auto_brim_by_height(float max_height) {
|
|||||||
return 8.f;
|
return 8.f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Vec2f WipeTower::move_box_inside_box(const BoundingBox &box1, const BoundingBox &box2,int scaled_offset)
|
||||||
|
{
|
||||||
|
Vec2f res{0, 0};
|
||||||
|
if (box1.size()[0] >= box2.size()[0]- 2*scaled_offset || box1.size()[1] >= box2.size()[1]-2*scaled_offset) return res;
|
||||||
|
|
||||||
|
if (box1.max[0] > box2.max[0] - scaled_offset) {
|
||||||
|
res[0] = unscaled<float>((box2.max[0] - scaled_offset) - box1.max[0]);
|
||||||
|
}
|
||||||
|
else if (box1.min[0] < box2.min[0] + scaled_offset) {
|
||||||
|
res[0] = unscaled<float>((box2.min[0] + scaled_offset) - box1.min[0]);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (box1.max[1] > box2.max[1] - scaled_offset) {
|
||||||
|
res[1] = unscaled<float>((box2.max[1] - scaled_offset) - box1.max[1]);
|
||||||
|
}
|
||||||
|
else if (box1.min[1] < box2.min[1] + scaled_offset) {
|
||||||
|
res[1] = unscaled<float>((box2.min[1] + scaled_offset) - box1.min[1]);
|
||||||
|
}
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
Polygon WipeTower::rib_section(float width, float depth, float rib_length, float rib_width,bool fillet_wall)
|
||||||
|
{
|
||||||
|
Polygon res;
|
||||||
|
res.points.resize(16);
|
||||||
|
float theta = std::atan(width / depth);
|
||||||
|
float costheta = std::cos(theta);
|
||||||
|
float sintheta = std::sin(theta);
|
||||||
|
float w = rib_width / 2.f;
|
||||||
|
float diag = std::sqrt(width * width + depth * depth);
|
||||||
|
float l = (rib_length - diag) / 2;
|
||||||
|
Vec2f diag_dir1 = Vec2f{width, depth}.normalized();
|
||||||
|
Vec2f diag_dir1_perp{-diag_dir1[1], diag_dir1[0]};
|
||||||
|
Vec2f diag_dir2 = Vec2f{-width, depth}.normalized();
|
||||||
|
Vec2f diag_dir2_perp{-diag_dir2[1], diag_dir2[0]};
|
||||||
|
std::vector<Vec2f> p{{0, 0}, {width, 0}, {width, depth}, {0, depth}};
|
||||||
|
Polyline p_render;
|
||||||
|
for (auto &x : p) p_render.points.push_back(scaled(x));
|
||||||
|
res.points[0] = scaled(Vec2f{p[0].x(), p[0].y() + w / sintheta});
|
||||||
|
res.points[1] = scaled(Vec2f{p[0] - diag_dir1 * l + diag_dir1_perp * w});
|
||||||
|
res.points[2] = scaled(Vec2f{p[0] - diag_dir1 * l - diag_dir1_perp * w});
|
||||||
|
res.points[3] = scaled(Vec2f{p[0].x() + w / costheta, p[0].y()});
|
||||||
|
|
||||||
|
res.points[4] = scaled(Vec2f{p[1].x() - w / costheta, p[1].y()});
|
||||||
|
res.points[5] = scaled(Vec2f{p[1] - diag_dir2 * l + diag_dir2_perp * w});
|
||||||
|
res.points[6] = scaled(Vec2f{p[1] - diag_dir2 * l - diag_dir2_perp * w});
|
||||||
|
res.points[7] = scaled(Vec2f{p[1].x(), p[1].y() + w / sintheta});
|
||||||
|
|
||||||
|
res.points[8] = scaled(Vec2f{p[2].x(), p[2].y() - w / sintheta});
|
||||||
|
res.points[9] = scaled(Vec2f{p[2] + diag_dir1 * l - diag_dir1_perp * w});
|
||||||
|
res.points[10] = scaled(Vec2f{p[2] + diag_dir1 * l + diag_dir1_perp * w});
|
||||||
|
res.points[11] = scaled(Vec2f{p[2].x() - w / costheta, p[2].y()});
|
||||||
|
|
||||||
|
res.points[12] = scaled(Vec2f{p[3].x() + w / costheta, p[3].y()});
|
||||||
|
res.points[13] = scaled(Vec2f{p[3] + diag_dir2 * l - diag_dir2_perp * w});
|
||||||
|
res.points[14] = scaled(Vec2f{p[3] + diag_dir2 * l + diag_dir2_perp * w});
|
||||||
|
res.points[15] = scaled(Vec2f{p[3].x(), p[3].y() - w / sintheta});
|
||||||
|
res.remove_duplicate_points();
|
||||||
|
if (fillet_wall) { res = rounding_polygon(res); }
|
||||||
|
res.points.shrink_to_fit();
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
TriangleMesh WipeTower::its_make_rib_tower(float width, float depth, float height, float rib_length, float rib_width, bool fillet_wall)
|
||||||
|
{
|
||||||
|
TriangleMesh res;
|
||||||
|
Polygon bottom = rib_section(width, depth, rib_length, rib_width, fillet_wall);
|
||||||
|
Polygon top = rib_section(width, depth, std::sqrt(width * width + depth * depth), rib_width, fillet_wall);
|
||||||
|
if (fillet_wall)
|
||||||
|
assert(bottom.points.size() == top.points.size());
|
||||||
|
int offset = bottom.points.size();
|
||||||
|
res.its.vertices.reserve(offset * 2);
|
||||||
|
auto faces_bottom = Triangulation::triangulate(bottom);
|
||||||
|
auto faces_top = Triangulation::triangulate(top);
|
||||||
|
res.its.indices.reserve(offset * 2 + faces_bottom.size() + faces_top.size());
|
||||||
|
for (auto &t : faces_bottom) res.its.indices.push_back({t[1], t[0], t[2]});
|
||||||
|
for (auto &t : faces_top) res.its.indices.push_back({t[0] + offset, t[1] + offset, t[2] + offset});
|
||||||
|
|
||||||
|
for (int i = 0; i < bottom.size(); i++) res.its.vertices.push_back({unscaled<float>(bottom[i][0]), unscaled<float>(bottom[i][1]), 0});
|
||||||
|
for (int i = 0; i < top.size(); i++) res.its.vertices.push_back({unscaled<float>(top[i][0]), unscaled<float>(top[i][1]), height});
|
||||||
|
|
||||||
|
for (int i = 0; i < offset; i++) {
|
||||||
|
int a = i;
|
||||||
|
int b = (i + 1) % offset;
|
||||||
|
int c = i + offset;
|
||||||
|
int d = b + offset;
|
||||||
|
res.its.indices.push_back({a, b, c});
|
||||||
|
res.its.indices.push_back({d, c, b});
|
||||||
|
}
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
TriangleMesh WipeTower::its_make_rib_brim(const Polygon& brim, float layer_height) {
|
||||||
|
TriangleMesh res;
|
||||||
|
int offset = brim.size();
|
||||||
|
res.its.vertices.reserve(brim.size() * 2);
|
||||||
|
auto faces= Triangulation::triangulate(brim);
|
||||||
|
res.its.indices.reserve(brim.size() * 2 + 2 * faces.size());
|
||||||
|
for (auto &t : faces) res.its.indices.push_back({t[1], t[0], t[2]});
|
||||||
|
for (auto &t : faces) res.its.indices.push_back({t[0] + offset, t[1] + offset, t[2] + offset});
|
||||||
|
|
||||||
|
for (int i = 0; i < brim.size(); i++) res.its.vertices.push_back({unscaled<float>(brim[i][0]), unscaled<float>(brim[i][1]), 0});
|
||||||
|
for (int i = 0; i < brim.size(); i++) res.its.vertices.push_back({unscaled<float>(brim[i][0]), unscaled<float>(brim[i][1]), layer_height});
|
||||||
|
|
||||||
|
for (int i = 0; i < offset; i++) {
|
||||||
|
int a = i;
|
||||||
|
int b = (i + 1) % offset;
|
||||||
|
int c = i + offset;
|
||||||
|
int d = b + offset;
|
||||||
|
res.its.indices.push_back({a, b, c});
|
||||||
|
res.its.indices.push_back({d, c, b});
|
||||||
|
}
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
WipeTower::WipeTower(const PrintConfig& config, int plate_idx, Vec3d plate_origin, size_t initial_tool, const float wipe_tower_height) :
|
WipeTower::WipeTower(const PrintConfig& config, int plate_idx, Vec3d plate_origin, size_t initial_tool, const float wipe_tower_height) :
|
||||||
m_semm(config.single_extruder_multi_material.value),
|
m_semm(config.single_extruder_multi_material.value),
|
||||||
m_wipe_tower_pos(config.wipe_tower_x.get_at(plate_idx), config.wipe_tower_y.get_at(plate_idx)),
|
m_wipe_tower_pos(config.wipe_tower_x.get_at(plate_idx), config.wipe_tower_y.get_at(plate_idx)),
|
||||||
@ -3641,6 +3758,8 @@ void WipeTower::plan_tower_new()
|
|||||||
update_all_layer_depth(max_depth);
|
update_all_layer_depth(max_depth);
|
||||||
m_rib_length = std::max({m_rib_length, sqrt(m_wipe_tower_depth * m_wipe_tower_depth + m_wipe_tower_width * m_wipe_tower_width)});
|
m_rib_length = std::max({m_rib_length, sqrt(m_wipe_tower_depth * m_wipe_tower_depth + m_wipe_tower_width * m_wipe_tower_width)});
|
||||||
m_rib_length += m_extra_rib_length;
|
m_rib_length += m_extra_rib_length;
|
||||||
|
m_rib_length = std::max(0.f, m_rib_length);
|
||||||
|
m_rib_width = std::min(m_rib_width, std::min(m_wipe_tower_depth, m_wipe_tower_width) / 2.f); // Ensure that the rib wall of the wipetower are attached to the infill.
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -3705,7 +3824,7 @@ void WipeTower::generate_new(std::vector<std::vector<WipeTower::ToolChangeResult
|
|||||||
if (m_plan.empty())
|
if (m_plan.empty())
|
||||||
return;
|
return;
|
||||||
//m_extra_spacing = 1.f;
|
//m_extra_spacing = 1.f;
|
||||||
|
m_wipe_tower_height = m_plan.back().z;//real wipe_tower_height
|
||||||
plan_tower_new();
|
plan_tower_new();
|
||||||
|
|
||||||
m_layer_info = m_plan.begin();
|
m_layer_info = m_plan.begin();
|
||||||
|
@ -28,7 +28,11 @@ public:
|
|||||||
static const std::map<float, float> min_depth_per_height;
|
static const std::map<float, float> min_depth_per_height;
|
||||||
static float get_limit_depth_by_height(float max_height);
|
static float get_limit_depth_by_height(float max_height);
|
||||||
static float get_auto_brim_by_height(float max_height);
|
static float get_auto_brim_by_height(float max_height);
|
||||||
|
static TriangleMesh its_make_rib_tower(float width, float depth, float height, float rib_length, float rib_width, bool fillet_wall);
|
||||||
|
static TriangleMesh its_make_rib_brim(const Polygon& brim, float layer_height);
|
||||||
|
static Polygon rib_section(float width, float depth, float rib_length, float rib_width, bool fillet_wall);
|
||||||
|
static Vec2f move_box_inside_box(const BoundingBox &box1, const BoundingBox &box2, int offset = 0);
|
||||||
|
static Polygon rounding_polygon(Polygon &polygon, double rounding = 2., double angle_tol = 30. / 180. * PI);
|
||||||
struct Extrusion
|
struct Extrusion
|
||||||
{
|
{
|
||||||
Extrusion(const Vec2f &pos, float width, unsigned int tool) : pos(pos), width(width), tool(tool) {}
|
Extrusion(const Vec2f &pos, float width, unsigned int tool) : pos(pos), width(width), tool(tool) {}
|
||||||
@ -191,20 +195,16 @@ public:
|
|||||||
if (m_outer_wall.empty()) return BoundingBoxf({Vec2d(0,0)});
|
if (m_outer_wall.empty()) return BoundingBoxf({Vec2d(0,0)});
|
||||||
BoundingBox box = get_extents(m_outer_wall.begin()->second);
|
BoundingBox box = get_extents(m_outer_wall.begin()->second);
|
||||||
BoundingBoxf res = BoundingBoxf(unscale(box.min), unscale(box.max));
|
BoundingBoxf res = BoundingBoxf(unscale(box.min), unscale(box.max));
|
||||||
res.translate(m_rib_offset.cast<double>());
|
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
std::map<float, Polylines> get_outer_wall() const
|
std::map<float, Polylines> get_outer_wall() const
|
||||||
{
|
{
|
||||||
std::map<float, Polylines> res = m_outer_wall;
|
return m_outer_wall;
|
||||||
Point trans = scaled(m_rib_offset);
|
|
||||||
for (auto &[h,polylines] : res)
|
|
||||||
for (auto &polyline : polylines)
|
|
||||||
polyline.translate(trans.x(), trans.y());
|
|
||||||
return res;
|
|
||||||
}
|
}
|
||||||
float get_height() const { return m_wipe_tower_height; }
|
float get_height() const { return m_wipe_tower_height; }
|
||||||
float get_layer_height() const { return m_layer_height; }
|
float get_layer_height() const { return m_layer_height; }
|
||||||
|
float get_rib_length() const { return m_rib_length; }
|
||||||
|
float get_rib_width() const { return m_rib_width; }
|
||||||
|
|
||||||
void set_last_layer_extruder_fill(bool extruder_fill) {
|
void set_last_layer_extruder_fill(bool extruder_fill) {
|
||||||
if (!m_plan.empty()) {
|
if (!m_plan.empty()) {
|
||||||
|
@ -954,13 +954,20 @@ static StringObjectException layered_print_cleareance_valid(const Print &print,
|
|||||||
|
|
||||||
Polygons convex_hulls_temp;
|
Polygons convex_hulls_temp;
|
||||||
if (print.has_wipe_tower()) {
|
if (print.has_wipe_tower()) {
|
||||||
Polygon wipe_tower_convex_hull;
|
if (!print.is_step_done(psWipeTower)) {
|
||||||
wipe_tower_convex_hull.points.emplace_back(scale_(x), scale_(y));
|
Polygon wipe_tower_convex_hull;
|
||||||
wipe_tower_convex_hull.points.emplace_back(scale_(x + width), scale_(y));
|
wipe_tower_convex_hull.points.emplace_back(scale_(x), scale_(y));
|
||||||
wipe_tower_convex_hull.points.emplace_back(scale_(x + width), scale_(y + depth));
|
wipe_tower_convex_hull.points.emplace_back(scale_(x + width), scale_(y));
|
||||||
wipe_tower_convex_hull.points.emplace_back(scale_(x), scale_(y + depth));
|
wipe_tower_convex_hull.points.emplace_back(scale_(x + width), scale_(y + depth));
|
||||||
wipe_tower_convex_hull.rotate(a);
|
wipe_tower_convex_hull.points.emplace_back(scale_(x), scale_(y + depth));
|
||||||
convex_hulls_temp.push_back(wipe_tower_convex_hull);
|
wipe_tower_convex_hull.rotate(a);
|
||||||
|
convex_hulls_temp.push_back(wipe_tower_convex_hull);
|
||||||
|
} else {
|
||||||
|
//here, wipe_tower_polygon is not always convex.
|
||||||
|
Polygon wipe_tower_polygon = print.wipe_tower_data().wipe_tower_mesh_data->bottom;
|
||||||
|
wipe_tower_polygon.translate(Point(scale_(x), scale_(y)));
|
||||||
|
convex_hulls_temp.push_back(wipe_tower_polygon);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
if (!intersection(convex_hulls_other, convex_hulls_temp).empty()) {
|
if (!intersection(convex_hulls_other, convex_hulls_temp).empty()) {
|
||||||
if (warning) {
|
if (warning) {
|
||||||
@ -2319,7 +2326,7 @@ std::vector<Point> Print::first_layer_wipe_tower_corners(bool check_wipe_tower_e
|
|||||||
{
|
{
|
||||||
double width = m_wipe_tower_data.bbx.max.x() - m_wipe_tower_data.bbx.min.x();
|
double width = m_wipe_tower_data.bbx.max.x() - m_wipe_tower_data.bbx.min.x();
|
||||||
double depth = m_wipe_tower_data.bbx.max.y() -m_wipe_tower_data.bbx.min.y();
|
double depth = m_wipe_tower_data.bbx.max.y() -m_wipe_tower_data.bbx.min.y();
|
||||||
Vec2d pt0 = m_wipe_tower_data.bbx.min;
|
Vec2d pt0 = m_wipe_tower_data.bbx.min + m_wipe_tower_data.rib_offset.cast<double>();
|
||||||
for (Vec2d pt : {
|
for (Vec2d pt : {
|
||||||
pt0,
|
pt0,
|
||||||
Vec2d(pt0.x()+width, pt0.y() ),
|
Vec2d(pt0.x()+width, pt0.y() ),
|
||||||
@ -2599,8 +2606,8 @@ const WipeTowerData& Print::wipe_tower_data(size_t filaments_cnt) const
|
|||||||
}
|
}
|
||||||
const_cast<Print *>(this)->m_wipe_tower_data.brim_width = m_config.prime_tower_brim_width;
|
const_cast<Print *>(this)->m_wipe_tower_data.brim_width = m_config.prime_tower_brim_width;
|
||||||
}
|
}
|
||||||
|
if (m_config.prime_tower_brim_width < 0) const_cast<Print *>(this)->m_wipe_tower_data.brim_width = WipeTower::get_auto_brim_by_height(max_height);
|
||||||
}
|
}
|
||||||
if (m_config.prime_tower_brim_width < 0 ) const_cast<Print *>(this)->m_wipe_tower_data.brim_width = WipeTower::get_auto_brim_by_height(max_height);
|
|
||||||
return m_wipe_tower_data;
|
return m_wipe_tower_data;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -2783,8 +2790,12 @@ void Print::_make_wipe_tower()
|
|||||||
|
|
||||||
m_wipe_tower_data.used_filament = wipe_tower.get_used_filament();
|
m_wipe_tower_data.used_filament = wipe_tower.get_used_filament();
|
||||||
m_wipe_tower_data.number_of_toolchanges = wipe_tower.get_number_of_toolchanges();
|
m_wipe_tower_data.number_of_toolchanges = wipe_tower.get_number_of_toolchanges();
|
||||||
|
m_wipe_tower_data.construct_mesh(wipe_tower.width(), wipe_tower.get_depth(), wipe_tower.get_height(), wipe_tower.get_brim_width(), config().prime_tower_rib_wall.value,
|
||||||
|
wipe_tower.get_rib_width(), wipe_tower.get_rib_length(), config().prime_tower_fillet_wall.value);
|
||||||
const Vec3d origin = this->get_plate_origin();
|
const Vec3d origin = this->get_plate_origin();
|
||||||
m_fake_wipe_tower.set_fake_extrusion_data(wipe_tower.position(), wipe_tower.width(), wipe_tower.get_height(), wipe_tower.get_layer_height(), m_wipe_tower_data.depth,
|
m_fake_wipe_tower.rib_offset = wipe_tower.get_rib_offset();
|
||||||
|
m_fake_wipe_tower.set_fake_extrusion_data(wipe_tower.position() + m_fake_wipe_tower.rib_offset, wipe_tower.width(), wipe_tower.get_height(), wipe_tower.get_layer_height(),
|
||||||
|
m_wipe_tower_data.depth,
|
||||||
m_wipe_tower_data.brim_width, {scale_(origin.x()), scale_(origin.y())});
|
m_wipe_tower_data.brim_width, {scale_(origin.x()), scale_(origin.y())});
|
||||||
m_fake_wipe_tower.outer_wall = wipe_tower.get_outer_wall();
|
m_fake_wipe_tower.outer_wall = wipe_tower.get_outer_wall();
|
||||||
}
|
}
|
||||||
@ -4162,6 +4173,25 @@ ExtrusionLayers FakeWipeTower::getTrueExtrusionLayersFromWipeTower() const
|
|||||||
}
|
}
|
||||||
return wtels;
|
return wtels;
|
||||||
}
|
}
|
||||||
|
void WipeTowerData::construct_mesh(float width, float depth, float height, float brim_width, bool is_rib_wipe_tower, float rib_width, float rib_length,bool fillet_wall)
|
||||||
|
{
|
||||||
|
wipe_tower_mesh_data = WipeTowerMeshData{};
|
||||||
|
float first_layer_height=0.08; //brim height
|
||||||
|
if (!is_rib_wipe_tower) {
|
||||||
|
wipe_tower_mesh_data->real_wipe_tower_mesh = make_cube(width, depth, height);
|
||||||
|
wipe_tower_mesh_data->real_brim_mesh = make_cube(width + 2 * brim_width, depth + 2 * brim_width, first_layer_height);
|
||||||
|
wipe_tower_mesh_data->real_brim_mesh.translate({-brim_width, -brim_width, 0});
|
||||||
|
wipe_tower_mesh_data->bottom = {scaled(Vec2f{-brim_width, -brim_width}), scaled(Vec2f{width + brim_width, 0}), scaled(Vec2f{width + brim_width, depth + brim_width}),
|
||||||
|
scaled(Vec2f{0, depth})};
|
||||||
|
} else {
|
||||||
|
wipe_tower_mesh_data->real_wipe_tower_mesh = WipeTower::its_make_rib_tower(width, depth, height, rib_length, rib_width, fillet_wall);
|
||||||
|
wipe_tower_mesh_data->bottom = WipeTower::rib_section(width, depth, rib_length, rib_width, fillet_wall);
|
||||||
|
wipe_tower_mesh_data->bottom = offset(wipe_tower_mesh_data->bottom, scaled(brim_width)).front();
|
||||||
|
wipe_tower_mesh_data->real_brim_mesh = WipeTower::its_make_rib_brim(wipe_tower_mesh_data->bottom, first_layer_height);
|
||||||
|
wipe_tower_mesh_data->real_wipe_tower_mesh.translate(Vec3f(rib_offset[0], rib_offset[1],0));
|
||||||
|
wipe_tower_mesh_data->real_brim_mesh.translate(Vec3f(rib_offset[0], rib_offset[1], 0));
|
||||||
|
wipe_tower_mesh_data->bottom.translate(scaled(Vec2f(rib_offset[0], rib_offset[1])));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
} // namespace Slic3r
|
} // namespace Slic3r
|
||||||
|
@ -618,10 +618,11 @@ struct FakeWipeTower
|
|||||||
Vec2f pos;
|
Vec2f pos;
|
||||||
float width;
|
float width;
|
||||||
float height;
|
float height;
|
||||||
float layer_height;
|
float layer_height;// Due to variable layer height, this parameter may be not right.
|
||||||
float depth;
|
float depth;
|
||||||
float brim_width;
|
float brim_width;
|
||||||
Vec2d plate_origin;
|
Vec2d plate_origin;
|
||||||
|
Vec2f rib_offset{0.f,0.f};
|
||||||
std::map<float , Polylines> outer_wall; //wipe tower's true outer wall and brim
|
std::map<float , Polylines> outer_wall; //wipe tower's true outer wall and brim
|
||||||
|
|
||||||
void set_fake_extrusion_data(Vec2f p, float w, float h, float lh, float d, float bd, Vec2d o)
|
void set_fake_extrusion_data(Vec2f p, float w, float h, float lh, float d, float bd, Vec2d o)
|
||||||
@ -635,7 +636,7 @@ struct FakeWipeTower
|
|||||||
plate_origin = o;
|
plate_origin = o;
|
||||||
}
|
}
|
||||||
|
|
||||||
void set_pos(Vec2f p) { pos = p; }
|
void set_pos(Vec2f p) { pos = p+rib_offset; }
|
||||||
|
|
||||||
std::vector<ExtrusionPaths> getFakeExtrusionPathsFromWipeTower() const
|
std::vector<ExtrusionPaths> getFakeExtrusionPathsFromWipeTower() const
|
||||||
{
|
{
|
||||||
@ -667,6 +668,12 @@ struct FakeWipeTower
|
|||||||
|
|
||||||
struct WipeTowerData
|
struct WipeTowerData
|
||||||
{
|
{
|
||||||
|
struct WipeTowerMeshData
|
||||||
|
{
|
||||||
|
Polygon bottom;
|
||||||
|
TriangleMesh real_wipe_tower_mesh;
|
||||||
|
TriangleMesh real_brim_mesh;
|
||||||
|
};
|
||||||
// Following section will be consumed by the GCodeGenerator.
|
// Following section will be consumed by the GCodeGenerator.
|
||||||
// Tool ordering of a non-sequential print has to be known to calculate the wipe tower.
|
// Tool ordering of a non-sequential print has to be known to calculate the wipe tower.
|
||||||
// Cache it here, so it does not need to be recalculated during the G-code generation.
|
// Cache it here, so it does not need to be recalculated during the G-code generation.
|
||||||
@ -681,9 +688,9 @@ struct WipeTowerData
|
|||||||
// Depth of the wipe tower to pass to GLCanvas3D for exact bounding box:
|
// Depth of the wipe tower to pass to GLCanvas3D for exact bounding box:
|
||||||
float depth;
|
float depth;
|
||||||
float brim_width;
|
float brim_width;
|
||||||
BoundingBoxf bbx;
|
BoundingBoxf bbx;//including brim
|
||||||
Vec2f rib_offset;
|
Vec2f rib_offset;
|
||||||
|
std::optional<WipeTowerMeshData> wipe_tower_mesh_data;//added rib_offset
|
||||||
void clear() {
|
void clear() {
|
||||||
priming.reset(nullptr);
|
priming.reset(nullptr);
|
||||||
tool_changes.clear();
|
tool_changes.clear();
|
||||||
@ -692,7 +699,9 @@ struct WipeTowerData
|
|||||||
number_of_toolchanges = -1;
|
number_of_toolchanges = -1;
|
||||||
depth = 0.f;
|
depth = 0.f;
|
||||||
brim_width = 0.f;
|
brim_width = 0.f;
|
||||||
|
wipe_tower_mesh_data = std::nullopt;
|
||||||
}
|
}
|
||||||
|
void construct_mesh(float width, float depth, float height, float brim_width, bool is_rib_wipe_tower, float rib_width, float rib_length, bool fillet_wall);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
// Only allow the WipeTowerData to be instantiated internally by Print,
|
// Only allow the WipeTowerData to be instantiated internally by Print,
|
||||||
|
@ -1508,6 +1508,50 @@ int GLVolumeCollection::load_wipe_tower_preview(
|
|||||||
return int(volumes.size() - 1);
|
return int(volumes.size() - 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
int GLVolumeCollection::load_real_wipe_tower_preview(
|
||||||
|
int obj_idx, float pos_x, float pos_y, const TriangleMesh& wt_mesh,const TriangleMesh &brim_mesh,bool render_brim, float rotation_angle, bool size_unknown, bool opengl_initialized)
|
||||||
|
{
|
||||||
|
int plate_idx = obj_idx - 1000;
|
||||||
|
if (wt_mesh.its.vertices.empty()) return int(this->volumes.size() - 1);
|
||||||
|
|
||||||
|
std::vector<std::array<float, 4>> extruder_colors = GUI::wxGetApp().plater()->get_extruders_colors();
|
||||||
|
std::vector<std::array<float, 4>> colors;
|
||||||
|
GUI::PartPlateList &ppl = GUI::wxGetApp().plater()->get_partplate_list();
|
||||||
|
std::vector<int> plate_extruders = ppl.get_plate(plate_idx)->get_extruders(true);
|
||||||
|
|
||||||
|
for (int extruder_id : plate_extruders) {
|
||||||
|
if (extruder_id <= extruder_colors.size())
|
||||||
|
colors.push_back(extruder_colors[extruder_id - 1]);
|
||||||
|
else
|
||||||
|
colors.push_back(extruder_colors[0]);
|
||||||
|
}
|
||||||
|
|
||||||
|
volumes.emplace_back(new GLWipeTowerVolume(colors));
|
||||||
|
GLWipeTowerVolume &v = *dynamic_cast<GLWipeTowerVolume *>(volumes.back());
|
||||||
|
v.iva_per_colors.resize(colors.size());
|
||||||
|
auto mesh = wt_mesh;
|
||||||
|
if (render_brim) {
|
||||||
|
mesh.merge(brim_mesh);
|
||||||
|
}
|
||||||
|
if (!colors.empty()) {
|
||||||
|
v.iva_per_colors[0].load_mesh(mesh);
|
||||||
|
v.iva_per_colors[0].finalize_geometry(opengl_initialized);
|
||||||
|
}
|
||||||
|
TriangleMesh wipe_tower_shell = mesh.convex_hull_3d();
|
||||||
|
v.indexed_vertex_array->load_mesh(wipe_tower_shell);
|
||||||
|
v.indexed_vertex_array->finalize_geometry(opengl_initialized);
|
||||||
|
v.set_convex_hull(wipe_tower_shell);
|
||||||
|
v.set_volume_offset(Vec3d(pos_x, pos_y, 0.0));
|
||||||
|
v.set_volume_rotation(Vec3d(0., 0., (M_PI / 180.) * rotation_angle));
|
||||||
|
v.composite_id = GLVolume::CompositeID(obj_idx, 0, 0);
|
||||||
|
v.geometry_id.first = 0;
|
||||||
|
v.geometry_id.second = wipe_tower_instance_id().id + (obj_idx - 1000);
|
||||||
|
v.is_wipe_tower = true;
|
||||||
|
v.shader_outside_printer_detection_enabled = !size_unknown;
|
||||||
|
return int(volumes.size() - 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
GLVolume* GLVolumeCollection::new_toolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats)
|
GLVolume* GLVolumeCollection::new_toolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats)
|
||||||
{
|
{
|
||||||
GLVolume *out = new_nontoolpath_volume(rgba, reserve_vbo_floats);
|
GLVolume *out = new_nontoolpath_volume(rgba, reserve_vbo_floats);
|
||||||
|
@ -719,7 +719,8 @@ public:
|
|||||||
|
|
||||||
int load_wipe_tower_preview(
|
int load_wipe_tower_preview(
|
||||||
int obj_idx, float pos_x, float pos_y, float width, float depth, float height, float rotation_angle, bool size_unknown, float brim_width, bool opengl_initialized);
|
int obj_idx, float pos_x, float pos_y, float width, float depth, float height, float rotation_angle, bool size_unknown, float brim_width, bool opengl_initialized);
|
||||||
|
int load_real_wipe_tower_preview(
|
||||||
|
int obj_idx, float pos_x, float pos_y,const TriangleMesh& wt_mesh,const TriangleMesh &brim_mesh,bool render_brim, float rotation_angle, bool size_unknown, bool opengl_initialized);
|
||||||
GLVolume* new_toolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats = 0);
|
GLVolume* new_toolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats = 0);
|
||||||
GLVolume* new_nontoolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats = 0);
|
GLVolume* new_nontoolpath_volume(const std::array<float, 4>& rgba, size_t reserve_vbo_floats = 0);
|
||||||
|
|
||||||
|
@ -3071,61 +3071,88 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
|
|||||||
Vec3d plate_origin = ppl.get_plate(plate_id)->get_origin();
|
Vec3d plate_origin = ppl.get_plate(plate_id)->get_origin();
|
||||||
|
|
||||||
const Print* print = m_process->fff_print();
|
const Print* print = m_process->fff_print();
|
||||||
|
const Print* current_print = part_plate->fff_print();
|
||||||
float brim_width = print->wipe_tower_data(filaments_count).brim_width;
|
float brim_width = print->wipe_tower_data(filaments_count).brim_width;
|
||||||
const DynamicPrintConfig &print_cfg = wxGetApp().preset_bundle->prints.get_edited_preset().config;
|
const DynamicPrintConfig &print_cfg = wxGetApp().preset_bundle->prints.get_edited_preset().config;
|
||||||
double wipe_vol = get_max_element(v);
|
double wipe_vol = get_max_element(v);
|
||||||
int nozzle_nums = wxGetApp().preset_bundle->get_printer_extruder_count();
|
int nozzle_nums = wxGetApp().preset_bundle->get_printer_extruder_count();
|
||||||
Vec3d wipe_tower_size = ppl.get_plate(plate_id)->estimate_wipe_tower_size(print_cfg, w, wipe_vol, nozzle_nums);
|
Vec3d wipe_tower_size = ppl.get_plate(plate_id)->estimate_wipe_tower_size(print_cfg, w, wipe_vol, nozzle_nums);
|
||||||
|
|
||||||
{ // update for wipe tower position
|
{
|
||||||
part_plate->get_extruder_areas();
|
const float margin = WIPE_TOWER_MARGIN;
|
||||||
const float margin = WIPE_TOWER_MARGIN;
|
BoundingBoxf3 plate_bbox = part_plate->get_bounding_box();
|
||||||
BoundingBoxf3 plate_bbox = part_plate->get_bounding_box();
|
BoundingBoxf plate_bbox_2d(Vec2d(plate_bbox.min(0), plate_bbox.min(1)), Vec2d(plate_bbox.max(0), plate_bbox.max(1)));
|
||||||
BoundingBoxf plate_bbox_2d(Vec2d(plate_bbox.min(0), plate_bbox.min(1)), Vec2d(plate_bbox.max(0), plate_bbox.max(1)));
|
const std::vector<Pointfs> &extruder_areas = part_plate->get_extruder_areas();
|
||||||
const std::vector<Pointfs>& extruder_areas = part_plate->get_extruder_areas();
|
|
||||||
for (Pointfs points : extruder_areas) {
|
for (Pointfs points : extruder_areas) {
|
||||||
BoundingBoxf bboxf(points);
|
BoundingBoxf bboxf(points);
|
||||||
plate_bbox_2d.min = plate_bbox_2d.min(0) >= bboxf.min(0) ? plate_bbox_2d.min : bboxf.min;
|
plate_bbox_2d.min = plate_bbox_2d.min(0) >= bboxf.min(0) ? plate_bbox_2d.min : bboxf.min;
|
||||||
plate_bbox_2d.max = plate_bbox_2d.max(0) <= bboxf.max(0) ? plate_bbox_2d.max : bboxf.max;
|
plate_bbox_2d.max = plate_bbox_2d.max(0) <= bboxf.max(0) ? plate_bbox_2d.max : bboxf.max;
|
||||||
}
|
}
|
||||||
|
|
||||||
coordf_t plate_bbox_x_min_local_coord = plate_bbox_2d.min(0) - plate_origin(0);
|
coordf_t plate_bbox_x_min_local_coord = plate_bbox_2d.min(0) - plate_origin(0);
|
||||||
coordf_t plate_bbox_x_max_local_coord = plate_bbox_2d.max(0) - plate_origin(0);
|
coordf_t plate_bbox_x_max_local_coord = plate_bbox_2d.max(0) - plate_origin(0);
|
||||||
coordf_t plate_bbox_y_max_local_coord = plate_bbox_2d.max(1) - plate_origin(1);
|
coordf_t plate_bbox_y_max_local_coord = plate_bbox_2d.max(1) - plate_origin(1);
|
||||||
bool need_update = false;
|
|
||||||
if (x + margin + wipe_tower_size(0) > plate_bbox_x_max_local_coord) {
|
|
||||||
x = plate_bbox_x_max_local_coord - wipe_tower_size(0) - margin;
|
|
||||||
need_update = true;
|
|
||||||
} else if (x < margin + plate_bbox_x_min_local_coord) {
|
|
||||||
x = margin + plate_bbox_x_min_local_coord;
|
|
||||||
need_update = true;
|
|
||||||
}
|
|
||||||
if (need_update) {
|
|
||||||
ConfigOptionFloat wt_x_opt(x);
|
|
||||||
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_x"))->set_at(&wt_x_opt, plate_id, 0);
|
|
||||||
need_update = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (y + margin + wipe_tower_size(1) > plate_bbox_y_max_local_coord) {
|
if (!current_print->is_step_done(psWipeTower)) {
|
||||||
y = plate_bbox_y_max_local_coord - wipe_tower_size(1) - margin;
|
// update for wipe tower position
|
||||||
need_update = true;
|
{
|
||||||
} else if (y < margin) {
|
bool need_update = false;
|
||||||
y = margin;
|
if (x + margin + wipe_tower_size(0) > plate_bbox_x_max_local_coord) {
|
||||||
need_update = true;
|
x = plate_bbox_x_max_local_coord - wipe_tower_size(0) - margin;
|
||||||
}
|
need_update = true;
|
||||||
if (need_update) {
|
} else if (x < margin + plate_bbox_x_min_local_coord) {
|
||||||
ConfigOptionFloat wt_y_opt(y);
|
x = margin + plate_bbox_x_min_local_coord;
|
||||||
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_y"))->set_at(&wt_y_opt, plate_id, 0);
|
need_update = true;
|
||||||
|
}
|
||||||
|
if (need_update) {
|
||||||
|
ConfigOptionFloat wt_x_opt(x);
|
||||||
|
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_x"))->set_at(&wt_x_opt, plate_id, 0);
|
||||||
|
need_update = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (y + margin + wipe_tower_size(1) > plate_bbox_y_max_local_coord) {
|
||||||
|
y = plate_bbox_y_max_local_coord - wipe_tower_size(1) - margin;
|
||||||
|
need_update = true;
|
||||||
|
} else if (y < margin) {
|
||||||
|
y = margin;
|
||||||
|
need_update = true;
|
||||||
|
}
|
||||||
|
if (need_update) {
|
||||||
|
ConfigOptionFloat wt_y_opt(y);
|
||||||
|
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_y"))->set_at(&wt_y_opt, plate_id, 0);
|
||||||
|
}
|
||||||
|
int volume_idx_wipe_tower_new = m_volumes.load_wipe_tower_preview(1000 + plate_id, x + plate_origin(0), y + plate_origin(1),
|
||||||
|
(float) wipe_tower_size(0), (float) wipe_tower_size(1), (float) wipe_tower_size(2),
|
||||||
|
a,
|
||||||
|
/*!print->is_step_done(psWipeTower)*/ true, brim_width, m_initialized);
|
||||||
|
int volume_idx_wipe_tower_old = volume_idxs_wipe_tower_old[plate_id];
|
||||||
|
if (volume_idx_wipe_tower_old != -1) map_glvolume_old_to_new[volume_idx_wipe_tower_old] = volume_idx_wipe_tower_new;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
const float margin = 2.f;
|
||||||
|
auto tower_bottom = current_print->wipe_tower_data().wipe_tower_mesh_data->bottom;
|
||||||
|
tower_bottom.translate(scaled(Vec2d{x, y}));
|
||||||
|
tower_bottom.translate(scaled(Vec2d{plate_origin[0], plate_origin[1]}));
|
||||||
|
auto tower_bottom_bbox = get_extents(tower_bottom);
|
||||||
|
BoundingBoxf3 plate_bbox = wxGetApp().plater()->get_partplate_list().get_plate(plate_id)->get_build_volume(true);
|
||||||
|
BoundingBox plate_bbox2d = BoundingBox(scaled(Vec2f(plate_bbox.min[0], plate_bbox.min[1])), scaled(Vec2f(plate_bbox.max[0], plate_bbox.max[1])));
|
||||||
|
Vec2f offset = WipeTower::move_box_inside_box(tower_bottom_bbox, plate_bbox2d, scaled(margin));
|
||||||
|
if (!is_approx(offset[0], 0.f)) {
|
||||||
|
ConfigOptionFloat wt_x_opt(x + offset[0]);
|
||||||
|
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_x"))->set_at(&wt_x_opt, plate_id, 0);
|
||||||
|
}
|
||||||
|
if (!is_approx(offset[1], 0.f)) {
|
||||||
|
ConfigOptionFloat wt_y_opt(y + offset[1]);
|
||||||
|
dynamic_cast<ConfigOptionFloats *>(proj_cfg.option("wipe_tower_y"))->set_at(&wt_y_opt, plate_id, 0);
|
||||||
|
}
|
||||||
|
int volume_idx_wipe_tower_new = m_volumes.load_real_wipe_tower_preview(1000 + plate_id, x + plate_origin(0) + offset[0], y + plate_origin(1) + offset[1],
|
||||||
|
current_print->wipe_tower_data().wipe_tower_mesh_data->real_wipe_tower_mesh,
|
||||||
|
current_print->wipe_tower_data().wipe_tower_mesh_data->real_brim_mesh,
|
||||||
|
true,a,/*!print->is_step_done(psWipeTower)*/ true, m_initialized);
|
||||||
|
int volume_idx_wipe_tower_old = volume_idxs_wipe_tower_old[plate_id];
|
||||||
|
if (volume_idx_wipe_tower_old != -1) map_glvolume_old_to_new[volume_idx_wipe_tower_old] = volume_idx_wipe_tower_new;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int volume_idx_wipe_tower_new = m_volumes.load_wipe_tower_preview(
|
|
||||||
1000 + plate_id, x + plate_origin(0), y + plate_origin(1),
|
|
||||||
(float)wipe_tower_size(0), (float)wipe_tower_size(1), (float)wipe_tower_size(2), a,
|
|
||||||
/*!print->is_step_done(psWipeTower)*/ true, brim_width, m_initialized);
|
|
||||||
int volume_idx_wipe_tower_old = volume_idxs_wipe_tower_old[plate_id];
|
|
||||||
if (volume_idx_wipe_tower_old != -1)
|
|
||||||
map_glvolume_old_to_new[volume_idx_wipe_tower_old] = volume_idx_wipe_tower_new;
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -1196,28 +1196,32 @@ void Selection::translate(const Vec3d &displacement, TransformationType transfor
|
|||||||
if (v.is_wipe_tower) {//in world cs
|
if (v.is_wipe_tower) {//in world cs
|
||||||
int plate_idx = v.object_idx() - 1000;
|
int plate_idx = v.object_idx() - 1000;
|
||||||
BoundingBoxf3 plate_bbox = wxGetApp().plater()->get_partplate_list().get_plate(plate_idx)->get_build_volume(true);
|
BoundingBoxf3 plate_bbox = wxGetApp().plater()->get_partplate_list().get_plate(plate_idx)->get_build_volume(true);
|
||||||
|
BoundingBox plate_bbox2d = BoundingBox(scaled(Vec2f(plate_bbox.min[0], plate_bbox.min[1])), scaled(Vec2f(plate_bbox.max[0], plate_bbox.max[1])));
|
||||||
Vec3d tower_size = v.bounding_box().size();
|
Vec3d tower_size = v.bounding_box().size();
|
||||||
Vec3d tower_origin = m_cache.volumes_data[i].get_volume_position();
|
Vec3d tower_origin = m_cache.volumes_data[i].get_volume_position();
|
||||||
Vec3d actual_displacement = displacement;
|
Vec3d actual_displacement = displacement;
|
||||||
const double margin = WIPE_TOWER_MARGIN;
|
const double margin = wxGetApp().plater()->get_partplate_list().get_plate(plate_idx)->fff_print()->is_step_done(psWipeTower)?2.:WIPE_TOWER_MARGIN;
|
||||||
|
|
||||||
actual_displacement = (m_cache.volumes_data[i].get_instance_rotation_matrix() * m_cache.volumes_data[i].get_instance_scale_matrix() *
|
actual_displacement = (m_cache.volumes_data[i].get_instance_rotation_matrix() * m_cache.volumes_data[i].get_instance_scale_matrix() *
|
||||||
m_cache.volumes_data[i].get_instance_mirror_matrix())
|
m_cache.volumes_data[i].get_instance_mirror_matrix())
|
||||||
.inverse() *
|
.inverse() *
|
||||||
displacement;
|
displacement;
|
||||||
if (tower_origin(0) + actual_displacement(0) - margin < plate_bbox.min(0)) {
|
BoundingBoxf3 tower_bbox = v.bounding_box();
|
||||||
actual_displacement(0) = plate_bbox.min(0) - tower_origin(0) + margin;
|
tower_bbox.translate(actual_displacement + tower_origin);
|
||||||
} else if (tower_origin(0) + actual_displacement(0) + tower_size(0) + margin > plate_bbox.max(0)) {
|
BoundingBox tower_bbox2d = BoundingBox(scaled(Vec2f(tower_bbox.min[0], tower_bbox.min[1])), scaled(Vec2f(tower_bbox.max[0], tower_bbox.max[1])));
|
||||||
actual_displacement(0) = plate_bbox.max(0) - tower_origin(0) - tower_size(0) - margin;
|
Vec2f offset = WipeTower::move_box_inside_box(tower_bbox2d, plate_bbox2d,scaled(margin));
|
||||||
}
|
//if (tower_origin(0) + actual_displacement(0) - margin < plate_bbox.min(0)) {
|
||||||
|
// actual_displacement(0) = plate_bbox.min(0) - tower_origin(0) + margin;
|
||||||
if (tower_origin(1) + actual_displacement(1) - margin < plate_bbox.min(1)) {
|
//} else if (tower_origin(0) + actual_displacement(0) + tower_size(0) + margin > plate_bbox.max(0)) {
|
||||||
actual_displacement(1) = plate_bbox.min(1) - tower_origin(1) + margin;
|
// actual_displacement(0) = plate_bbox.max(0) - tower_origin(0) - tower_size(0) - margin;
|
||||||
} else if (tower_origin(1) + actual_displacement(1) + tower_size(1) + margin > plate_bbox.max(1)) {
|
//}
|
||||||
actual_displacement(1) = plate_bbox.max(1) - tower_origin(1) - tower_size(1) - margin;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
//if (tower_origin(1) + actual_displacement(1) - margin < plate_bbox.min(1)) {
|
||||||
|
// actual_displacement(1) = plate_bbox.min(1) - tower_origin(1) + margin;
|
||||||
|
//} else if (tower_origin(1) + actual_displacement(1) + tower_size(1) + margin > plate_bbox.max(1)) {
|
||||||
|
// actual_displacement(1) = plate_bbox.max(1) - tower_origin(1) - tower_size(1) - margin;
|
||||||
|
//}
|
||||||
|
actual_displacement += Vec3d(offset[0], offset[1],0);
|
||||||
v.set_volume_offset(m_cache.volumes_data[i].get_volume_position() + actual_displacement);
|
v.set_volume_offset(m_cache.volumes_data[i].get_volume_position() + actual_displacement);
|
||||||
}
|
}
|
||||||
else if (transformation_type.local() && transformation_type.absolute()) {
|
else if (transformation_type.local() && transformation_type.absolute()) {
|
||||||
|
Loading…
x
Reference in New Issue
Block a user