This commit is contained in:
YuSanka 2018-12-07 18:00:17 +01:00
commit 386d46417a
21 changed files with 505 additions and 59 deletions

View file

@ -1876,7 +1876,7 @@ sub export_stl {
$self->statusbar->SetStatusText(L("STL file exported to ").$output_file);
}
# XXX: not done
# XXX: VK: done
sub reload_from_disk {
my ($self) = @_;
@ -1908,7 +1908,7 @@ sub reload_from_disk {
$self->remove($obj_idx);
}
# XXX: VK: done
# XXX: VK: integrated into Plater::export_stl()
sub export_object_stl {
my ($self) = @_;
my ($obj_idx, $object) = $self->selected_object;

View file

@ -139,6 +139,8 @@ add_library(libslic3r STATIC
Rasterizer/Rasterizer.cpp
SLAPrint.cpp
SLAPrint.hpp
SLA/SLAAutoSupports.hpp
SLA/SLAAutoSupports.cpp
Slicing.cpp
Slicing.hpp
SlicingAdaptive.cpp

View file

@ -2159,9 +2159,11 @@ std::string GCode::extrude_loop(ExtrusionLoop loop, std::string description, dou
m_wipe.path = paths.front().polyline; // TODO: don't limit wipe to last path
// make a little move inwards before leaving loop
if (paths.back().role() == erExternalPerimeter && m_layer != NULL && m_config.perimeters.value > 1) {
if (paths.back().role() == erExternalPerimeter && m_layer != NULL && m_config.perimeters.value > 1 && paths.front().size() >= 2 && paths.back().polyline.points.size() >= 3) {
// detect angle between last and first segment
// the side depends on the original winding order of the polygon (left for contours, right for holes)
//FIXME improve the algorithm in case the loop is tiny.
//FIXME improve the algorithm in case the loop is split into segments with a low number of points (see the Point b query).
Point a = paths.front().polyline.points[1]; // second point
Point b = *(paths.back().polyline.points.end()-3); // second to last point
if (was_clockwise) {

View file

@ -987,6 +987,8 @@ bool ModelObject::needed_repair() const
ModelObjectPtrs ModelObject::cut(size_t instance, coordf_t z, bool keep_upper, bool keep_lower, bool rotate_lower)
{
if (!keep_upper && !keep_lower) { return {}; }
// Clone the object to duplicate instances, materials etc.
ModelObject* upper = keep_upper ? ModelObject::new_clone(*this) : nullptr;
ModelObject* lower = keep_lower ? ModelObject::new_clone(*this) : nullptr;
@ -1024,15 +1026,21 @@ ModelObjectPtrs ModelObject::cut(size_t instance, coordf_t z, bool keep_upper, b
std::vector<BoundingBoxf3> lower_bboxes { instances.size() };
for (ModelVolume *volume : volumes) {
const auto volume_matrix = volume->get_matrix();
if (! volume->is_model_part()) {
// Don't cut modifiers
// Modifiers are not cut, but we still need to add the instance transformation
// to the modifier volume transformation to preserve their shape properly.
volume->set_transformation(Geometry::Transformation(instance_matrix * volume_matrix));
if (keep_upper) { upper->add_volume(*volume); }
if (keep_lower) { lower->add_volume(*volume); }
} else {
TriangleMesh upper_mesh, lower_mesh;
// Transform the mesh by the combined transformation matrix
volume->mesh.transform(instance_matrix * volume->get_matrix());
volume->mesh.transform(instance_matrix * volume_matrix);
// Perform cut
TriangleMeshSlicer tms(&volume->mesh);

View file

@ -360,13 +360,20 @@ double Print::max_allowed_layer_height() const
return nozzle_diameter_max;
}
static void clamp_exturder_to_default(ConfigOptionInt &opt, size_t num_extruders)
{
if (opt.value > (int)num_extruders)
// assign the default extruder
opt.value = 1;
}
static PrintObjectConfig object_config_from_model(const PrintObjectConfig &default_object_config, const ModelObject &object, size_t num_extruders)
{
PrintObjectConfig config = default_object_config;
normalize_and_apply_config(config, object.config);
// Clamp extruders to the number of extruders this printer is physically equipped with.
config.support_material_extruder.value = std::min(config.support_material_extruder.value, (int)num_extruders);
config.support_material_interface_extruder.value = std::min(config.support_material_interface_extruder.value, (int)num_extruders);
// Clamp invalid extruders to the default extruder (with index 1).
clamp_exturder_to_default(config.support_material_extruder, num_extruders);
clamp_exturder_to_default(config.support_material_interface_extruder, num_extruders);
return config;
}
@ -377,10 +384,10 @@ static PrintRegionConfig region_config_from_model_volume(const PrintRegionConfig
normalize_and_apply_config(config, volume.config);
if (! volume.material_id().empty())
normalize_and_apply_config(config, volume.material()->config);
// Clamp extruders to the number of extruders this printer is physically equipped with.
config.infill_extruder.value = std::min(config.infill_extruder.value, (int)num_extruders);
config.perimeter_extruder.value = std::min(config.perimeter_extruder.value, (int)num_extruders);
config.solid_infill_extruder.value = std::min(config.solid_infill_extruder.value, (int)num_extruders);
// Clamp invalid extruders to the default extruder (with index 1).
clamp_exturder_to_default(config.infill_extruder, num_extruders);
clamp_exturder_to_default(config.perimeter_extruder, num_extruders);
clamp_exturder_to_default(config.solid_infill_extruder, num_extruders);
return config;
}
@ -393,7 +400,7 @@ void Print::add_model_object(ModelObject* model_object, int idx)
m_model.objects.emplace_back(ModelObject::new_copy(*model_object));
m_model.objects.back()->set_model(&m_model);
// Initialize a new print object and store it at the given position.
PrintObject *object = new PrintObject(this, model_object);
PrintObject *object = new PrintObject(this, model_object, true);
if (idx != -1) {
delete m_objects[idx];
m_objects[idx] = object;
@ -957,7 +964,7 @@ Print::ApplyStatus Print::apply(const Model &model, const DynamicPrintConfig &co
if (old.empty()) {
// Simple case, just generate new instances.
for (const PrintInstances &print_instances : new_print_instances) {
PrintObject *print_object = new PrintObject(this, model_object);
PrintObject *print_object = new PrintObject(this, model_object, false);
print_object->set_trafo(print_instances.trafo);
print_object->set_copies(print_instances.copies);
print_object->config_apply(config);
@ -976,7 +983,7 @@ Print::ApplyStatus Print::apply(const Model &model, const DynamicPrintConfig &co
for (; it_old != old.end() && transform3d_lower((*it_old)->trafo, new_instances.trafo); ++ it_old);
if (it_old == old.end() || ! transform3d_equal((*it_old)->trafo, new_instances.trafo)) {
// This is a new instance (or a set of instances with the same trafo). Just add it.
PrintObject *print_object = new PrintObject(this, model_object);
PrintObject *print_object = new PrintObject(this, model_object, false);
print_object->set_trafo(new_instances.trafo);
print_object->set_copies(new_instances.copies);
print_object->config_apply(config);

View file

@ -159,7 +159,7 @@ protected:
// to be called from Print only.
friend class Print;
PrintObject(Print* print, ModelObject* model_object);
PrintObject(Print* print, ModelObject* model_object, bool add_instances = true);
~PrintObject() {}
void config_apply(const ConfigBase &other, bool ignore_nonexistent = false) { this->m_config.apply(other, ignore_nonexistent); }

View file

@ -2561,6 +2561,33 @@ void PrintConfigDef::init_sla_params()
def->min = 0;
def->default_value = new ConfigOptionFloat(5.0);
def = this->add("support_density_at_horizontal", coInt);
def->label = L("Density on horizontal surfaces");
def->category = L("Supports");
def->tooltip = L("How many support points (approximately) should be placed on horizontal surface.");
def->sidetext = L("points per square dm");
def->cli = "";
def->min = 0;
def->default_value = new ConfigOptionInt(500);
def = this->add("support_density_at_45", coInt);
def->label = L("Density on surfaces at 45 degrees");
def->category = L("Supports");
def->tooltip = L("How many support points (approximately) should be placed on surface sloping at 45 degrees.");
def->sidetext = L("points per square dm");
def->cli = "";
def->min = 0;
def->default_value = new ConfigOptionInt(250);
def = this->add("support_minimal_z", coFloat);
def->label = L("Minimal support point height");
def->category = L("Supports");
def->tooltip = L("No support points will be placed lower than this value from the bottom.");
def->sidetext = L("mm");
def->cli = "";
def->min = 0;
def->default_value = new ConfigOptionFloat(0.f);
def = this->add("pad_enable", coBool);
def->label = L("Use pad");
def->category = L("Pad");

View file

@ -955,6 +955,11 @@ public:
// and the model object's bounding box bottom. Units in mm.
ConfigOptionFloat support_object_elevation /*= 5.0*/;
/////// Following options influence automatic support points placement:
ConfigOptionInt support_density_at_horizontal;
ConfigOptionInt support_density_at_45;
ConfigOptionFloat support_minimal_z;
// Now for the base pool (pad) /////////////////////////////////////////////
// Enabling or disabling support creation
@ -987,6 +992,9 @@ protected:
OPT_PTR(support_base_height);
OPT_PTR(support_critical_angle);
OPT_PTR(support_max_bridge_length);
OPT_PTR(support_density_at_horizontal);
OPT_PTR(support_density_at_45);
OPT_PTR(support_minimal_z);
OPT_PTR(support_object_elevation);
OPT_PTR(pad_enable);
OPT_PTR(pad_wall_thickness);

View file

@ -34,7 +34,7 @@
namespace Slic3r {
PrintObject::PrintObject(Print* print, ModelObject* model_object) :
PrintObject::PrintObject(Print* print, ModelObject* model_object, bool add_instances) :
PrintObjectBaseWithState(print, model_object),
typed_slices(false),
size(Vec3crd::Zero()),
@ -54,7 +54,7 @@ PrintObject::PrintObject(Print* print, ModelObject* model_object) :
this->size = (modobj_bbox.size() * (1. / SCALING_FACTOR)).cast<coord_t>();
}
{
if (add_instances) {
Points copies;
copies.reserve(m_model_object->instances.size());
for (const ModelInstance *mi : m_model_object->instances) {

View file

@ -0,0 +1,155 @@
#include "igl/random_points_on_mesh.h"
#include "igl/AABB.h"
#include "SLAAutoSupports.hpp"
#include "Model.hpp"
#include <iostream>
namespace Slic3r {
SLAAutoSupports::SLAAutoSupports(ModelObject& mo, const SLAAutoSupports::Config& c)
: m_model_object(mo), mesh(), m_config(c)
{}
float SLAAutoSupports::approximate_geodesic_distance(const Vec3f& p1, const Vec3f& p2, Vec3f& n1, Vec3f& n2)
{
n1.normalize();
n2.normalize();
Vec3f v = (p2-p1);
v.normalize();
float c1 = n1.dot(v);
float c2 = n2.dot(v);
float result = pow(p1(0)-p2(0), 2) + pow(p1(1)-p2(1), 2) + pow(p1(2)-p2(2), 2);
// Check for division by zero:
if(fabs(c1 - c2) > 0.0001)
result *= (asin(c1) - asin(c2)) / (c1 - c2);
return result;
}
void SLAAutoSupports::generate()
{
// Loads the ModelObject raw_mesh and transforms it by first instance's transformation matrix (disregarding translation).
// Instances only differ in z-rotation, so it does not matter which of them will be used for the calculation.
// The supports point will be calculated on this mesh (so scaling ang vertical direction is correctly accounted for).
// Results will be inverse-transformed to raw_mesh coordinates.
TriangleMesh mesh = m_model_object.raw_mesh();
Transform3d transformation_matrix = m_model_object.instances[0]->get_matrix(true/*dont_translate*/);
mesh.transform(transformation_matrix);
// Check that the object is thick enough to produce any support points
BoundingBoxf3 bb = mesh.bounding_box();
if (bb.size()(2) < m_config.minimal_z)
return;
// All points that we curretly have must be transformed too, so distance to them is correcly calculated.
for (Vec3f& point : m_model_object.sla_support_points)
point = transformation_matrix.cast<float>() * point;
const stl_file& stl = mesh.stl;
Eigen::MatrixXf V;
Eigen::MatrixXi F;
V.resize(3 * stl.stats.number_of_facets, 3);
F.resize(stl.stats.number_of_facets, 3);
for (unsigned int i=0; i<stl.stats.number_of_facets; ++i) {
const stl_facet* facet = stl.facet_start+i;
V(3*i+0, 0) = facet->vertex[0](0); V(3*i+0, 1) = facet->vertex[0](1); V(3*i+0, 2) = facet->vertex[0](2);
V(3*i+1, 0) = facet->vertex[1](0); V(3*i+1, 1) = facet->vertex[1](1); V(3*i+1, 2) = facet->vertex[1](2);
V(3*i+2, 0) = facet->vertex[2](0); V(3*i+2, 1) = facet->vertex[2](1); V(3*i+2, 2) = facet->vertex[2](2);
F(i, 0) = 3*i+0;
F(i, 1) = 3*i+1;
F(i, 2) = 3*i+2;
}
// In order to calculate distance to already placed points, we must keep know which facet the point lies on.
std::vector<Vec3f> facets_normals;
// The AABB hierarchy will be used to find normals of already placed points.
// The points added automatically will just push_back the new normal on the fly.
igl::AABB<Eigen::MatrixXf,3> aabb;
aabb.init(V, F);
for (unsigned int i=0; i<m_model_object.sla_support_points.size(); ++i) {
int facet_idx = 0;
Eigen::Matrix<float, 1, 3> dump;
Eigen::MatrixXf query_point = m_model_object.sla_support_points[i];
aabb.squared_distance(V, F, query_point, facet_idx, dump);
Vec3f a1 = V.row(F(facet_idx,1)) - V.row(F(facet_idx,0));
Vec3f a2 = V.row(F(facet_idx,2)) - V.row(F(facet_idx,0));
Vec3f normal = a1.cross(a2);
normal.normalize();
facets_normals.push_back(normal);
}
// New potential support point is randomly generated on the mesh and distance to all already placed points is calculated.
// In case it is never smaller than certain limit (depends on the new point's facet normal), the point is accepted.
// The process stops after certain number of points is refused in a row.
Vec3f point;
Vec3f normal;
int added_points = 0;
int refused_points = 0;
const int refused_limit = 30;
// Angle at which the density reaches zero:
const float threshold_angle = std::min(M_PI_2, M_PI_4 * acos(0.f/m_config.density_at_horizontal) / acos(m_config.density_at_45/m_config.density_at_horizontal));
srand(time(NULL)); // rand() is used by igl::random_point_on_mesh
while (refused_points < refused_limit) {
// Place a random point on the mesh and calculate corresponding facet's normal:
Eigen::VectorXi FI;
Eigen::MatrixXf B;
igl::random_points_on_mesh(1, V, F, B, FI);
point = B(0,0)*V.row(F(FI(0),0)) +
B(0,1)*V.row(F(FI(0),1)) +
B(0,2)*V.row(F(FI(0),2));
if (point(2) - bb.min(2) < m_config.minimal_z)
continue;
Vec3f a1 = V.row(F(FI(0),1)) - V.row(F(FI(0),0));
Vec3f a2 = V.row(F(FI(0),2)) - V.row(F(FI(0),0));
normal = a1.cross(a2);
normal.normalize();
// calculate angle between the normal and vertical:
float angle = angle_from_normal(normal);
if (angle > threshold_angle)
continue;
const float distance_limit = 1./(2.4*get_required_density(angle));
bool add_it = true;
for (unsigned int i=0; i<m_model_object.sla_support_points.size(); ++i) {
if (approximate_geodesic_distance(m_model_object.sla_support_points[i], point, facets_normals[i], normal) < distance_limit) {
add_it = false;
++refused_points;
break;
}
}
if (add_it) {
m_model_object.sla_support_points.push_back(point);
facets_normals.push_back(normal);
++added_points;
refused_points = 0;
}
}
// Now transform all support points to mesh coordinates:
for (Vec3f& point : m_model_object.sla_support_points)
point = transformation_matrix.inverse().cast<float>() * point;
}
float SLAAutoSupports::get_required_density(float angle) const
{
// calculation would be density_0 * cos(angle). To provide one more degree of freedom, we will scale the angle
// to get the user-set density for 45 deg. So it ends up as density_0 * cos(K * angle).
float K = 4.f * float(acos(m_config.density_at_45/m_config.density_at_horizontal) / M_PI);
return std::max(0.f, float(m_config.density_at_horizontal * cos(K*angle)));
}
} // namespace Slic3r

View file

@ -0,0 +1,42 @@
#ifndef SLAAUTOSUPPORTS_HPP_
#define SLAAUTOSUPPORTS_HPP_
#include <libslic3r/Point.hpp>
#include <libslic3r/TriangleMesh.hpp>
namespace Slic3r {
class ModelObject;
class SLAAutoSupports {
public:
struct Config {
float density_at_horizontal;
float density_at_45;
float minimal_z;
};
SLAAutoSupports(ModelObject& mo, const SLAAutoSupports::Config& c);
void generate();
private:
TriangleMesh mesh;
static float angle_from_normal(const stl_normal& normal) { return acos((-normal.normalized())(2)); }
float get_required_density(float angle) const;
static float approximate_geodesic_distance(const Vec3f& p1, const Vec3f& p2, Vec3f& n1, Vec3f& n2);
ModelObject& m_model_object;
SLAAutoSupports::Config m_config;
};
} // namespace Slic3r
#endif // SLAAUTOSUPPORTS_HPP_

View file

@ -27,10 +27,13 @@
#define ENABLE_WORLD_ROTATIONS (1 && ENABLE_1_42_0)
// Scene's GUI made using imgui library
#define ENABLE_IMGUI (1 && ENABLE_1_42_0)
#define DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI (1 && ENABLE_IMGUI)
// Modified Sla support gizmo
#define ENABLE_SLA_SUPPORT_GIZMO_MOD (1 && ENABLE_1_42_0)
// Removes the wxNotebook from plater
#define ENABLE_REMOVE_TABS_FROM_PLATER (1 && ENABLE_1_42_0)
// Constrains the camera target into the scene bounding box
#define ENABLE_CONSTRAINED_CAMERA_TARGET (1 && ENABLE_1_42_0)
#endif // _technologies_h_

View file

@ -35,7 +35,7 @@ public:
void repair();
float volume();
void check_topology();
bool is_manifold() const { return this->stl.stats.connected_facets_3_edge == this->stl.stats.number_of_facets; }
bool is_manifold() const { return this->stl.stats.connected_facets_3_edge == (int)this->stl.stats.number_of_facets; }
void WriteOBJFile(char* output_file);
void scale(float factor);
void scale(const Vec3d &versor);

View file

@ -273,8 +273,13 @@ GLCanvas3D::Camera::Camera()
, zoom(1.0f)
, phi(45.0f)
// , distance(0.0f)
#if !ENABLE_CONSTRAINED_CAMERA_TARGET
, target(0.0, 0.0, 0.0)
#endif // !ENABLE_CONSTRAINED_CAMERA_TARGET
, m_theta(45.0f)
#if ENABLE_CONSTRAINED_CAMERA_TARGET
, m_target(Vec3d::Zero())
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
{
}
@ -292,16 +297,32 @@ std::string GLCanvas3D::Camera::get_type_as_string() const
};
}
float GLCanvas3D::Camera::get_theta() const
{
return m_theta;
}
void GLCanvas3D::Camera::set_theta(float theta)
{
m_theta = clamp(0.0f, GIMBALL_LOCK_THETA_MAX, theta);
}
#if ENABLE_CONSTRAINED_CAMERA_TARGET
void GLCanvas3D::Camera::set_target(const Vec3d& target, GLCanvas3D& canvas)
{
m_target = target;
m_target(0) = clamp(m_scene_box.min(0), m_scene_box.max(0), m_target(0));
m_target(1) = clamp(m_scene_box.min(1), m_scene_box.max(1), m_target(1));
m_target(2) = clamp(m_scene_box.min(2), m_scene_box.max(2), m_target(2));
if (!m_target.isApprox(target))
canvas.viewport_changed();
}
void GLCanvas3D::Camera::set_scene_box(const BoundingBoxf3& box, GLCanvas3D& canvas)
{
if (m_scene_box != box)
{
m_scene_box = box;
canvas.viewport_changed();
}
}
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
GLCanvas3D::Bed::Bed()
: m_type(Custom)
{
@ -1383,7 +1404,7 @@ bool GLCanvas3D::Selection::is_single_full_instance() const
return false;
int object_idx = m_valid ? get_object_idx() : -1;
if (object_idx == -1)
if ((object_idx < 0) || ((int)m_model->objects.size() <= object_idx))
return false;
int instance_idx = (*m_volumes)[*m_list.begin()]->instance_idx();
@ -1458,13 +1479,13 @@ void GLCanvas3D::Selection::translate(const Vec3d& displacement)
for (unsigned int i : m_list)
{
#if ENABLE_MODELVOLUME_TRANSFORM
if (m_mode == Instance)
(*m_volumes)[i]->set_instance_offset(m_cache.volumes_data[i].get_instance_position() + displacement);
else if (m_mode == Volume)
{
Vec3d local_displacement = (m_cache.volumes_data[i].get_instance_rotation_matrix() * m_cache.volumes_data[i].get_instance_scale_matrix()).inverse() * displacement;
(*m_volumes)[i]->set_volume_offset(m_cache.volumes_data[i].get_volume_position() + local_displacement);
}
if ((m_mode == Volume) || (*m_volumes)[i]->is_wipe_tower)
{
Vec3d local_displacement = (m_cache.volumes_data[i].get_instance_rotation_matrix() * m_cache.volumes_data[i].get_instance_scale_matrix()).inverse() * displacement;
(*m_volumes)[i]->set_volume_offset(m_cache.volumes_data[i].get_volume_position() + local_displacement);
}
else if (m_mode == Instance)
(*m_volumes)[i]->set_instance_offset(m_cache.volumes_data[i].get_instance_position() + displacement);
#else
(*m_volumes)[i]->set_offset(m_cache.volumes_data[i].get_position() + displacement);
#endif // ENABLE_MODELVOLUME_TRANSFORM
@ -3650,6 +3671,15 @@ BoundingBoxf3 GLCanvas3D::volumes_bounding_box() const
return bb;
}
#if ENABLE_CONSTRAINED_CAMERA_TARGET
BoundingBoxf3 GLCanvas3D::scene_bounding_box() const
{
BoundingBoxf3 bb = volumes_bounding_box();
bb.merge(m_bed.get_bounding_box());
return bb;
}
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
bool GLCanvas3D::is_layers_editing_enabled() const
{
return m_layers_editing.is_enabled();
@ -3789,7 +3819,12 @@ void GLCanvas3D::set_viewport_from_scene(const GLCanvas3D& other)
{
m_camera.phi = other.m_camera.phi;
m_camera.set_theta(other.m_camera.get_theta());
#if ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.set_scene_box(other.m_camera.get_scene_box(), *this);
m_camera.set_target(other.m_camera.get_target(), *this);
#else
m_camera.target = other.m_camera.target;
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.zoom = other.m_camera.zoom;
m_dirty = true;
}
@ -4318,6 +4353,12 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
// restore to default value
m_regenerate_volumes = true;
#if ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.set_scene_box(scene_bounding_box(), *this);
m_camera.set_target(m_camera.get_target(), *this);
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
// and force this canvas to be redrawn.
m_dirty = true;
}
@ -4857,7 +4898,11 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
float z = 0.0f;
const Vec3d& cur_pos = _mouse_to_3d(pos, &z);
Vec3d orig = _mouse_to_3d(m_mouse.drag.start_position_2D, &z);
#if ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.set_target(m_camera.get_target() + orig - cur_pos, *this);
#else
m_camera.target += orig - cur_pos;
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
viewport_changed();
@ -4938,10 +4983,14 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
#if ENABLE_WORLD_ROTATIONS
_update_gizmos_data();
#endif // ENABLE_WORLD_ROTATIONS
wxGetApp().obj_manipul()->update_settings_value(m_selection);
// Let the platter know that the dragging finished, so a delayed refresh
// of the scene with the background processing data should be performed.
post_event(SimpleEvent(EVT_GLCANVAS_MOUSE_DRAGGING_FINISHED));
#if ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.set_scene_box(scene_bounding_box(), *this);
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
}
m_moving = false;
@ -5533,7 +5582,11 @@ void GLCanvas3D::_zoom_to_bounding_box(const BoundingBoxf3& bbox)
{
m_camera.zoom = zoom;
// center view around bounding box center
#if ENABLE_CONSTRAINED_CAMERA_TARGET
m_camera.set_target(bbox.center(), *this);
#else
m_camera.target = bbox.center();
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
viewport_changed();
@ -5655,7 +5708,12 @@ void GLCanvas3D::_camera_tranform() const
::glRotatef(-m_camera.get_theta(), 1.0f, 0.0f, 0.0f); // pitch
::glRotatef(m_camera.phi, 0.0f, 0.0f, 1.0f); // yaw
#if ENABLE_CONSTRAINED_CAMERA_TARGET
Vec3d target = -m_camera.get_target();
::glTranslated(target(0), target(1), target(2));
#else
::glTranslated(-m_camera.target(0), -m_camera.target(1), -m_camera.target(2));
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
}
void GLCanvas3D::_picking_pass() const
@ -5970,6 +6028,23 @@ void GLCanvas3D::_render_camera_target() const
::glLineWidth(2.0f);
::glBegin(GL_LINES);
#if ENABLE_CONSTRAINED_CAMERA_TARGET
const Vec3d& target = m_camera.get_target();
// draw line for x axis
::glColor3f(1.0f, 0.0f, 0.0f);
::glVertex3d(target(0) - half_length, target(1), target(2));
::glVertex3d(target(0) + half_length, target(1), target(2));
// draw line for y axis
::glColor3f(0.0f, 1.0f, 0.0f);
::glVertex3d(target(0), target(1) - half_length, target(2));
::glVertex3d(target(0), target(1) + half_length, target(2));
::glEnd();
::glBegin(GL_LINES);
::glColor3f(0.0f, 0.0f, 1.0f);
::glVertex3d(target(0), target(1), target(2) - half_length);
::glVertex3d(target(0), target(1), target(2) + half_length);
#else
// draw line for x axis
::glColor3f(1.0f, 0.0f, 0.0f);
::glVertex3d(m_camera.target(0) - half_length, m_camera.target(1), m_camera.target(2));
@ -5984,6 +6059,7 @@ void GLCanvas3D::_render_camera_target() const
::glColor3f(0.0f, 0.0f, 1.0f);
::glVertex3d(m_camera.target(0), m_camera.target(1), m_camera.target(2) - half_length);
::glVertex3d(m_camera.target(0), m_camera.target(1), m_camera.target(2) + half_length);
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
::glEnd();
}
#endif // ENABLE_SHOW_CAMERA_TARGET

View file

@ -153,9 +153,15 @@ class GLCanvas3D
float zoom;
float phi;
// float distance;
#if !ENABLE_CONSTRAINED_CAMERA_TARGET
Vec3d target;
#endif !// ENABLE_CONSTRAINED_CAMERA_TARGET
private:
#if ENABLE_CONSTRAINED_CAMERA_TARGET
Vec3d m_target;
BoundingBoxf3 m_scene_box;
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
float m_theta;
public:
@ -163,8 +169,16 @@ class GLCanvas3D
std::string get_type_as_string() const;
float get_theta() const;
float get_theta() const { return m_theta; }
void set_theta(float theta);
#if ENABLE_CONSTRAINED_CAMERA_TARGET
const Vec3d& get_target() const { return m_target; }
void set_target(const Vec3d& target, GLCanvas3D& canvas);
const BoundingBoxf3& get_scene_box() const { return m_scene_box; }
void set_scene_box(const BoundingBoxf3& box, GLCanvas3D& canvas);
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
};
class Bed
@ -782,7 +796,9 @@ private:
wxWindow *m_external_gizmo_widgets_parent;
#endif // not ENABLE_IMGUI
#if !ENABLE_CONSTRAINED_CAMERA_TARGET
void viewport_changed();
#endif // !ENABLE_CONSTRAINED_CAMERA_TARGET
public:
GLCanvas3D(wxGLCanvas* canvas);
@ -845,6 +861,9 @@ public:
float get_camera_zoom() const;
BoundingBoxf3 volumes_bounding_box() const;
#if ENABLE_CONSTRAINED_CAMERA_TARGET
BoundingBoxf3 scene_bounding_box() const;
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
bool is_layers_editing_enabled() const;
bool is_layers_editing_allowed() const;
@ -936,6 +955,10 @@ public:
void update_gizmos_on_off_state();
#if ENABLE_CONSTRAINED_CAMERA_TARGET
void viewport_changed();
#endif // ENABLE_CONSTRAINED_CAMERA_TARGET
private:
bool _is_shown_on_screen() const;
void _force_zoom_to_bed();

View file

@ -20,6 +20,7 @@
#include <wx/stattext.h>
#include <wx/debug.h>
#include "Tab.hpp"
#include "GUI.hpp"
#include "GUI_Utils.hpp"
#include "GUI_App.hpp"
@ -642,13 +643,13 @@ void GLGizmoRotate::transform_to_local() const
case X:
{
::glRotatef(90.0f, 0.0f, 1.0f, 0.0f);
::glRotatef(90.0f, 0.0f, 0.0f, 1.0f);
::glRotatef(-90.0f, 0.0f, 0.0f, 1.0f);
break;
}
case Y:
{
::glRotatef(-90.0f, 1.0f, 0.0f, 0.0f);
::glRotatef(90.0f, 0.0f, 0.0f, 1.0f);
::glRotatef(-90.0f, 0.0f, 0.0f, 1.0f);
::glRotatef(-90.0f, 0.0f, 1.0f, 0.0f);
break;
}
default:
@ -670,14 +671,14 @@ Vec3d GLGizmoRotate::mouse_position_in_local_plane(const Linef3& mouse_ray) cons
{
case X:
{
m.rotate(Eigen::AngleAxisd(-half_pi, Vec3d::UnitZ()));
m.rotate(Eigen::AngleAxisd(half_pi, Vec3d::UnitZ()));
m.rotate(Eigen::AngleAxisd(-half_pi, Vec3d::UnitY()));
break;
}
case Y:
{
m.rotate(Eigen::AngleAxisd(-half_pi, Vec3d::UnitZ()));
m.rotate(Eigen::AngleAxisd(half_pi, Vec3d::UnitX()));
m.rotate(Eigen::AngleAxisd(half_pi, Vec3d::UnitY()));
m.rotate(Eigen::AngleAxisd(half_pi, Vec3d::UnitZ()));
break;
}
default:
@ -769,6 +770,7 @@ void GLGizmoRotate3D::on_render(const GLCanvas3D::Selection& selection) const
#if ENABLE_IMGUI
void GLGizmoRotate3D::on_render_input_window(float x, float y, const GLCanvas3D::Selection& selection)
{
#if !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
Vec3d rotation(Geometry::rad2deg(m_gizmos[0].get_angle()), Geometry::rad2deg(m_gizmos[1].get_angle()), Geometry::rad2deg(m_gizmos[2].get_angle()));
wxString label = _(L("Rotation (deg)"));
@ -777,6 +779,7 @@ void GLGizmoRotate3D::on_render_input_window(float x, float y, const GLCanvas3D:
m_imgui->begin(label, ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoCollapse);
m_imgui->input_vec3("", rotation, 100.0f, "%.2f");
m_imgui->end();
#endif // !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
}
#endif // ENABLE_IMGUI
@ -1073,14 +1076,16 @@ void GLGizmoScale3D::on_render_for_picking(const GLCanvas3D::Selection& selectio
#if ENABLE_IMGUI
void GLGizmoScale3D::on_render_input_window(float x, float y, const GLCanvas3D::Selection& selection)
{
#if !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
bool single_instance = selection.is_single_full_instance();
wxString label = _(L("Scale (%)"));
m_imgui->set_next_window_pos(x, y, ImGuiCond_Always);
m_imgui->set_next_window_bg_alpha(0.5f);
m_imgui->begin(label, ImGuiWindowFlags_NoMove | ImGuiWindowFlags_NoResize | ImGuiWindowFlags_NoCollapse);
m_imgui->input_vec3("", m_scale, 100.0f, "%.2f");
m_imgui->input_vec3("", m_scale * 100.f, 100.0f, "%.2f");
m_imgui->end();
#endif // !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
}
#endif // ENABLE_IMGUI
@ -1320,6 +1325,7 @@ void GLGizmoMove3D::on_render_for_picking(const GLCanvas3D::Selection& selection
#if ENABLE_IMGUI
void GLGizmoMove3D::on_render_input_window(float x, float y, const GLCanvas3D::Selection& selection)
{
#if !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
bool show_position = selection.is_single_full_instance();
const Vec3d& position = selection.get_bounding_box().center();
@ -1332,6 +1338,7 @@ void GLGizmoMove3D::on_render_input_window(float x, float y, const GLCanvas3D::S
m_imgui->input_vec3("", displacement, 100.0f, "%.2f");
m_imgui->end();
#endif // !DISABLE_MOVE_ROTATE_SCALE_GIZMOS_IMGUI
}
#endif // ENABLE_IMGUI
@ -1732,7 +1739,9 @@ GLGizmoSlaSupports::GLGizmoSlaSupports(GLCanvas3D& parent)
#if ENABLE_SLA_SUPPORT_GIZMO_MOD
m_quadric = ::gluNewQuadric();
if (m_quadric != nullptr)
::gluQuadricDrawStyle(m_quadric, GLU_FILL);
// using GLU_FILL does not work when the instance's transformation
// contains mirroring (normals are reverted)
::gluQuadricDrawStyle(m_quadric, GLU_SILHOUETTE);
#endif // ENABLE_SLA_SUPPORT_GIZMO_MOD
}
@ -1780,8 +1789,7 @@ void GLGizmoSlaSupports::set_sla_support_data(ModelObject* model_object, const G
#else
void GLGizmoSlaSupports::set_model_object_ptr(ModelObject* model_object)
{
if (model_object != nullptr)
{
if (model_object != nullptr) {
m_starting_center = Vec3d::Zero();
m_model_object = model_object;
@ -1810,6 +1818,7 @@ void GLGizmoSlaSupports::on_render(const GLCanvas3D::Selection& selection) const
Vec3d dragged_offset = selection.get_bounding_box().center() - m_starting_center;
#endif // !ENABLE_SLA_SUPPORT_GIZMO_MOD
for (auto& g : m_grabbers) {
g.color[0] = 1.f;
g.color[1] = 0.f;
@ -1869,6 +1878,16 @@ void GLGizmoSlaSupports::render_grabbers(const GLCanvas3D::Selection& selection,
float render_color[3];
for (int i = 0; i < (int)m_grabbers.size(); ++i)
{
// first precalculate the grabber position in world coordinates, so that the grabber
// is not scaled with the object (as it would be if rendered with current gl matrix).
Eigen::Matrix<GLfloat, 4, 4> glmatrix;
glGetFloatv (GL_MODELVIEW_MATRIX, glmatrix.data());
Eigen::Matrix<float, 4, 1> grabber_pos;
for (int j=0; j<3; ++j)
grabber_pos(j) = m_grabbers[i].center(j);
grabber_pos[3] = 1.f;
Eigen::Matrix<float, 4, 1> grabber_world_position = glmatrix * grabber_pos;
if (!picking && (m_hover_id == i))
{
render_color[0] = 1.0f - m_grabbers[i].color[0];
@ -1880,8 +1899,10 @@ void GLGizmoSlaSupports::render_grabbers(const GLCanvas3D::Selection& selection,
::glColor3fv(render_color);
::glPushMatrix();
::glTranslated(m_grabbers[i].center(0), m_grabbers[i].center(1), m_grabbers[i].center(2));
::gluSphere(m_quadric, 0.75, 36, 18);
::glLoadIdentity();
::glTranslated(grabber_world_position(0), grabber_world_position(1), grabber_world_position(2) + z_shift);
::gluQuadricDrawStyle(m_quadric, GLU_SILHOUETTE);
::gluSphere(m_quadric, 0.75, 64, 36);
::glPopMatrix();
}
@ -1930,7 +1951,7 @@ void GLGizmoSlaSupports::render_grabbers(bool picking) const
GLUquadricObj *quadric;
quadric = ::gluNewQuadric();
::gluQuadricDrawStyle(quadric, GLU_FILL );
::gluSphere( quadric , 0.75f, 36 , 18 );
::gluSphere( quadric , 0.75f, 64 , 32 );
::gluDeleteQuadric(quadric);
::glPopMatrix();
if (!picking)
@ -1989,6 +2010,7 @@ void GLGizmoSlaSupports::update_mesh()
// we'll now reload Grabbers (selection might have changed):
m_grabbers.clear();
for (const Vec3f& point : m_model_object->sla_support_points) {
m_grabbers.push_back(Grabber());
m_grabbers.back().center = point.cast<double>();
@ -2080,7 +2102,6 @@ void GLGizmoSlaSupports::delete_current_grabber(bool delete_all)
if (delete_all) {
m_grabbers.clear();
m_model_object->sla_support_points.clear();
m_parent.reload_scene(true); // in case this was called from ImGui overlay dialog, the refresh would be delayed
// This should trigger the support generation
// wxGetApp().plater()->reslice();
@ -2156,12 +2177,34 @@ void GLGizmoSlaSupports::on_render_input_window(float x, float y, const GLCanvas
m_imgui->text(_(L("Right mouse click - remove point")));
m_imgui->text(" ");
bool remove_all_clicked = m_imgui->button(_(L("Remove all points")));
bool generate = m_imgui->button(_(L("Generate points automatically")));
bool remove_all_clicked = m_imgui->button(_(L("Remove all points")) + (m_model_object == nullptr ? "" : " (" + std::to_string(m_model_object->sla_support_points.size())+")"));
m_imgui->end();
if (remove_all_clicked)
delete_current_grabber(true);
if (generate) {
const DynamicPrintConfig& cfg = *wxGetApp().get_tab(Preset::TYPE_SLA_PRINT)->get_config();
SLAAutoSupports::Config config;
config.density_at_horizontal = cfg.opt_int("support_density_at_horizontal") / 10000.f;
config.density_at_45 = cfg.opt_int("support_density_at_45") / 10000.f;
config.minimal_z = cfg.opt_float("support_minimal_z");
SLAAutoSupports sas(*m_model_object, config);
sas.generate();
m_grabbers.clear();
for (const Vec3f& point : m_model_object->sla_support_points) {
m_grabbers.push_back(Grabber());
m_grabbers.back().center = point.cast<double>();
}
}
if (remove_all_clicked || generate) {
m_parent.reload_scene(true);
m_parent.post_event(SimpleEvent(EVT_GLCANVAS_SCHEDULE_BACKGROUND_PROCESS));
}
}
#endif // ENABLE_IMGUI
@ -2177,6 +2220,7 @@ bool GLGizmoSlaSupports::on_is_selectable() const
}
std::string GLGizmoSlaSupports::on_get_name() const
{
return L("SLA Support Points");
}

View file

@ -5,8 +5,10 @@
#include "../../slic3r/GUI/GLTexture.hpp"
#include "../../slic3r/GUI/GLCanvas3D.hpp"
#include "libslic3r/Point.hpp"
#include "libslic3r/BoundingBox.hpp"
#include "libslic3r/SLA/SLAAutoSupports.hpp"
#include <array>
#include <vector>
@ -434,6 +436,7 @@ protected:
class GLGizmoSlaSupports : public GLGizmoBase
{
private:
SLAAutoSupports* m_sas = nullptr;
ModelObject* m_model_object = nullptr;
#if ENABLE_SLA_SUPPORT_GIZMO_MOD
ModelObject* m_old_model_object = nullptr;

View file

@ -733,7 +733,7 @@ void Sidebar::show_info_sizer()
auto& stats = model_object->volumes.front()->mesh.stl.stats;
auto sf = model_instance->get_scaling_factor();
p->object_info->info_volume->SetLabel(wxString::Format("%.2f", stats.volume * sf(0) * sf(1) * sf(2)));
p->object_info->info_volume->SetLabel(wxString::Format("%.2f", size(0) * size(1) * size(2) * sf(0) * sf(1) * sf(2)));
p->object_info->info_facets->SetLabel(wxString::Format(_(L("%d (%d shells)")), static_cast<int>(model_object->facets_count()), stats.number_of_parts));
int errors = stats.degenerate_facets + stats.edges_fixed + stats.facets_removed +
@ -914,7 +914,7 @@ struct Plater::priv
wxMenu sla_object_menu;
// Data
Slic3r::DynamicPrintConfig *config;
Slic3r::DynamicPrintConfig *config; // FIXME: leak?
Slic3r::Print fff_print;
Slic3r::SLAPrint sla_print;
Slic3r::Model model;
@ -1010,7 +1010,6 @@ struct Plater::priv
unsigned int update_background_process();
void async_apply_config();
void reload_from_disk();
void export_object_stl();
void fix_through_netfabb(const int obj_idx);
#if ENABLE_REMOVE_TABS_FROM_PLATER
@ -2097,12 +2096,33 @@ void Plater::priv::update_sla_scene()
void Plater::priv::reload_from_disk()
{
// TODO
}
const auto &selection = get_selection();
const auto obj_orig_idx = selection.get_object_idx();
if (selection.is_wipe_tower() || obj_orig_idx == -1) { return; }
void Plater::priv::export_object_stl()
{
// TODO
auto *object_orig = model.objects[obj_orig_idx];
std::vector<fs::path> input_paths(1, object_orig->input_file);
const auto new_idxs = load_files(input_paths, true, false);
for (const auto idx : new_idxs) {
ModelObject *object = model.objects[idx];
object->clear_instances();
for (const ModelInstance *instance : object_orig->instances) {
object->add_instance(*instance);
}
if (object->volumes.size() == object_orig->volumes.size()) {
for (size_t i = 0; i < object->volumes.size(); i++) {
object->volumes[i]->config.apply(object_orig->volumes[i]->config);
}
}
// XXX: Restore more: layer_height_ranges, layer_height_profile, layer_height_profile_valid (?)
}
remove(obj_orig_idx);
}
void Plater::priv::fix_through_netfabb(const int obj_idx)
@ -2524,6 +2544,12 @@ bool Plater::priv::complit_init_object_menu()
wxMenuItem* item_split = append_submenu(&object_menu, split_menu, wxID_ANY, _(L("Split")), _(L("Split the selected object")), "shape_ungroup.png");
append_menu_item(&object_menu, wxID_ANY, _(L("Reload from Disk")), _(L("Reload the selected file from Disk")),
[this](wxCommandEvent&) { reload_from_disk(); });
append_menu_item(&object_menu, wxID_ANY, _(L("Export object as STL…")), _(L("Export this single object as STL file")),
[this](wxCommandEvent&) { q->export_stl(true); });
// Append "Add..." popupmenu
object_menu.AppendSeparator();
sidebar->obj_list()->append_menu_items_add_volume(&object_menu);
@ -2932,7 +2958,7 @@ void Plater::export_gcode(fs::path output_path)
}
}
void Plater::export_stl()
void Plater::export_stl(bool selection_only)
{
if (p->model.objects.empty()) { return; }
@ -2942,7 +2968,19 @@ void Plater::export_stl()
// Store a binary STL
wxString path = dialog->GetPath();
auto path_cstr = path.c_str();
auto mesh = p->model.mesh();
TriangleMesh mesh;
if (selection_only) {
const auto &selection = p->get_selection();
if (selection.is_wipe_tower()) { return; }
const auto obj_idx = selection.get_object_idx();
if (obj_idx == -1) { return; }
mesh = p->model.objects[obj_idx]->mesh();
} else {
auto mesh = p->model.mesh();
}
Slic3r::store_stl(path_cstr, &mesh, true);
p->statusbar()->set_status_text(wxString::Format(_(L("STL file exported to %s")), path));
}

View file

@ -146,7 +146,7 @@ public:
// Note: empty path means "use the default"
void export_gcode(boost::filesystem::path output_path = boost::filesystem::path());
void export_stl();
void export_stl(bool selection_only = false);
void export_amf();
void export_3mf(const boost::filesystem::path& output_path = boost::filesystem::path());
void reslice();

View file

@ -403,6 +403,9 @@ const std::vector<std::string>& Preset::sla_print_options()
"support_critical_angle",
"support_max_bridge_length",
"support_object_elevation",
"support_density_at_horizontal",
"support_density_at_45",
"support_minimal_z",
"pad_enable",
"pad_wall_thickness",
"pad_wall_height",

View file

@ -3112,6 +3112,11 @@ void TabSLAPrint::build()
optgroup->append_single_option_line("support_critical_angle");
optgroup->append_single_option_line("support_max_bridge_length");
optgroup = page->new_optgroup(_(L("Automatic generation")));
optgroup->append_single_option_line("support_density_at_horizontal");
optgroup->append_single_option_line("support_density_at_45");
optgroup->append_single_option_line("support_minimal_z");
page = add_options_page(_(L("Pad")), "brick.png");
optgroup = page->new_optgroup(_(L("Pad")));
optgroup->append_single_option_line("pad_enable");