Tech ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS - Out of bed detection for circular printbeds

This commit is contained in:
enricoturri1966 2021-09-21 13:51:57 +02:00
parent 35579252b8
commit cf380fb456
16 changed files with 692 additions and 79 deletions

View File

@ -0,0 +1,130 @@
#version 110
#define INTENSITY_CORRECTION 0.6
// normalized values for (-0.6/1.31, 0.6/1.31, 1./1.31)
const vec3 LIGHT_TOP_DIR = vec3(-0.4574957, 0.4574957, 0.7624929);
#define LIGHT_TOP_DIFFUSE (0.8 * INTENSITY_CORRECTION)
#define LIGHT_TOP_SPECULAR (0.125 * INTENSITY_CORRECTION)
#define LIGHT_TOP_SHININESS 20.0
// normalized values for (1./1.43, 0.2/1.43, 1./1.43)
const vec3 LIGHT_FRONT_DIR = vec3(0.6985074, 0.1397015, 0.6985074);
#define LIGHT_FRONT_DIFFUSE (0.3 * INTENSITY_CORRECTION)
#define INTENSITY_AMBIENT 0.3
const vec3 ZERO = vec3(0.0, 0.0, 0.0);
const vec3 GREEN = vec3(0.0, 0.7, 0.0);
const vec3 YELLOW = vec3(0.5, 0.7, 0.0);
const vec3 RED = vec3(0.7, 0.0, 0.0);
const vec3 WHITE = vec3(1.0, 1.0, 1.0);
const float EPSILON = 0.0001;
const float BANDS_WIDTH = 10.0;
struct PrintVolumeDetection
{
// 0 = rectangle, 1 = circle, 2 = custom, 3 = invalid
int type;
// type = 0 (rectangle):
// x = min.x, y = min.y, z = max.x, w = max.y
// type = 1 (circle):
// x = center.x, y = center.y, z = radius
vec4 xy_data;
// x = min z, y = max z
vec2 z_data;
};
struct SlopeDetection
{
bool actived;
float normal_z;
mat3 volume_world_normal_matrix;
};
uniform vec4 uniform_color;
uniform SlopeDetection slope;
#ifdef ENABLE_ENVIRONMENT_MAP
uniform sampler2D environment_tex;
uniform bool use_environment_tex;
#endif // ENABLE_ENVIRONMENT_MAP
varying vec3 clipping_planes_dots;
// x = diffuse, y = specular;
varying vec2 intensity;
uniform PrintVolumeDetection print_volume;
varying vec4 model_pos;
varying vec4 world_pos;
varying float world_normal_z;
varying vec3 eye_normal;
uniform bool compute_triangle_normals_in_fs;
void main()
{
if (any(lessThan(clipping_planes_dots, ZERO)))
discard;
vec3 color = uniform_color.rgb;
float alpha = uniform_color.a;
vec2 intensity_fs = intensity;
vec3 eye_normal_fs = eye_normal;
float world_normal_z_fs = world_normal_z;
if (compute_triangle_normals_in_fs) {
vec3 triangle_normal = normalize(cross(dFdx(model_pos.xyz), dFdy(model_pos.xyz)));
#ifdef FLIP_TRIANGLE_NORMALS
triangle_normal = -triangle_normal;
#endif
// First transform the normal into camera space and normalize the result.
eye_normal_fs = normalize(gl_NormalMatrix * triangle_normal);
// Compute the cos of the angle between the normal and lights direction. The light is directional so the direction is constant for every vertex.
// Since these two are normalized the cosine is the dot product. We also need to clamp the result to the [0,1] range.
float NdotL = max(dot(eye_normal_fs, LIGHT_TOP_DIR), 0.0);
intensity_fs = vec2(0.0, 0.0);
intensity_fs.x = INTENSITY_AMBIENT + NdotL * LIGHT_TOP_DIFFUSE;
vec3 position = (gl_ModelViewMatrix * model_pos).xyz;
intensity_fs.y = LIGHT_TOP_SPECULAR * pow(max(dot(-normalize(position), reflect(-LIGHT_TOP_DIR, eye_normal_fs)), 0.0), LIGHT_TOP_SHININESS);
// Perform the same lighting calculation for the 2nd light source (no specular applied).
NdotL = max(dot(eye_normal_fs, LIGHT_FRONT_DIR), 0.0);
intensity_fs.x += NdotL * LIGHT_FRONT_DIFFUSE;
// z component of normal vector in world coordinate used for slope shading
world_normal_z_fs = slope.actived ? (normalize(slope.volume_world_normal_matrix * triangle_normal)).z : 0.0;
}
if (slope.actived && world_normal_z_fs < slope.normal_z - EPSILON) {
color = vec3(0.7, 0.7, 1.0);
alpha = 1.0;
}
// if the fragment is outside the print volume -> use darker color
vec3 pv_check_min = ZERO;
vec3 pv_check_max = ZERO;
if (print_volume.type == 0) {
// rectangle
pv_check_min = world_pos.xyz - vec3(print_volume.xy_data.x, print_volume.xy_data.y, print_volume.z_data.x);
pv_check_max = world_pos.xyz - vec3(print_volume.xy_data.z, print_volume.xy_data.w, print_volume.z_data.y);
}
else if (print_volume.type == 1) {
// circle
float delta_radius = print_volume.xy_data.z - distance(world_pos.xy, print_volume.xy_data.xy);
pv_check_min = vec3(delta_radius, 0.0, world_pos.z - print_volume.z_data.x);
pv_check_max = vec3(0.0, 0.0, world_pos.z - print_volume.z_data.y);
}
color = (any(lessThan(pv_check_min, ZERO)) || any(greaterThan(pv_check_max, ZERO))) ? mix(color, ZERO, 0.3333) : color;
#ifdef ENABLE_ENVIRONMENT_MAP
if (use_environment_tex)
gl_FragColor = vec4(0.45 * texture2D(environment_tex, normalize(eye_normal_fs).xy * 0.5 + 0.5).xyz + 0.8 * color * intensity_fs.x, alpha);
else
#endif
gl_FragColor = vec4(vec3(intensity_fs.y) + color * intensity_fs.x, alpha);
}

View File

@ -0,0 +1,78 @@
#version 110
#define INTENSITY_CORRECTION 0.6
// normalized values for (-0.6/1.31, 0.6/1.31, 1./1.31)
const vec3 LIGHT_TOP_DIR = vec3(-0.4574957, 0.4574957, 0.7624929);
#define LIGHT_TOP_DIFFUSE (0.8 * INTENSITY_CORRECTION)
#define LIGHT_TOP_SPECULAR (0.125 * INTENSITY_CORRECTION)
#define LIGHT_TOP_SHININESS 20.0
// normalized values for (1./1.43, 0.2/1.43, 1./1.43)
const vec3 LIGHT_FRONT_DIR = vec3(0.6985074, 0.1397015, 0.6985074);
#define LIGHT_FRONT_DIFFUSE (0.3 * INTENSITY_CORRECTION)
//#define LIGHT_FRONT_SPECULAR (0.0 * INTENSITY_CORRECTION)
//#define LIGHT_FRONT_SHININESS 5.0
#define INTENSITY_AMBIENT 0.3
const vec3 ZERO = vec3(0.0, 0.0, 0.0);
struct SlopeDetection
{
bool actived;
float normal_z;
mat3 volume_world_normal_matrix;
};
uniform mat4 volume_world_matrix;
uniform SlopeDetection slope;
// Clipping plane, x = min z, y = max z. Used by the FFF and SLA previews to clip with a top / bottom plane.
uniform vec2 z_range;
// Clipping plane - general orientation. Used by the SLA gizmo.
uniform vec4 clipping_plane;
// x = diffuse, y = specular;
varying vec2 intensity;
varying vec3 clipping_planes_dots;
varying vec4 model_pos;
varying vec4 world_pos;
varying float world_normal_z;
varying vec3 eye_normal;
uniform bool compute_triangle_normals_in_fs;
void main()
{
if (!compute_triangle_normals_in_fs) {
// First transform the normal into camera space and normalize the result.
eye_normal = normalize(gl_NormalMatrix * gl_Normal);
// Compute the cos of the angle between the normal and lights direction. The light is directional so the direction is constant for every vertex.
// Since these two are normalized the cosine is the dot product. We also need to clamp the result to the [0,1] range.
float NdotL = max(dot(eye_normal, LIGHT_TOP_DIR), 0.0);
intensity.x = INTENSITY_AMBIENT + NdotL * LIGHT_TOP_DIFFUSE;
vec3 position = (gl_ModelViewMatrix * gl_Vertex).xyz;
intensity.y = LIGHT_TOP_SPECULAR * pow(max(dot(-normalize(position), reflect(-LIGHT_TOP_DIR, eye_normal)), 0.0), LIGHT_TOP_SHININESS);
// Perform the same lighting calculation for the 2nd light source (no specular applied).
NdotL = max(dot(eye_normal, LIGHT_FRONT_DIR), 0.0);
intensity.x += NdotL * LIGHT_FRONT_DIFFUSE;
}
model_pos = gl_Vertex;
// Point in homogenous coordinates.
world_pos = volume_world_matrix * gl_Vertex;
// z component of normal vector in world coordinate used for slope shading
if (!compute_triangle_normals_in_fs)
world_normal_z = slope.actived ? (normalize(slope.volume_world_normal_matrix * gl_Normal)).z : 0.0;
gl_Position = ftransform();
// Fill in the scalars for fragment shader clipping. Fragments with any of these components lower than zero are discarded.
clipping_planes_dots = vec3(dot(world_pos, clipping_plane), world_pos.z - z_range.x, z_range.y - world_pos.z);
}

View File

@ -305,6 +305,15 @@ bool directions_parallel(double angle1, double angle2, double max_diff)
return diff < max_diff || fabs(diff - PI) < max_diff;
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool directions_perpendicular(double angle1, double angle2, double max_diff)
{
double diff = fabs(angle1 - angle2);
max_diff += EPSILON;
return fabs(diff - 0.5 * PI) < max_diff || fabs(diff - 1.5 * PI) < max_diff;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
template<class T>
bool contains(const std::vector<T> &vector, const Point &point)
{

View File

@ -336,6 +336,9 @@ Polygon convex_hull(Points points);
Polygon convex_hull(const Polygons &polygons);
bool directions_parallel(double angle1, double angle2, double max_diff = 0);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool directions_perpendicular(double angle1, double angle2, double max_diff = 0);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
template<class T> bool contains(const std::vector<T> &vector, const Point &point);
template<typename T> T rad2deg(T angle) { return T(180.0) * angle / T(PI); }
double rad2deg_dir(double angle);

View File

@ -63,6 +63,13 @@ bool Line::parallel_to(double angle) const
return Slic3r::Geometry::directions_parallel(this->direction(), angle);
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool Line::perpendicular_to(double angle) const
{
return Slic3r::Geometry::directions_perpendicular(this->direction(), angle);
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool Line::intersection(const Line &l2, Point *intersection) const
{
const Line &l1 = *this;

View File

@ -85,6 +85,10 @@ public:
double perp_distance_to(const Point &point) const;
bool parallel_to(double angle) const;
bool parallel_to(const Line &line) const { return this->parallel_to(line.direction()); }
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool perpendicular_to(double angle) const;
bool perpendicular_to(const Line& line) const { return this->perpendicular_to(line.direction()); }
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
double atan2_() const { return atan2(this->b(1) - this->a(1), this->b(0) - this->a(0)); }
double orientation() const;
double direction() const;

View File

@ -7,11 +7,10 @@
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/Geometry.hpp"
#include "libslic3r/Tesselate.hpp"
#include "libslic3r/PresetBundle.hpp"
#include "GUI_App.hpp"
#include "libslic3r/PresetBundle.hpp"
#include "GLCanvas3D.hpp"
#include "3DScene.hpp"
#include <GL/glew.h>
@ -154,7 +153,11 @@ bool Bed3D::set_shape(const Pointfs& shape, const std::string& custom_texture, c
std::string model;
std::string texture;
if (force_as_custom)
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
type = EType::Custom;
#else
type = Custom;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
else {
auto [new_type, system_model, system_texture] = detect_type(shape);
type = new_type;
@ -174,7 +177,12 @@ bool Bed3D::set_shape(const Pointfs& shape, const std::string& custom_texture, c
model_filename.clear();
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
EShapeType shape_type = detect_shape_type(shape);
if (m_shape == shape && m_type == type && m_shape_type == shape_type && m_texture_filename == texture_filename && m_model_filename == model_filename)
#else
if (m_shape == shape && m_type == type && m_texture_filename == texture_filename && m_model_filename == model_filename)
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// No change, no need to update the UI.
return false;
@ -182,6 +190,9 @@ bool Bed3D::set_shape(const Pointfs& shape, const std::string& custom_texture, c
m_texture_filename = texture_filename;
m_model_filename = model_filename;
m_type = type;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
m_shape_type = shape_type;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
calc_bounding_boxes();
@ -229,6 +240,77 @@ void Bed3D::render_for_picking(GLCanvas3D& canvas, bool bottom, float scale_fact
render_internal(canvas, bottom, scale_factor, false, false, true);
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool Bed3D::is_rectangle(const Pointfs& shape, Vec2d* min, Vec2d* max)
{
const Lines lines = Polygon::new_scale(shape).lines();
bool ret = lines.size() == 4 && lines[0].parallel_to(lines[2]) && lines[1].parallel_to(lines[3]) && lines[0].perpendicular_to(lines[1]);
if (ret) {
if (min != nullptr) {
*min = shape.front();
for (const Vec2d& pt : shape) {
min->x() = std::min(min->x(), pt.x());
min->y() = std::min(min->y(), pt.y());
}
}
if (max != nullptr) {
*max = shape.front();
for (const Vec2d& pt : shape) {
max->x() = std::max(max->x(), pt.x());
max->y() = std::max(max->y(), pt.y());
}
}
}
return ret;
}
bool Bed3D::is_circle(const Pointfs& shape, Vec2d* center, double* radius)
{
if (shape.size() < 3)
return false;
// Analyze the array of points.
// Do they reside on a circle ?
const Vec2d box_center = BoundingBoxf(shape).center();
std::vector<double> vertex_distances;
double avg_dist = 0.0;
for (const Vec2d& pt : shape) {
double distance = (pt - box_center).norm();
vertex_distances.push_back(distance);
avg_dist += distance;
}
avg_dist /= vertex_distances.size();
bool defined_value = true;
for (double el : vertex_distances) {
if (fabs(el - avg_dist) > 10.0 * SCALED_EPSILON)
defined_value = false;
break;
}
if (center != nullptr)
*center = box_center;
if (radius != nullptr)
*radius = avg_dist;
return defined_value;
}
Bed3D::EShapeType Bed3D::detect_shape_type(const Pointfs& shape)
{
if (shape.size() < 3)
return EShapeType::Invalid;
else if (is_rectangle(shape))
return EShapeType::Rectangle;
else if (is_circle(shape))
return EShapeType::Circle;
else
return EShapeType::Custom;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
void Bed3D::render_internal(GLCanvas3D& canvas, bool bottom, float scale_factor,
bool show_axes, bool show_texture, bool picking)
{
@ -244,9 +326,15 @@ void Bed3D::render_internal(GLCanvas3D& canvas, bool bottom, float scale_factor,
switch (m_type)
{
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
case EType::System: { render_system(canvas, bottom, show_texture); break; }
default:
case EType::Custom: { render_custom(canvas, bottom, show_texture, picking); break; }
#else
case System: { render_system(canvas, bottom, show_texture); break; }
default:
case Custom: { render_custom(canvas, bottom, show_texture, picking); break; }
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
glsafe(::glDisable(GL_DEPTH_TEST));
@ -320,7 +408,11 @@ std::tuple<Bed3D::EType, std::string, std::string> Bed3D::detect_type(const Poin
std::string model_filename = PresetUtils::system_printer_bed_model(*curr);
std::string texture_filename = PresetUtils::system_printer_bed_texture(*curr);
if (!model_filename.empty() && !texture_filename.empty())
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
return { EType::System, model_filename, texture_filename };
#else
return { System, model_filename, texture_filename };
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
}
@ -328,7 +420,11 @@ std::tuple<Bed3D::EType, std::string, std::string> Bed3D::detect_type(const Poin
}
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
return { EType::Custom, "", "" };
#else
return { Custom, "", "" };
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
void Bed3D::render_axes() const

View File

@ -62,15 +62,36 @@ class Bed3D
};
public:
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
enum class EType : unsigned char
{
System,
Custom
};
enum class EShapeType : unsigned char
{
Rectangle,
Circle,
Custom,
Invalid
};
#else
enum EType : unsigned char
{
System,
Custom,
Num_Types
};
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
private:
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
EType m_type{ EType::Custom };
EShapeType m_shape_type{ EShapeType::Invalid };
#else
EType m_type{ Custom };
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Pointfs m_shape;
std::string m_texture_filename;
std::string m_model_filename;
@ -94,16 +115,18 @@ public:
~Bed3D() { reset(); }
EType get_type() const { return m_type; }
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
EShapeType get_shape_type() const { return m_shape_type; }
bool is_custom() const { return m_type == EType::Custom; }
#else
bool is_custom() const { return m_type == Custom; }
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
const Pointfs& get_shape() const { return m_shape; }
// Return true if the bed shape changed, so the calee will update the UI.
bool set_shape(const Pointfs& shape, const std::string& custom_texture, const std::string& custom_model, bool force_as_custom = false);
const BoundingBoxf3& get_bounding_box(bool extended) const {
return extended ? m_extended_bounding_box : m_bounding_box;
}
const BoundingBoxf3& get_bounding_box(bool extended) const { return extended ? m_extended_bounding_box : m_bounding_box; }
bool contains(const Point& point) const;
Point point_projection(const Point& point) const;
@ -113,6 +136,12 @@ public:
void render_for_picking(GLCanvas3D& canvas, bool bottom, float scale_factor);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
static bool is_rectangle(const Pointfs& shape, Vec2d* min = nullptr, Vec2d* max = nullptr);
static bool is_circle(const Pointfs& shape, Vec2d* center = nullptr, double* radius = nullptr);
static EShapeType detect_shape_type(const Pointfs& shape);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
private:
void calc_bounding_boxes() const;
void calc_triangles(const ExPolygon& poly);

View File

@ -873,10 +873,17 @@ void GLVolumeCollection::render(GLVolumeCollection::ERenderType type, bool disab
shader->set_uniform("uniform_color", volume.first->render_color);
shader->set_uniform("z_range", m_z_range, 2);
shader->set_uniform("clipping_plane", m_clipping_plane, 4);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
shader->set_uniform("print_volume.type", static_cast<int>(m_print_volume.type));
shader->set_uniform("print_volume.xy_data", m_print_volume.data);
shader->set_uniform("print_volume.z_data", m_print_volume.zs);
shader->set_uniform("volume_world_matrix", volume.first->world_matrix());
#else
shader->set_uniform("print_box.min", m_print_box_min, 3);
shader->set_uniform("print_box.max", m_print_box_max, 3);
shader->set_uniform("print_box.actived", volume.first->shader_outside_printer_detection_enabled);
shader->set_uniform("print_box.volume_world_matrix", volume.first->world_matrix());
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
shader->set_uniform("slope.actived", m_slope.active && !volume.first->is_modifier && !volume.first->is_wipe_tower);
shader->set_uniform("slope.volume_world_normal_matrix", static_cast<Matrix3f>(volume.first->world_matrix().matrix().block(0, 0, 3, 3).inverse().transpose().cast<float>()));
shader->set_uniform("slope.normal_z", m_slope.normal_z);
@ -925,6 +932,31 @@ void GLVolumeCollection::render(GLVolumeCollection::ERenderType type, bool disab
glsafe(::glDisable(GL_BLEND));
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
static bool same(const Polygon& lhs, const Polygon& rhs)
{
if (lhs.points.size() != rhs.points.size())
return false;
size_t rhs_id = 0;
while (rhs_id < rhs.points.size()) {
if (rhs.points[rhs_id].isApprox(lhs.points.front()))
break;
++rhs_id;
}
if (rhs_id == rhs.points.size())
return false;
for (size_t i = 0; i < lhs.points.size(); ++i) {
if (!lhs.points[i].isApprox(rhs.points[(i + rhs_id) % lhs.points.size()]))
return false;
}
return true;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool GLVolumeCollection::check_outside_state(const DynamicPrintConfig* config, ModelInstanceEPrintVolumeState* out_state) const
{
if (config == nullptr)
@ -934,6 +966,10 @@ bool GLVolumeCollection::check_outside_state(const DynamicPrintConfig* config, M
if (opt == nullptr)
return false;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
const Polygon bed_poly = offset(Polygon::new_scale(opt->values), static_cast<float>(scale_(BedEpsilon))).front();
const float bed_height = config->opt_float("max_print_height");
#else
const BoundingBox bed_box_2D = get_extents(Polygon::new_scale(opt->values));
BoundingBoxf3 print_volume({ unscale<double>(bed_box_2D.min.x()), unscale<double>(bed_box_2D.min.y()), 0.0 },
{ unscale<double>(bed_box_2D.max.x()), unscale<double>(bed_box_2D.max.y()), config->opt_float("max_print_height") });
@ -943,6 +979,7 @@ bool GLVolumeCollection::check_outside_state(const DynamicPrintConfig* config, M
print_volume.min.y() -= BedEpsilon;
print_volume.max.x() += BedEpsilon;
print_volume.max.y() += BedEpsilon;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
ModelInstanceEPrintVolumeState state = ModelInstancePVS_Inside;
@ -957,7 +994,19 @@ bool GLVolumeCollection::check_outside_state(const DynamicPrintConfig* config, M
#else
const BoundingBoxf3& bb = volume->transformed_convex_hull_bounding_box();
#endif // ENABLE_FIX_SINKING_OBJECT_OUT_OF_BED_DETECTION
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
const indexed_triangle_set& its = GUI::wxGetApp().plater()->model().objects[volume->object_idx()]->volumes[volume->volume_idx()]->mesh().its;
const Polygon volume_hull_2d = its_convex_hull_2d_above(its, volume->world_matrix().cast<float>(), 0.0f);
Polygons intersection_polys = intersection(bed_poly, volume_hull_2d);
bool contained_xy = !intersection_polys.empty() && same(intersection_polys.front(), volume_hull_2d);
bool contained_z = -1e10 < bb.min.z() && bb.max.z() < bed_height;
bool contained = contained_xy && contained_z;
bool intersects_xy = !contained_xy && !intersection_polys.empty();
bool intersects_z = !contained_z && bb.min.z() < bed_height && -1e10 < bb.max.z();
bool intersects = intersects_xy || intersects_z;
#else
bool contained = print_volume.contains(bb);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
volume->is_outside = !contained;
if (!volume->printable)
@ -968,8 +1017,13 @@ bool GLVolumeCollection::check_outside_state(const DynamicPrintConfig* config, M
if (state == ModelInstancePVS_Inside && volume->is_outside)
state = ModelInstancePVS_Fully_Outside;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (state == ModelInstancePVS_Fully_Outside && volume->is_outside && intersects)
state = ModelInstancePVS_Partly_Outside;
#else
if (state == ModelInstancePVS_Fully_Outside && volume->is_outside && print_volume.intersects(bb))
state = ModelInstancePVS_Partly_Outside;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
if (out_state != nullptr)

View File

@ -532,10 +532,30 @@ public:
All
};
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
struct PrintVolume
{
// see: Bed3D::EShapeType
int type{ 0 };
// data contains:
// Rectangle:
// [0] = min.x, [1] = min.y, [2] = max.x, [3] = max.y
// Circle:
// [0] = center.x, [1] = center.y, [3] = radius
std::array<float, 4> data;
// [0] = min z, [1] = max z
std::array<float, 2> zs;
};
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
private:
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
PrintVolume m_print_volume;
#else
// min and max vertex of the print box volume
float m_print_box_min[3];
float m_print_box_max[3];
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// z range for clipping in shaders
float m_z_range[2];
@ -607,10 +627,14 @@ public:
bool empty() const { return volumes.empty(); }
void set_range(double low, double high) { for (GLVolume *vol : this->volumes) vol->set_range(low, high); }
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
void set_print_volume(const PrintVolume& print_volume) { m_print_volume = print_volume; }
#else
void set_print_box(float min_x, float min_y, float min_z, float max_x, float max_y, float max_z) {
m_print_box_min[0] = min_x; m_print_box_min[1] = min_y; m_print_box_min[2] = min_z;
m_print_box_max[0] = max_x; m_print_box_max[1] = max_y; m_print_box_max[2] = max_z;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
void set_z_range(float min_z, float max_z) { m_z_range[0] = min_z; m_z_range[1] = max_z; }
void set_clipping_plane(const double* coeffs) { m_clipping_plane[0] = coeffs[0]; m_clipping_plane[1] = coeffs[1]; m_clipping_plane[2] = coeffs[2]; m_clipping_plane[3] = coeffs[3]; }

View File

@ -22,9 +22,25 @@ namespace GUI {
BedShape::BedShape(const ConfigOptionPoints& points)
{
auto polygon = Polygon::new_scale(points.values);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (points.size() < 3) {
m_type = Bed3D::EShapeType::Invalid;
return;
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// is this a rectangle ?
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Vec2d min;
Vec2d max;
if (Bed3D::is_rectangle(points.values, &min, &max)) {
m_type = Bed3D::EShapeType::Rectangle;
m_rectSize = max - min;
m_rectOrigin = -min;
return;
}
#else
Polygon polygon = Polygon::new_scale(points.values);
if (points.size() == 4) {
auto lines = polygon.lines();
if (lines[0].parallel_to(lines[2]) && lines[1].parallel_to(lines[3])) {
@ -48,8 +64,21 @@ BedShape::BedShape(const ConfigOptionPoints& points)
return;
}
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// is this a circle ?
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Vec2d center;
double radius;
if (Bed3D::is_circle(points.values, &center, &radius)) {
m_type = Bed3D::EShapeType::Circle;
m_diameter = 2.0 * radius;
return;
}
// This is a custom bed shape, use the polygon provided.
m_type = Bed3D::EShapeType::Custom;
#else
{
// Analyze the array of points.Do they reside on a circle ?
auto center = polygon.bounding_box().center();
@ -84,6 +113,7 @@ BedShape::BedShape(const ConfigOptionPoints& points)
// This is a custom bed shape, use the polygon provided.
m_type = Type::Custom;
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
static std::string get_option_label(BedShape::Parameter param)
@ -134,6 +164,18 @@ void BedShape::append_option_line(ConfigOptionsGroupShp optgroup, Parameter para
}
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
wxString BedShape::get_name(Bed3D::EShapeType type)
{
switch (type) {
case Bed3D::EShapeType::Rectangle: { return _L("Rectangular"); }
case Bed3D::EShapeType::Circle: { return _L("Circular"); }
case Bed3D::EShapeType::Custom: { return _L("Custom"); }
case Bed3D::EShapeType::Invalid:
default: return _L("Invalid");
}
}
#else
wxString BedShape::get_name(Type type)
{
switch (type) {
@ -144,21 +186,34 @@ wxString BedShape::get_name(Type type)
default: return _L("Invalid");
}
}
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
size_t BedShape::get_type()
{
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
return static_cast<size_t>(m_type == Bed3D::EShapeType::Invalid ? Bed3D::EShapeType::Rectangle : m_type);
#else
return static_cast<size_t>(m_type == Type::Invalid ? Type::Rectangular : m_type);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
}
wxString BedShape::get_full_name_with_params()
{
wxString out = _L("Shape") + ": " + get_name(m_type);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (m_type == Bed3D::EShapeType::Rectangle) {
#else
if (m_type == Type::Rectangular) {
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
out += "\n" + _(get_option_label(Parameter::RectSize)) + ": [" + ConfigOptionPoint(m_rectSize).serialize() + "]";
out += "\n" + _(get_option_label(Parameter::RectOrigin))+ ": [" + ConfigOptionPoint(m_rectOrigin).serialize() + "]";
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
else if (m_type == Bed3D::EShapeType::Circle)
#else
else if (m_type == Type::Circular)
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
out += "\n" + _L(get_option_label(Parameter::Diameter)) + ": [" + double_to_string(m_diameter) + "]";
return out;
@ -166,11 +221,19 @@ wxString BedShape::get_full_name_with_params()
void BedShape::apply_optgroup_values(ConfigOptionsGroupShp optgroup)
{
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (m_type == Bed3D::EShapeType::Rectangle || m_type == Bed3D::EShapeType::Invalid) {
#else
if (m_type == Type::Rectangular || m_type == Type::Invalid) {
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
optgroup->set_value("rect_size" , new ConfigOptionPoints{ m_rectSize });
optgroup->set_value("rect_origin" , new ConfigOptionPoints{ m_rectOrigin });
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
else if (m_type == Bed3D::EShapeType::Circle)
#else
else if (m_type == Type::Circular)
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
optgroup->set_value("diameter", double_to_string(m_diameter));
}
@ -222,7 +285,7 @@ void BedShapePanel::build_panel(const ConfigOptionPoints& default_pt, const Conf
m_custom_texture = custom_texture.value.empty() ? NONE : custom_texture.value;
m_custom_model = custom_model.value.empty() ? NONE : custom_model.value;
auto sbsizer = new wxStaticBoxSizer(wxVERTICAL, this, _(L("Shape")));
auto sbsizer = new wxStaticBoxSizer(wxVERTICAL, this, _L("Shape"));
sbsizer->GetStaticBox()->SetFont(wxGetApp().bold_font());
wxGetApp().UpdateDarkUI(sbsizer->GetStaticBox());
@ -232,16 +295,28 @@ void BedShapePanel::build_panel(const ConfigOptionPoints& default_pt, const Conf
sbsizer->Add(m_shape_options_book);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
auto optgroup = init_shape_options_page(BedShape::get_name(Bed3D::EShapeType::Rectangle));
#else
auto optgroup = init_shape_options_page(BedShape::get_name(BedShape::Type::Rectangular));
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
BedShape::append_option_line(optgroup, BedShape::Parameter::RectSize);
BedShape::append_option_line(optgroup, BedShape::Parameter::RectOrigin);
activate_options_page(optgroup);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
optgroup = init_shape_options_page(BedShape::get_name(Bed3D::EShapeType::Circle));
#else
optgroup = init_shape_options_page(BedShape::get_name(BedShape::Type::Circular));
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
BedShape::append_option_line(optgroup, BedShape::Parameter::Diameter);
activate_options_page(optgroup);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
optgroup = init_shape_options_page(BedShape::get_name(Bed3D::EShapeType::Custom));
#else
optgroup = init_shape_options_page(BedShape::get_name(BedShape::Type::Custom));
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Line line{ "", "" };
line.full_width = 1;
@ -265,10 +340,7 @@ void BedShapePanel::build_panel(const ConfigOptionPoints& default_pt, const Conf
wxPanel* texture_panel = init_texture_panel();
wxPanel* model_panel = init_model_panel();
Bind(wxEVT_CHOICEBOOK_PAGE_CHANGED, ([this](wxCommandEvent& e)
{
update_shape();
}));
Bind(wxEVT_CHOICEBOOK_PAGE_CHANGED, ([this](wxCommandEvent& e) { update_shape(); }));
// right pane with preview canvas
m_canvas = new Bed_2D(this);
@ -295,7 +367,7 @@ void BedShapePanel::build_panel(const ConfigOptionPoints& default_pt, const Conf
ConfigOptionsGroupShp BedShapePanel::init_shape_options_page(const wxString& title)
{
wxPanel* panel = new wxPanel(m_shape_options_book);
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _(L("Settings")));
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _L("Settings"));
optgroup->label_width = 10;
optgroup->m_on_change = [this](t_config_option_key opt_key, boost::any value) {
@ -319,7 +391,7 @@ wxPanel* BedShapePanel::init_texture_panel()
{
wxPanel* panel = new wxPanel(this);
wxGetApp().UpdateDarkUI(panel, true);
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _(L("Texture")));
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _L("Texture"));
optgroup->label_width = 10;
optgroup->m_on_change = [this](t_config_option_key opt_key, boost::any value) {
@ -329,7 +401,7 @@ wxPanel* BedShapePanel::init_texture_panel()
Line line{ "", "" };
line.full_width = 1;
line.widget = [this](wxWindow* parent) {
wxButton* load_btn = new wxButton(parent, wxID_ANY, _(L("Load...")));
wxButton* load_btn = new wxButton(parent, wxID_ANY, _L("Load..."));
wxSizer* load_sizer = new wxBoxSizer(wxHORIZONTAL);
load_sizer->Add(load_btn, 1, wxEXPAND);
@ -338,7 +410,7 @@ wxPanel* BedShapePanel::init_texture_panel()
wxSizer* filename_sizer = new wxBoxSizer(wxHORIZONTAL);
filename_sizer->Add(filename_lbl, 1, wxEXPAND);
wxButton* remove_btn = new wxButton(parent, wxID_ANY, _(L("Remove")));
wxButton* remove_btn = new wxButton(parent, wxID_ANY, _L("Remove"));
wxSizer* remove_sizer = new wxBoxSizer(wxHORIZONTAL);
remove_sizer->Add(remove_btn, 1, wxEXPAND);
@ -347,31 +419,23 @@ wxPanel* BedShapePanel::init_texture_panel()
sizer->Add(load_sizer, 1, wxEXPAND);
sizer->Add(remove_sizer, 1, wxEXPAND | wxTOP, 2);
load_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e)
{
load_texture();
}));
remove_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e)
{
load_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e) { load_texture(); }));
remove_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e) {
m_custom_texture = NONE;
update_shape();
}));
filename_lbl->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e)
{
filename_lbl->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e) {
e.SetText(_(boost::filesystem::path(m_custom_texture).filename().string()));
wxStaticText* lbl = dynamic_cast<wxStaticText*>(e.GetEventObject());
if (lbl != nullptr)
{
if (lbl != nullptr) {
bool exists = (m_custom_texture == NONE) || boost::filesystem::exists(m_custom_texture);
lbl->SetForegroundColour(exists ? /*wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOWTEXT)*/wxGetApp().get_label_clr_default() : wxColor(*wxRED));
wxString tooltip_text = "";
if (m_custom_texture != NONE)
{
if (m_custom_texture != NONE) {
if (!exists)
tooltip_text += _(L("Not found:")) + " ";
tooltip_text += _L("Not found:") + " ";
tooltip_text += _(m_custom_texture);
}
@ -382,10 +446,7 @@ wxPanel* BedShapePanel::init_texture_panel()
}
}));
remove_btn->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e)
{
e.Enable(m_custom_texture != NONE);
}));
remove_btn->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e) { e.Enable(m_custom_texture != NONE); }));
return sizer;
};
@ -401,7 +462,7 @@ wxPanel* BedShapePanel::init_model_panel()
{
wxPanel* panel = new wxPanel(this);
wxGetApp().UpdateDarkUI(panel, true);
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _(L("Model")));
ConfigOptionsGroupShp optgroup = std::make_shared<ConfigOptionsGroup>(panel, _L("Model"));
optgroup->label_width = 10;
optgroup->m_on_change = [this](t_config_option_key opt_key, boost::any value) {
@ -411,7 +472,7 @@ wxPanel* BedShapePanel::init_model_panel()
Line line{ "", "" };
line.full_width = 1;
line.widget = [this](wxWindow* parent) {
wxButton* load_btn = new wxButton(parent, wxID_ANY, _(L("Load...")));
wxButton* load_btn = new wxButton(parent, wxID_ANY, _L("Load..."));
wxSizer* load_sizer = new wxBoxSizer(wxHORIZONTAL);
load_sizer->Add(load_btn, 1, wxEXPAND);
@ -419,7 +480,7 @@ wxPanel* BedShapePanel::init_model_panel()
wxSizer* filename_sizer = new wxBoxSizer(wxHORIZONTAL);
filename_sizer->Add(filename_lbl, 1, wxEXPAND);
wxButton* remove_btn = new wxButton(parent, wxID_ANY, _(L("Remove")));
wxButton* remove_btn = new wxButton(parent, wxID_ANY, _L("Remove"));
wxSizer* remove_sizer = new wxBoxSizer(wxHORIZONTAL);
remove_sizer->Add(remove_btn, 1, wxEXPAND);
@ -428,31 +489,24 @@ wxPanel* BedShapePanel::init_model_panel()
sizer->Add(load_sizer, 1, wxEXPAND);
sizer->Add(remove_sizer, 1, wxEXPAND | wxTOP, 2);
load_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e)
{
load_model();
}));
load_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e) { load_model(); }));
remove_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e)
{
remove_btn->Bind(wxEVT_BUTTON, ([this](wxCommandEvent& e) {
m_custom_model = NONE;
update_shape();
}));
filename_lbl->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e)
{
filename_lbl->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e) {
e.SetText(_(boost::filesystem::path(m_custom_model).filename().string()));
wxStaticText* lbl = dynamic_cast<wxStaticText*>(e.GetEventObject());
if (lbl != nullptr)
{
if (lbl != nullptr) {
bool exists = (m_custom_model == NONE) || boost::filesystem::exists(m_custom_model);
lbl->SetForegroundColour(exists ? /*wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOWTEXT)*/wxGetApp().get_label_clr_default() : wxColor(*wxRED));
wxString tooltip_text = "";
if (m_custom_model != NONE)
{
if (m_custom_model != NONE) {
if (!exists)
tooltip_text += _(L("Not found:")) + " ";
tooltip_text += _L("Not found:") + " ";
tooltip_text += _(m_custom_model);
}
@ -463,10 +517,7 @@ wxPanel* BedShapePanel::init_model_panel()
}
}));
remove_btn->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e)
{
e.Enable(m_custom_model != NONE);
}));
remove_btn->Bind(wxEVT_UPDATE_UI, ([this](wxUpdateUIEvent& e) { e.Enable(m_custom_model != NONE); }));
return sizer;
};
@ -511,9 +562,17 @@ void BedShapePanel::update_shape()
auto page_idx = m_shape_options_book->GetSelection();
auto opt_group = m_optgroups[page_idx];
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Bed3D::EShapeType page_type = static_cast<Bed3D::EShapeType>(page_idx);
#else
BedShape::Type page_type = static_cast<BedShape::Type>(page_idx);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (page_type == Bed3D::EShapeType::Rectangle) {
#else
if (page_type == BedShape::Type::Rectangular) {
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Vec2d rect_size(Vec2d::Zero());
Vec2d rect_origin(Vec2d::Zero());
@ -544,7 +603,11 @@ void BedShapePanel::update_shape()
Vec2d(x1, y1),
Vec2d(x0, y1) };
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
else if (page_type == Bed3D::EShapeType::Circle) {
#else
else if (page_type == BedShape::Type::Circular) {
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
double diameter;
try { diameter = boost::any_cast<double>(opt_group->get_value("diameter")); }
catch (const std::exception & /* e */) { return; }
@ -560,7 +623,11 @@ void BedShapePanel::update_shape()
}
m_shape = points;
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
else if (page_type == Bed3D::EShapeType::Custom)
#else
else if (page_type == BedShape::Type::Custom)
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
m_shape = m_loaded_shape;
update_preview();
@ -569,14 +636,13 @@ void BedShapePanel::update_shape()
// Loads an stl file, projects it to the XY plane and calculates a polygon.
void BedShapePanel::load_stl()
{
wxFileDialog dialog(this, _(L("Choose an STL file to import bed shape from:")), "", "", file_wildcards(FT_STL), wxFD_OPEN | wxFD_FILE_MUST_EXIST);
wxFileDialog dialog(this, _L("Choose an STL file to import bed shape from:"), "", "", file_wildcards(FT_STL), wxFD_OPEN | wxFD_FILE_MUST_EXIST);
if (dialog.ShowModal() != wxID_OK)
return;
std::string file_name = dialog.GetPath().ToUTF8().data();
if (!boost::algorithm::iends_with(file_name, ".stl"))
{
show_error(this, _(L("Invalid file format.")));
if (!boost::algorithm::iends_with(file_name, ".stl")) {
show_error(this, _L("Invalid file format."));
return;
}
@ -587,7 +653,7 @@ void BedShapePanel::load_stl()
model = Model::read_from_file(file_name);
}
catch (std::exception &) {
show_error(this, _(L("Error! Invalid model")));
show_error(this, _L("Error! Invalid model"));
return;
}
@ -595,11 +661,11 @@ void BedShapePanel::load_stl()
auto expolygons = mesh.horizontal_projection();
if (expolygons.size() == 0) {
show_error(this, _(L("The selected file contains no geometry.")));
show_error(this, _L("The selected file contains no geometry."));
return;
}
if (expolygons.size() > 1) {
show_error(this, _(L("The selected file contains several disjoint areas. This is not supported.")));
show_error(this, _L("The selected file contains several disjoint areas. This is not supported."));
return;
}
@ -614,7 +680,7 @@ void BedShapePanel::load_stl()
void BedShapePanel::load_texture()
{
wxFileDialog dialog(this, _(L("Choose a file to import bed texture from (PNG/SVG):")), "", "",
wxFileDialog dialog(this, _L("Choose a file to import bed texture from (PNG/SVG):"), "", "",
file_wildcards(FT_TEX), wxFD_OPEN | wxFD_FILE_MUST_EXIST);
if (dialog.ShowModal() != wxID_OK)
@ -623,9 +689,8 @@ void BedShapePanel::load_texture()
m_custom_texture = NONE;
std::string file_name = dialog.GetPath().ToUTF8().data();
if (!boost::algorithm::iends_with(file_name, ".png") && !boost::algorithm::iends_with(file_name, ".svg"))
{
show_error(this, _(L("Invalid file format.")));
if (!boost::algorithm::iends_with(file_name, ".png") && !boost::algorithm::iends_with(file_name, ".svg")) {
show_error(this, _L("Invalid file format."));
return;
}
@ -637,7 +702,7 @@ void BedShapePanel::load_texture()
void BedShapePanel::load_model()
{
wxFileDialog dialog(this, _(L("Choose an STL file to import bed model from:")), "", "",
wxFileDialog dialog(this, _L("Choose an STL file to import bed model from:"), "", "",
file_wildcards(FT_STL), wxFD_OPEN | wxFD_FILE_MUST_EXIST);
if (dialog.ShowModal() != wxID_OK)
@ -646,9 +711,8 @@ void BedShapePanel::load_model()
m_custom_model = NONE;
std::string file_name = dialog.GetPath().ToUTF8().data();
if (!boost::algorithm::iends_with(file_name, ".stl"))
{
show_error(this, _(L("Invalid file format.")));
if (!boost::algorithm::iends_with(file_name, ".stl")) {
show_error(this, _L("Invalid file format."));
return;
}

View File

@ -5,6 +5,9 @@
#include "GUI_Utils.hpp"
#include "2DBed.hpp"
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
#include "3DBed.hpp"
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
#include "I18N.hpp"
#include <wx/dialog.h>
@ -19,12 +22,14 @@ using ConfigOptionsGroupShp = std::shared_ptr<ConfigOptionsGroup>;
struct BedShape
{
#if !ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
enum class Type {
Rectangular = 0,
Circular,
Custom,
Invalid
};
#endif // !ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
enum class Parameter {
RectSize,
@ -34,10 +39,18 @@ struct BedShape
BedShape(const ConfigOptionPoints& points);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
bool is_custom() { return m_type == Bed3D::EShapeType::Custom; }
#else
bool is_custom() { return m_type == Type::Custom; }
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
static void append_option_line(ConfigOptionsGroupShp optgroup, Parameter param);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
static wxString get_name(Bed3D::EShapeType type);
#else
static wxString get_name(Type type);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
// convert Type to size_t
size_t get_type();
@ -46,7 +59,11 @@ struct BedShape
void apply_optgroup_values(ConfigOptionsGroupShp optgroup);
private:
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Bed3D::EShapeType m_type{ Bed3D::EShapeType::Invalid };
#else
Type m_type {Type::Invalid};
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Vec2d m_rectSize {200, 200};
Vec2d m_rectOrigin {0, 0};
double m_diameter {0};

View File

@ -2115,8 +2115,38 @@ void GLCanvas3D::load_sla_preview()
// Release OpenGL data before generating new data.
reset_volumes();
_load_sla_shells();
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Bed3D::EShapeType type = wxGetApp().plater()->get_bed().get_shape_type();
switch (type)
{
case Bed3D::EShapeType::Circle: {
Vec2d center;
double radius;
if (Bed3D::is_circle(wxGetApp().plater()->get_bed().get_shape(), &center, &radius)) {
m_volumes.set_print_volume({ static_cast<int>(type),
{ float(center.x()), float(center.y()), float(radius) + BedEpsilon, 0.0f },
{ 0.0f, float(m_config->opt_float("max_print_height")) } });
}
break;
}
case Bed3D::EShapeType::Rectangle: {
const BoundingBoxf3& bed_bb = wxGetApp().plater()->get_bed().get_bounding_box(false);
m_volumes.set_print_volume({ static_cast<int>(type),
{ float(bed_bb.min.x()) - BedEpsilon, float(bed_bb.min.y()) - BedEpsilon, float(bed_bb.max.x()) + BedEpsilon, float(bed_bb.max.y()) + BedEpsilon },
{ 0.0f, float(m_config->opt_float("max_print_height")) } });
break;
}
default:
case Bed3D::EShapeType::Custom: {
m_volumes.set_print_volume({ static_cast<int>(type),
{ 0.0f, 0.0f, 0.0f, 0.0f },
{ 0.0f, 0.0f } });
}
}
#else
const BoundingBoxf3& bed_bb = wxGetApp().plater()->get_bed().get_bounding_box(false);
m_volumes.set_print_box(float(bed_bb.min.x()) - BedEpsilon, float(bed_bb.min.y()) - BedEpsilon, 0.0f, float(bed_bb.max.x()) + BedEpsilon, float(bed_bb.max.y()) + BedEpsilon, (float)m_config->opt_float("max_print_height"));
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
_update_sla_shells_outside_state();
_set_warning_notification_if_needed(EWarning::SlaSupportsOutside);
}
@ -5073,8 +5103,38 @@ void GLCanvas3D::_render_objects(GLVolumeCollection::ERenderType type)
m_layers_editing.select_object(*m_model, this->is_layers_editing_enabled() ? m_selection.get_object_idx() : -1);
if (m_config != nullptr) {
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
Bed3D::EShapeType type = wxGetApp().plater()->get_bed().get_shape_type();
switch (type)
{
case Bed3D::EShapeType::Circle: {
Vec2d center;
double radius;
if (Bed3D::is_circle(wxGetApp().plater()->get_bed().get_shape(), &center, &radius)) {
m_volumes.set_print_volume({ static_cast<int>(type),
{ float(center.x()), float(center.y()), float(radius) + BedEpsilon, 0.0f },
{ 0.0f, float(m_config->opt_float("max_print_height")) } });
}
break;
}
case Bed3D::EShapeType::Rectangle: {
const BoundingBoxf3& bed_bb = wxGetApp().plater()->get_bed().get_bounding_box(false);
m_volumes.set_print_volume({ static_cast<int>(type),
{ float(bed_bb.min.x()) - BedEpsilon, float(bed_bb.min.y()) - BedEpsilon, float(bed_bb.max.x()) + BedEpsilon, float(bed_bb.max.y()) + BedEpsilon },
{ 0.0f, float(m_config->opt_float("max_print_height")) } });
break;
}
default:
case Bed3D::EShapeType::Custom: {
m_volumes.set_print_volume({ static_cast<int>(type),
{ 0.0f, 0.0f, 0.0f, 0.0f },
{ 0.0f, 0.0f } });
}
}
#else
const BoundingBoxf3& bed_bb = wxGetApp().plater()->get_bed().get_bounding_box(false);
m_volumes.set_print_box((float)bed_bb.min.x() - BedEpsilon, (float)bed_bb.min.y() - BedEpsilon, 0.0f, (float)bed_bb.max.x() + BedEpsilon, (float)bed_bb.max.y() + BedEpsilon, (float)m_config->opt_float("max_print_height"));
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (m_requires_check_outside_state) {
m_volumes.check_outside_state(m_config, nullptr);
@ -5094,7 +5154,11 @@ void GLCanvas3D::_render_objects(GLVolumeCollection::ERenderType type)
m_volumes.set_clipping_plane(m_camera_clipping_plane.get_data());
m_volumes.set_show_sinking_contours(! m_gizmos.is_hiding_instances());
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
GLShaderProgram* shader = wxGetApp().get_shader("gouraud_mod");
#else
GLShaderProgram* shader = wxGetApp().get_shader("gouraud");
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (shader != nullptr) {
shader->start_using();

View File

@ -64,6 +64,19 @@ std::pair<bool, std::string> GLShadersManager::init()
// For Apple's on Arm CPU computed triangle normals inside fragment shader using dFdx and dFdy has the opposite direction.
// Because of this, objects had darker colors inside the multi-material gizmo.
// Based on https://stackoverflow.com/a/66206648, the similar behavior was also spotted on some other devices with Arm CPU.
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (platform_flavor() == PlatformFlavor::OSXOnArm)
valid &= append_shader("gouraud_mod", { "gouraud_mod.vs", "gouraud_mod.fs" }, { "FLIP_TRIANGLE_NORMALS"sv
#if ENABLE_ENVIRONMENT_MAP
, "ENABLE_ENVIRONMENT_MAP"sv
#endif
});
else
valid &= append_shader("gouraud_mod", { "gouraud_mod.vs", "gouraud_mod.fs" }
#if ENABLE_ENVIRONMENT_MAP
, { "ENABLE_ENVIRONMENT_MAP"sv }
#endif
#else
if (platform_flavor() == PlatformFlavor::OSXOnArm)
valid &= append_shader("gouraud", { "gouraud.vs", "gouraud.fs" }, { "FLIP_TRIANGLE_NORMALS"sv
#if ENABLE_ENVIRONMENT_MAP
@ -75,6 +88,7 @@ std::pair<bool, std::string> GLShadersManager::init()
#if ENABLE_ENVIRONMENT_MAP
, { "ENABLE_ENVIRONMENT_MAP"sv }
#endif
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
);
// used to render variable layers heights in 3d editor
valid &= append_shader("variable_layer_height", { "variable_layer_height.vs", "variable_layer_height.fs" });

View File

@ -607,7 +607,11 @@ void TriangleSelectorMmGui::render(ImGuiWrapper *imgui)
auto *shader = wxGetApp().get_current_shader();
if (!shader)
return;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
assert(shader->get_name() == "gouraud_mod");
#else
assert(shader->get_name() == "gouraud");
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
ScopeGuard guard([shader]() { if (shader) shader->set_uniform("compute_triangle_normals_in_fs", false);});
shader->set_uniform("compute_triangle_normals_in_fs", true);

View File

@ -97,12 +97,20 @@ void GLGizmoPainterBase::render_triangles(const Selection& selection, const bool
clp_dataf[3] = float(clp->get_data()[3]);
}
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
auto* shader = wxGetApp().get_shader("gouraud_mod");
#else
auto *shader = wxGetApp().get_shader("gouraud");
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
if (! shader)
return;
shader->start_using();
shader->set_uniform("slope.actived", false);
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
shader->set_uniform("print_volume.type", 0);
#else
shader->set_uniform("print_box.actived", false);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
shader->set_uniform("clipping_plane", clp_dataf, 4);
ScopeGuard guard([shader]() { if (shader) shader->stop_using(); });
@ -128,7 +136,11 @@ void GLGizmoPainterBase::render_triangles(const Selection& selection, const bool
// to the shader input variable print_box.volume_world_matrix before
// rendering the painted triangles. When this matrix is not set, the
// wrong transformation matrix is used for "Clipping of view".
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
shader->set_uniform("volume_world_matrix", trafo_matrix);
#else
shader->set_uniform("print_box.volume_world_matrix", trafo_matrix);
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
m_triangle_selectors[mesh_id]->render(m_imgui);
@ -591,7 +603,11 @@ void TriangleSelectorGUI::render(ImGuiWrapper* imgui)
auto* shader = wxGetApp().get_current_shader();
if (! shader)
return;
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
assert(shader->get_name() == "gouraud_mod");
#else
assert(shader->get_name() == "gouraud");
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
for (auto iva : {std::make_pair(&m_iva_enforcers, enforcers_color),
std::make_pair(&m_iva_blockers, blockers_color)}) {