Merge remote-tracking branch 'remotes/origin/dev_native' into vb_3dscene_partial_update
This commit is contained in:
commit
dafa4621aa
@ -935,6 +935,10 @@ public:
|
||||
// The max length of a bridge in mm
|
||||
ConfigOptionFloat support_max_bridge_length /*= 15.0*/;
|
||||
|
||||
// The elevation in Z direction upwards. This is the space between the pad
|
||||
// and the model object's bounding box bottom.
|
||||
ConfigOptionFloat support_object_elevation;
|
||||
|
||||
// Now for the base pool (plate) ///////////////////////////////////////////
|
||||
|
||||
ConfigOptionFloat pad_wall_thickness /*= 2*/;
|
||||
|
@ -418,17 +418,32 @@ ExPolygons concave_hull(const ExPolygons& polys, double max_dist_mm = 50)
|
||||
return punion;
|
||||
}
|
||||
|
||||
void base_plate(const TriangleMesh &mesh, ExPolygons &output, float h)
|
||||
void base_plate(const TriangleMesh &mesh, ExPolygons &output, float h,
|
||||
float layerh)
|
||||
{
|
||||
TriangleMesh m = mesh;
|
||||
TriangleMeshSlicer slicer(&m);
|
||||
|
||||
TriangleMesh upper, lower;
|
||||
slicer.cut(h, &upper, &lower);
|
||||
// TriangleMesh upper, lower;
|
||||
// slicer.cut(h, &upper, &lower);
|
||||
|
||||
// TODO: this might be slow
|
||||
output = lower.horizontal_projection();
|
||||
// TODO: this might be slow (in fact it was)
|
||||
// output = lower.horizontal_projection();
|
||||
|
||||
auto bb = mesh.bounding_box();
|
||||
float gnd = float(bb.min(Z));
|
||||
std::vector<float> heights = {float(bb.min(Z))};
|
||||
for(float hi = gnd + layerh; hi <= gnd + h; hi += layerh)
|
||||
heights.emplace_back(hi);
|
||||
|
||||
std::vector<ExPolygons> out; out.reserve(size_t(std::ceil(h/layerh)));
|
||||
slicer.slice(heights, &out, [](){});
|
||||
|
||||
size_t count = 0; for(auto& o : out) count += o.size();
|
||||
ExPolygons tmp; tmp.reserve(count);
|
||||
for(auto& o : out) for(auto& e : o) tmp.emplace_back(std::move(e));
|
||||
|
||||
output = unify(tmp);
|
||||
for(auto& o : output) o = o.simplify(0.1/SCALING_FACTOR).front();
|
||||
}
|
||||
|
||||
|
@ -15,7 +15,8 @@ using ExPolygons = std::vector<ExPolygon>;
|
||||
/// Calculate the polygon representing the silhouette from the specified height
|
||||
void base_plate(const TriangleMesh& mesh,
|
||||
ExPolygons& output,
|
||||
float height = 0.1f);
|
||||
float zlevel = 0.1f,
|
||||
float layerheight = 0.05f);
|
||||
|
||||
struct PoolConfig {
|
||||
double min_wall_thickness_mm = 2;
|
||||
|
@ -9,6 +9,7 @@
|
||||
#include "SLASpatIndex.hpp"
|
||||
#include "SLABasePool.hpp"
|
||||
#include <libnest2d/tools/benchmark.h>
|
||||
#include "ClipperUtils.hpp"
|
||||
|
||||
#include "Model.hpp"
|
||||
|
||||
@ -70,12 +71,6 @@ template<class Vec> double distance(const Vec& pp1, const Vec& pp2) {
|
||||
return distance(p);
|
||||
}
|
||||
|
||||
/// The horizontally projected 2D boundary of the model as individual line
|
||||
/// segments. This can be used later to create a spatial index of line segments
|
||||
/// and query for possible pillar positions for non-ground facing support points
|
||||
std::vector<std::pair<Vec2d, Vec2d>> model_boundary(const EigenMesh3D& emesh,
|
||||
double offs = 0.01);
|
||||
|
||||
Contour3D sphere(double rho, Portion portion = make_portion(0.0, 2.0*PI),
|
||||
double fa=(2*PI/360)) {
|
||||
|
||||
@ -416,9 +411,9 @@ struct Pillar {
|
||||
base.points.emplace_back(ep);
|
||||
|
||||
auto& indices = base.indices;
|
||||
auto hcenter = base.points.size() - 1;
|
||||
auto lcenter = base.points.size() - 2;
|
||||
auto offs = steps;
|
||||
auto hcenter = int(base.points.size() - 1);
|
||||
auto lcenter = int(base.points.size() - 2);
|
||||
auto offs = int(steps);
|
||||
for(int i = 0; i < steps - 1; ++i) {
|
||||
indices.emplace_back(i, i + offs, offs + i + 1);
|
||||
indices.emplace_back(i, offs + i + 1, i + 1);
|
||||
@ -426,7 +421,7 @@ struct Pillar {
|
||||
indices.emplace_back(lcenter, offs + i + 1, offs + i);
|
||||
}
|
||||
|
||||
auto last = steps - 1;
|
||||
auto last = int(steps - 1);
|
||||
indices.emplace_back(0, last, offs);
|
||||
indices.emplace_back(last, offs + last, offs);
|
||||
indices.emplace_back(hcenter, last, 0);
|
||||
@ -510,15 +505,20 @@ struct Pad {
|
||||
Pad() {}
|
||||
|
||||
Pad(const TriangleMesh& object_support_mesh,
|
||||
const ExPolygons& baseplate,
|
||||
double ground_level,
|
||||
const PoolConfig& cfg) : zlevel(ground_level)
|
||||
const PoolConfig& cfg) : zlevel(ground_level + cfg.min_wall_height_mm/2)
|
||||
{
|
||||
ExPolygons basep;
|
||||
base_plate(object_support_mesh, basep);
|
||||
base_plate(object_support_mesh, basep,
|
||||
float(cfg.min_wall_height_mm)/*,layer_height*/);
|
||||
for(auto& bp : baseplate) basep.emplace_back(bp);
|
||||
|
||||
create_base_pool(basep, tmesh, cfg);
|
||||
tmesh.translate(0, 0, float(zlevel));
|
||||
std::cout << "pad ground level " << zlevel << std::endl;
|
||||
}
|
||||
|
||||
bool empty() const { return tmesh.facets_count() == 0; }
|
||||
};
|
||||
|
||||
EigenMesh3D to_eigenmesh(const Contour3D& cntr) {
|
||||
@ -563,6 +563,10 @@ EigenMesh3D to_eigenmesh(const TriangleMesh& tmesh) {
|
||||
const stl_file& stl = tmesh.stl;
|
||||
|
||||
EigenMesh3D outmesh;
|
||||
|
||||
auto&& bb = tmesh.bounding_box();
|
||||
outmesh.ground_level += bb.min(Z);
|
||||
|
||||
auto& V = outmesh.V;
|
||||
auto& F = outmesh.F;
|
||||
|
||||
@ -586,11 +590,7 @@ EigenMesh3D to_eigenmesh(const TriangleMesh& tmesh) {
|
||||
}
|
||||
|
||||
EigenMesh3D to_eigenmesh(const ModelObject& modelobj) {
|
||||
auto&& rmesh = modelobj.raw_mesh();
|
||||
auto&& ret = to_eigenmesh(rmesh);
|
||||
auto&& bb = rmesh.bounding_box();
|
||||
ret.ground_level = bb.min(Z);
|
||||
return ret;
|
||||
return to_eigenmesh(modelobj.raw_mesh());
|
||||
}
|
||||
|
||||
EigenMesh3D to_eigenmesh(const Model& model) {
|
||||
@ -608,7 +608,12 @@ EigenMesh3D to_eigenmesh(const Model& model) {
|
||||
return to_eigenmesh(combined_mesh);
|
||||
}
|
||||
|
||||
|
||||
PointSet to_point_set(const std::vector<Vec3d> &v)
|
||||
{
|
||||
PointSet ret(v.size(), 3);
|
||||
{ long i = 0; for(const Vec3d& p : v) ret.row(i++) = p; }
|
||||
return ret;
|
||||
}
|
||||
|
||||
Vec3d model_coord(const ModelInstance& object, const Vec3f& mesh_coord) {
|
||||
return object.transform_vector(mesh_coord.cast<double>());
|
||||
@ -635,9 +640,18 @@ PointSet support_points(const Model& model) {
|
||||
PointSet support_points(const ModelObject& modelobject)
|
||||
{
|
||||
PointSet ret(modelobject.sla_support_points.size(), 3);
|
||||
auto rot = modelobject.instances.front()->get_rotation();
|
||||
// auto scaling = modelobject.instances.front()->get_scaling_factor();
|
||||
|
||||
// Transform3d tr;
|
||||
// tr.rotate(Eigen::AngleAxisd(rot(X), Vec3d::UnitX()) *
|
||||
// Eigen::AngleAxisd(rot(Y), Vec3d::UnitY()));
|
||||
|
||||
long i = 0;
|
||||
for(const Vec3f& msource : modelobject.sla_support_points) {
|
||||
ret.row(i++) = msource.cast<double>();
|
||||
Vec3d&& p = msource.cast<double>();
|
||||
// p = tr * p;
|
||||
ret.row(i++) = p;
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
@ -694,20 +708,18 @@ public:
|
||||
return m_pillars.back();
|
||||
}
|
||||
|
||||
const Head& pillar_head(long pillar_id) {
|
||||
assert(pillar_id > 0 && pillar_id < m_pillars.size());
|
||||
Pillar& p = m_pillars[pillar_id];
|
||||
assert(p.starts_from_head && p.start_junction_id > 0 &&
|
||||
const Head& pillar_head(long pillar_id) const {
|
||||
assert(pillar_id >= 0 && pillar_id < m_pillars.size());
|
||||
const Pillar& p = m_pillars[pillar_id];
|
||||
assert(p.starts_from_head && p.start_junction_id >= 0 &&
|
||||
p.start_junction_id < m_heads.size() );
|
||||
meshcache_valid = false;
|
||||
return m_heads[p.start_junction_id];
|
||||
}
|
||||
|
||||
const Pillar& head_pillar(long headid) {
|
||||
const Pillar& head_pillar(long headid) const {
|
||||
assert(headid >= 0 && headid < m_heads.size());
|
||||
Head& h = m_heads[headid];
|
||||
assert(h.pillar_id > 0 && h.pillar_id < m_pillars.size());
|
||||
meshcache_valid = false;
|
||||
const Head& h = m_heads[headid];
|
||||
assert(h.pillar_id >= 0 && h.pillar_id < m_pillars.size());
|
||||
return m_pillars[h.pillar_id];
|
||||
}
|
||||
|
||||
@ -743,8 +755,9 @@ public:
|
||||
}
|
||||
|
||||
const Pad& create_pad(const TriangleMesh& object_supports,
|
||||
const ExPolygons& baseplate,
|
||||
const PoolConfig& cfg) {
|
||||
m_pad = Pad(object_supports, ground_level, cfg);
|
||||
m_pad = Pad(object_supports, baseplate, ground_level, cfg);
|
||||
return m_pad;
|
||||
}
|
||||
|
||||
@ -778,16 +791,25 @@ public:
|
||||
}
|
||||
|
||||
BoundingBoxf3&& bb = meshcache.bounding_box();
|
||||
model_height = bb.max(Z);
|
||||
model_height = bb.max(Z) - bb.min(Z);
|
||||
|
||||
meshcache_valid = true;
|
||||
return meshcache;
|
||||
}
|
||||
|
||||
// WITH THE PAD
|
||||
double full_height() const {
|
||||
double h = mesh_height();
|
||||
if(!pad().empty()) h += pad().cfg.min_wall_height_mm / 2;
|
||||
return h;
|
||||
}
|
||||
|
||||
// WITHOUT THE PAD!!!
|
||||
double mesh_height() const {
|
||||
if(!meshcache_valid) merged_mesh();
|
||||
return model_height;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
template<class DistFn>
|
||||
@ -990,7 +1012,6 @@ bool SLASupportTree::generate(const PointSet &points,
|
||||
using Result = SLASupportTree::Impl;
|
||||
|
||||
Result& result = *m_impl;
|
||||
result.ground_level = mesh.ground_level;
|
||||
|
||||
enum Steps {
|
||||
BEGIN,
|
||||
@ -1259,13 +1280,11 @@ bool SLASupportTree::generate(const PointSet &points,
|
||||
const double hbr = cfg.head_back_radius_mm;
|
||||
const double pradius = cfg.pillar_radius_mm;
|
||||
const double maxbridgelen = cfg.max_bridge_length_mm;
|
||||
const double gndlvl = emesh.ground_level - cfg.object_elevation_mm;
|
||||
const double gndlvl = result.ground_level;
|
||||
|
||||
ClusterEl cl_centroids;
|
||||
cl_centroids.reserve(gnd_clusters.size());
|
||||
|
||||
std::cout << "gnd_clusters size: " << gnd_clusters.size() << std::endl;
|
||||
|
||||
SpatIndex pheadindex; // spatial index for the junctions
|
||||
for(auto cl : gnd_clusters) {
|
||||
// place all the centroid head positions into the index. We will
|
||||
@ -1665,52 +1684,34 @@ void SLASupportTree::merged_mesh_with_pad(TriangleMesh &outmesh) const {
|
||||
outmesh.merge(get_pad());
|
||||
}
|
||||
|
||||
template<class T> void slice_part(const T& inp,
|
||||
std::vector<SlicedSupports>& mergev,
|
||||
const std::vector<float>& heights)
|
||||
{
|
||||
for(auto& part : inp) {
|
||||
TriangleMesh&& m = mesh(part.mesh);
|
||||
TriangleMeshSlicer slicer(&m);
|
||||
SlicedSupports slout;
|
||||
slicer.slice(heights, &slout, [](){});
|
||||
|
||||
for(size_t i = 0; i < slout.size(); i++) {
|
||||
// move the layers obtained from this mesh to the merge area
|
||||
mergev[i].emplace_back(std::move(slout[i]));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
SlicedSupports SLASupportTree::slice(float layerh, float init_layerh) const
|
||||
{
|
||||
if(init_layerh < 0) init_layerh = layerh;
|
||||
auto& stree = get();
|
||||
const float modelh = stree.full_height();
|
||||
|
||||
std::vector<float> heights; heights.reserve(size_t(modelh/layerh) + 1);
|
||||
for(float h = init_layerh; h <= modelh; h += layerh) {
|
||||
const auto modelh = float(stree.full_height());
|
||||
auto gndlvl = float(this->m_impl->ground_level);
|
||||
const Pad& pad = m_impl->pad();
|
||||
if(!pad.empty()) gndlvl -= float(pad.cfg.min_wall_height_mm/2);
|
||||
|
||||
std::vector<float> heights = {gndlvl};
|
||||
heights.reserve(size_t(modelh/layerh) + 1);
|
||||
|
||||
for(float h = gndlvl + init_layerh; h < gndlvl + modelh; h += layerh) {
|
||||
heights.emplace_back(h);
|
||||
}
|
||||
|
||||
std::vector<SlicedSupports> mergev(heights.size());
|
||||
TriangleMesh fullmesh = m_impl->merged_mesh();
|
||||
fullmesh.merge(get_pad());
|
||||
TriangleMeshSlicer slicer(&fullmesh);
|
||||
SlicedSupports ret;
|
||||
slicer.slice(heights, &ret, m_ctl.cancelfn);
|
||||
|
||||
slice_part(stree.heads(), mergev, heights);
|
||||
slice_part(stree.pillars(), mergev, heights);
|
||||
slice_part(stree.junctions(), mergev, heights);
|
||||
slice_part(stree.bridges(), mergev, heights);
|
||||
slice_part(stree.compact_bridges(), mergev, heights);
|
||||
|
||||
// TODO: do this for all
|
||||
|
||||
for(SlicedSupports& level : mergev) {
|
||||
// TODO merge all expolygon in the current level
|
||||
}
|
||||
|
||||
return {};
|
||||
return ret;
|
||||
}
|
||||
|
||||
const TriangleMesh &SLASupportTree::add_pad(double min_wall_thickness_mm,
|
||||
const TriangleMesh &SLASupportTree::add_pad(const SliceLayer& baseplate,
|
||||
double min_wall_thickness_mm,
|
||||
double min_wall_height_mm,
|
||||
double max_merge_distance_mm,
|
||||
double edge_radius_mm) const
|
||||
@ -1722,7 +1723,7 @@ const TriangleMesh &SLASupportTree::add_pad(double min_wall_thickness_mm,
|
||||
// pcfg.min_wall_height_mm = min_wall_height_mm;
|
||||
// pcfg.max_merge_distance_mm = max_merge_distance_mm;
|
||||
// pcfg.edge_radius_mm = edge_radius_mm;
|
||||
return m_impl->create_pad(mm, pcfg).tmesh;
|
||||
return m_impl->create_pad(mm, baseplate, pcfg).tmesh;
|
||||
}
|
||||
|
||||
const TriangleMesh &SLASupportTree::get_pad() const
|
||||
@ -1730,9 +1731,17 @@ const TriangleMesh &SLASupportTree::get_pad() const
|
||||
return m_impl->pad().tmesh;
|
||||
}
|
||||
|
||||
double SLASupportTree::get_elevation() const
|
||||
{
|
||||
double ph = m_impl->pad().empty()? 0 :
|
||||
m_impl->pad().cfg.min_wall_height_mm/2.0;
|
||||
return -m_impl->ground_level + ph;
|
||||
}
|
||||
|
||||
SLASupportTree::SLASupportTree(const Model& model,
|
||||
const SupportConfig& cfg,
|
||||
const Controller& ctl): m_impl(new Impl())
|
||||
const Controller& ctl):
|
||||
m_impl(new Impl()), m_ctl(ctl)
|
||||
{
|
||||
generate(support_points(model), to_eigenmesh(model), cfg, ctl);
|
||||
}
|
||||
@ -1740,13 +1749,15 @@ SLASupportTree::SLASupportTree(const Model& model,
|
||||
SLASupportTree::SLASupportTree(const PointSet &points,
|
||||
const EigenMesh3D& emesh,
|
||||
const SupportConfig &cfg,
|
||||
const Controller &ctl): m_impl(new Impl())
|
||||
const Controller &ctl):
|
||||
m_impl(new Impl()), m_ctl(ctl)
|
||||
{
|
||||
m_impl->ground_level = emesh.ground_level - cfg.object_elevation_mm;
|
||||
generate(points, emesh, cfg, ctl);
|
||||
}
|
||||
|
||||
SLASupportTree::SLASupportTree(const SLASupportTree &c):
|
||||
m_impl( new Impl(*c.m_impl)) {}
|
||||
m_impl(new Impl(*c.m_impl)), m_ctl(c.m_ctl) {}
|
||||
|
||||
SLASupportTree &SLASupportTree::operator=(const SLASupportTree &c)
|
||||
{
|
||||
|
@ -63,16 +63,25 @@ struct SupportConfig {
|
||||
|
||||
// The elevation in Z direction upwards. This is the space between the pad
|
||||
// and the model object's bounding box bottom.
|
||||
double object_elevation_mm = 0;
|
||||
double object_elevation_mm = 10;
|
||||
};
|
||||
|
||||
/// A Control structure for the support calculation. Consists of the status
|
||||
/// indicator callback and the stop condition predicate.
|
||||
struct Controller {
|
||||
|
||||
// This will signal the status of the calculation to the front-end
|
||||
std::function<void(unsigned, const std::string&)> statuscb =
|
||||
[](unsigned, const std::string&){};
|
||||
|
||||
// Returns true if the calculation should be aborted.
|
||||
std::function<bool(void)> stopcondition = [](){ return false; };
|
||||
|
||||
// Similar to cancel callback. This should check the stop condition and
|
||||
// if true, throw an appropriate exception. (TriangleMeshSlicer needs this)
|
||||
// consider it a hard abort. stopcondition is permits the algorithm to
|
||||
// terminate itself
|
||||
std::function<void(void)> cancelfn = [](){};
|
||||
};
|
||||
|
||||
/// An index-triangle structure for libIGL functions. Also serves as an
|
||||
@ -101,11 +110,15 @@ void add_sla_supports(Model& model, const SupportConfig& cfg = {},
|
||||
const Controller& ctl = {});
|
||||
|
||||
EigenMesh3D to_eigenmesh(const TriangleMesh& m);
|
||||
PointSet to_point_set(const std::vector<Vec3d>&);
|
||||
|
||||
|
||||
// obsolete, not used anymore
|
||||
EigenMesh3D to_eigenmesh(const Model& model);
|
||||
EigenMesh3D to_eigenmesh(const ModelObject& model);
|
||||
|
||||
PointSet support_points(const Model& model);
|
||||
PointSet support_points(const ModelObject& modelobject);
|
||||
PointSet support_points(const Model& model);
|
||||
|
||||
|
||||
/* ************************************************************************** */
|
||||
|
||||
@ -120,6 +133,7 @@ public:
|
||||
class SLASupportTree {
|
||||
class Impl;
|
||||
std::unique_ptr<Impl> m_impl;
|
||||
Controller m_ctl;
|
||||
|
||||
Impl& get() { return *m_impl; }
|
||||
const Impl& get() const { return *m_impl; }
|
||||
@ -160,7 +174,8 @@ public:
|
||||
SlicedSupports slice(float layerh, float init_layerh = -1.0) const;
|
||||
|
||||
/// Adding the "pad" (base pool) under the supports
|
||||
const TriangleMesh& add_pad(double min_wall_thickness_mm,
|
||||
const TriangleMesh& add_pad(const SliceLayer& baseplate,
|
||||
double min_wall_thickness_mm,
|
||||
double min_wall_height_mm,
|
||||
double max_merge_distance_mm,
|
||||
double edge_radius_mm) const;
|
||||
@ -168,6 +183,11 @@ public:
|
||||
/// Get the pad geometry
|
||||
const TriangleMesh& get_pad() const;
|
||||
|
||||
/// The Z offset to raise the model and the supports to the ground level.
|
||||
/// This is the elevation given in the support config and the height of the
|
||||
/// pad (if requested).
|
||||
double get_elevation() const;
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -1,5 +1,6 @@
|
||||
#include "SLAPrint.hpp"
|
||||
#include "SLA/SLASupportTree.hpp"
|
||||
#include "SLA/SLABasePool.hpp"
|
||||
|
||||
#include <tbb/parallel_for.h>
|
||||
//#include <tbb/spin_mutex.h>//#include "tbb/mutex.h"
|
||||
@ -27,12 +28,12 @@ namespace {
|
||||
|
||||
const std::array<unsigned, slaposCount> OBJ_STEP_LEVELS =
|
||||
{
|
||||
0,
|
||||
20,
|
||||
30,
|
||||
50,
|
||||
70,
|
||||
80,
|
||||
100
|
||||
90
|
||||
};
|
||||
|
||||
const std::array<std::string, slaposCount> OBJ_STEP_LABELS =
|
||||
@ -47,8 +48,9 @@ const std::array<std::string, slaposCount> OBJ_STEP_LABELS =
|
||||
|
||||
const std::array<unsigned, slapsCount> PRINT_STEP_LEVELS =
|
||||
{
|
||||
// This is after processing all the Print objects, so we start from 50%
|
||||
50, // slapsRasterize
|
||||
100, // slapsValidate
|
||||
90, // slapsValidate
|
||||
};
|
||||
|
||||
const std::array<std::string, slapsCount> PRINT_STEP_LABELS =
|
||||
@ -118,8 +120,6 @@ void SLAPrint::process()
|
||||
{
|
||||
using namespace sla;
|
||||
|
||||
std::cout << "SLA Processing triggered" << std::endl;
|
||||
|
||||
// Assumption: at this point the print objects should be populated only with
|
||||
// the model objects we have to process and the instances are also filtered
|
||||
|
||||
@ -128,31 +128,32 @@ void SLAPrint::process()
|
||||
|
||||
// Slicing the model object. This method is oversimplified and needs to
|
||||
// be compared with the fff slicing algorithm for verification
|
||||
auto slice_model = [ilh](SLAPrintObject& po) {
|
||||
auto slice_model = [this, ilh](SLAPrintObject& po) {
|
||||
auto lh = float(po.m_config.layer_height.getFloat());
|
||||
|
||||
ModelObject *o = po.m_model_object;
|
||||
|
||||
TriangleMesh&& mesh = o->raw_mesh();
|
||||
TriangleMesh mesh = po.transformed_mesh();
|
||||
TriangleMeshSlicer slicer(&mesh);
|
||||
auto bb3d = mesh.bounding_box();
|
||||
|
||||
auto H = bb3d.max(Z) - bb3d.min(Z);
|
||||
std::vector<float> heights = {ilh};
|
||||
for(float h = ilh; h < H; h += lh) heights.emplace_back(h);
|
||||
auto gnd = float(bb3d.min(Z));
|
||||
std::vector<float> heights = {gnd};
|
||||
for(float h = gnd + ilh; h < gnd + H; h += lh) heights.emplace_back(h);
|
||||
|
||||
auto& layers = po.m_model_slices;
|
||||
slicer.slice(heights, &layers, [](){});
|
||||
slicer.slice(heights, &layers, [this](){
|
||||
throw_if_canceled();
|
||||
});
|
||||
};
|
||||
|
||||
auto support_points = [](SLAPrintObject& po) {
|
||||
ModelObject& mo = *po.m_model_object;
|
||||
if(!mo.sla_support_points.empty()) {
|
||||
po.m_supportdata.reset(new SLAPrintObject::SupportData());
|
||||
po.m_supportdata->emesh = sla::to_eigenmesh(mo);
|
||||
po.m_supportdata->support_points = sla::support_points(mo);
|
||||
po.m_supportdata->emesh = sla::to_eigenmesh(po.transformed_mesh());
|
||||
|
||||
std::cout << "support points copied "
|
||||
<< po.m_supportdata->support_points.rows() << std::endl;
|
||||
po.m_supportdata->support_points =
|
||||
sla::to_point_set(po.transformed_support_points());
|
||||
}
|
||||
|
||||
// for(SLAPrintObject *po : pobjects) {
|
||||
@ -163,6 +164,8 @@ void SLAPrint::process()
|
||||
|
||||
// In this step we create the supports
|
||||
auto support_tree = [this](SLAPrintObject& po) {
|
||||
if(!po.m_supportdata) return;
|
||||
|
||||
auto& emesh = po.m_supportdata->emesh;
|
||||
auto& pts = po.m_supportdata->support_points; // nowhere filled yet
|
||||
try {
|
||||
@ -175,6 +178,7 @@ void SLAPrint::process()
|
||||
set_status(unsigned(stinit + st*d), msg);
|
||||
};
|
||||
ctl.stopcondition = [this](){ return canceled(); };
|
||||
ctl.cancelfn = [this]() { throw_if_canceled(); };
|
||||
|
||||
po.m_supportdata->support_tree_ptr.reset(
|
||||
new SLASupportTree(pts, emesh, scfg, ctl));
|
||||
@ -190,6 +194,7 @@ void SLAPrint::process()
|
||||
// this step can only go after the support tree has been created
|
||||
// and before the supports had been sliced. (or the slicing has to be
|
||||
// repeated)
|
||||
|
||||
if(po.is_step_done(slaposSupportTree) &&
|
||||
po.m_supportdata &&
|
||||
po.m_supportdata->support_tree_ptr)
|
||||
@ -198,8 +203,15 @@ void SLAPrint::process()
|
||||
double h = po.m_config.pad_wall_height.getFloat();
|
||||
double md = po.m_config.pad_max_merge_distance.getFloat();
|
||||
double er = po.m_config.pad_edge_radius.getFloat();
|
||||
double lh = po.m_config.layer_height.getFloat();
|
||||
double elevation = po.m_config.support_object_elevation.getFloat();
|
||||
|
||||
po.m_supportdata->support_tree_ptr->add_pad(wt, h, md, er);
|
||||
sla::ExPolygons bp;
|
||||
if(elevation < h/2)
|
||||
sla::base_plate(po.transformed_mesh(), bp,
|
||||
float(h/2), float(lh));
|
||||
|
||||
po.m_supportdata->support_tree_ptr->add_pad(bp, wt, h, md, er);
|
||||
}
|
||||
};
|
||||
|
||||
@ -216,7 +228,7 @@ void SLAPrint::process()
|
||||
|
||||
// Rasterizing the model objects, and their supports
|
||||
auto rasterize = [this, ilh]() {
|
||||
using Layer = ExPolygons;
|
||||
using Layer = sla::ExPolygons;
|
||||
using LayerCopies = std::vector<SLAPrintObject::Instance>;
|
||||
struct LayerRef {
|
||||
std::reference_wrapper<const Layer> lref;
|
||||
@ -232,12 +244,17 @@ void SLAPrint::process()
|
||||
|
||||
// For all print objects, go through its initial layers and place them
|
||||
// into the layers hash
|
||||
// long long initlyridx = static_cast<long long>(scale_(ilh));
|
||||
for(SLAPrintObject *o : m_objects) {
|
||||
|
||||
double gndlvl = o->transformed_mesh().bounding_box().min(Z);
|
||||
|
||||
double lh = o->m_config.layer_height.getFloat();
|
||||
std::vector<ExPolygons> & oslices = o->m_model_slices;
|
||||
SlicedModel & oslices = o->m_model_slices;
|
||||
for(int i = 0; i < oslices.size(); ++i) {
|
||||
double h = ilh + i * lh;
|
||||
int a = i == 0 ? 0 : 1;
|
||||
int b = i == 0 ? 0 : i - 1;
|
||||
|
||||
double h = gndlvl + ilh * a + b * lh;
|
||||
long long lyridx = static_cast<long long>(scale_(h));
|
||||
auto& lyrs = levels[lyridx]; // this initializes a new record
|
||||
lyrs.emplace_back(oslices[i], o->m_instances);
|
||||
@ -245,36 +262,25 @@ void SLAPrint::process()
|
||||
|
||||
if(o->m_supportdata) { // deal with the support slices if present
|
||||
auto& sslices = o->m_supportdata->support_slices;
|
||||
double el = o->m_config.support_object_elevation.getFloat();
|
||||
//TODO: remove next line:
|
||||
el = SupportConfig().object_elevation_mm;
|
||||
|
||||
for(int i = 0; i < sslices.size(); ++i) {
|
||||
double h = ilh + i * lh;
|
||||
int a = i == 0 ? 0 : 1;
|
||||
int b = i == 0 ? 0 : i - 1;
|
||||
|
||||
double h = gndlvl - el + ilh * a + b * lh;
|
||||
|
||||
long long lyridx = static_cast<long long>(scale_(h));
|
||||
auto& lyrs = levels[lyridx];
|
||||
lyrs.emplace_back(sslices[i], o->m_instances);
|
||||
}
|
||||
}
|
||||
|
||||
// auto& oslices = o->m_model_slices;
|
||||
// auto& firstlyr = oslices.front();
|
||||
// auto& initlevel = levels[initlyridx];
|
||||
// initlevel.emplace_back(firstlyr, o->m_instances);
|
||||
|
||||
// // now push the support slices as well
|
||||
// // TODO
|
||||
|
||||
// double lh = o->m_config.layer_height.getFloat();
|
||||
// size_t li = 1;
|
||||
// for(auto lit = std::next(oslices.begin());
|
||||
// lit != oslices.end();
|
||||
// ++lit)
|
||||
// {
|
||||
// double h = ilh + li++ * lh;
|
||||
// long long lyridx = static_cast<long long>(scale_(h));
|
||||
// auto& lyrs = levels[lyridx];
|
||||
// lyrs.emplace_back(*lit, o->m_instances);
|
||||
// }
|
||||
}
|
||||
|
||||
if(canceled()) return;
|
||||
|
||||
// collect all the keys
|
||||
std::vector<long long> keys; keys.reserve(levels.size());
|
||||
for(auto& e : levels) keys.emplace_back(e.first);
|
||||
@ -301,32 +307,41 @@ void SLAPrint::process()
|
||||
auto lvlcnt = unsigned(levels.size());
|
||||
printer.layers(lvlcnt);
|
||||
|
||||
// TODO exclusive progress indication for this step would be good
|
||||
// as it is the longest of all. It would require synchronization
|
||||
// in the parallel processing.
|
||||
|
||||
// procedure to process one height level. This will run in parallel
|
||||
auto lvlfn = [&keys, &levels, &printer](unsigned level_id) {
|
||||
auto lvlfn = [this, &keys, &levels, &printer](unsigned level_id) {
|
||||
if(canceled()) return;
|
||||
|
||||
LayerRefs& lrange = levels[keys[level_id]];
|
||||
|
||||
for(auto& lyrref : lrange) { // for all layers in the current level
|
||||
const Layer& l = lyrref.lref; // get the layer reference
|
||||
const LayerCopies& copies = lyrref.copies;
|
||||
ExPolygonCollection sl = l;
|
||||
// Switch to the appropriate layer in the printer
|
||||
printer.begin_layer(level_id);
|
||||
|
||||
// Switch to the appropriate layer in the printer
|
||||
printer.begin_layer(level_id);
|
||||
for(auto& lyrref : lrange) { // for all layers in the current level
|
||||
if(canceled()) break;
|
||||
const Layer& sl = lyrref.lref; // get the layer reference
|
||||
const LayerCopies& copies = lyrref.copies;
|
||||
|
||||
// Draw all the polygons in the slice to the actual layer.
|
||||
for(auto& cp : copies) {
|
||||
for(ExPolygon slice : sl.expolygons) {
|
||||
for(ExPolygon slice : sl) {
|
||||
slice.translate(cp.shift(X), cp.shift(Y));
|
||||
slice.rotate(cp.rotation);
|
||||
printer.draw_polygon(slice, level_id);
|
||||
}
|
||||
}
|
||||
|
||||
// Finish the layer for later saving it.
|
||||
printer.finish_layer(level_id);
|
||||
}
|
||||
|
||||
// Finish the layer for later saving it.
|
||||
printer.finish_layer(level_id);
|
||||
};
|
||||
|
||||
// last minute escape
|
||||
if(canceled()) return;
|
||||
|
||||
// Sequential version (for testing)
|
||||
// for(unsigned l = 0; l < lvlcnt; ++l) process_level(l);
|
||||
|
||||
@ -362,6 +377,11 @@ void SLAPrint::process()
|
||||
[](){} // validate
|
||||
};
|
||||
|
||||
const unsigned min_objstatus = 0;
|
||||
const unsigned max_objstatus = PRINT_STEP_LEVELS[slapsRasterize];
|
||||
const size_t objcount = m_objects.size();
|
||||
const double ostepd = (max_objstatus - min_objstatus) / (objcount * 100.0);
|
||||
|
||||
for(SLAPrintObject * po : m_objects) {
|
||||
for(size_t s = 0; s < pobj_program.size(); ++s) {
|
||||
auto currentstep = objectsteps[s];
|
||||
@ -372,8 +392,9 @@ void SLAPrint::process()
|
||||
throw_if_canceled();
|
||||
|
||||
if(po->m_stepmask[s] && !po->is_step_done(currentstep)) {
|
||||
set_status(OBJ_STEP_LEVELS[currentstep],
|
||||
OBJ_STEP_LABELS[currentstep]);
|
||||
unsigned st = OBJ_STEP_LEVELS[currentstep];
|
||||
st = unsigned(min_objstatus + st * ostepd);
|
||||
set_status(st, OBJ_STEP_LABELS[currentstep]);
|
||||
|
||||
po->set_started(currentstep);
|
||||
pobj_program[s](*po);
|
||||
@ -386,8 +407,8 @@ void SLAPrint::process()
|
||||
slapsRasterize, slapsValidate
|
||||
};
|
||||
|
||||
// TODO: enable rasterizing
|
||||
m_stepmask[slapsRasterize] = false;
|
||||
// this would disable the rasterization step
|
||||
// m_stepmask[slapsRasterize] = false;
|
||||
|
||||
for(size_t s = 0; s < print_program.size(); ++s) {
|
||||
auto currentstep = printsteps[s];
|
||||
@ -423,22 +444,47 @@ TriangleMesh SLAPrintObject::support_mesh() const
|
||||
if(m_supportdata && m_supportdata->support_tree_ptr)
|
||||
m_supportdata->support_tree_ptr->merged_mesh(trm);
|
||||
|
||||
// TODO: is this necessary?
|
||||
trm.repair();
|
||||
|
||||
std::cout << "support mesh united and returned" << std::endl;
|
||||
return trm;
|
||||
// return make_cube(10., 10., 10.);
|
||||
}
|
||||
|
||||
TriangleMesh SLAPrintObject::pad_mesh() const
|
||||
{
|
||||
if(!m_supportdata || !m_supportdata->support_tree_ptr) {
|
||||
std::cout << "Empty pad mesh returned.." << std::endl;
|
||||
return TriangleMesh();
|
||||
}
|
||||
if(!m_supportdata || !m_supportdata->support_tree_ptr) return {};
|
||||
|
||||
// FIXME: pad mesh is empty here for some reason.
|
||||
return m_supportdata->support_tree_ptr->get_pad();
|
||||
}
|
||||
|
||||
const TriangleMesh &SLAPrintObject::transformed_mesh() const {
|
||||
// we need to transform the raw mesh...
|
||||
// currently all the instances share the same x and y rotation and scaling
|
||||
// so we have to extract those from e.g. the first instance and apply to the
|
||||
// raw mesh. This is also true for the support points.
|
||||
// BUT: when the support structure is spawned for each instance than it has
|
||||
// to omit the X, Y rotation and scaling as those have been already applied
|
||||
// or apply an inverse transformation on the support structure after it
|
||||
// has been created.
|
||||
|
||||
if(m_trmesh_valid) return m_transformed_rmesh;
|
||||
m_transformed_rmesh = m_model_object->raw_mesh();
|
||||
m_transformed_rmesh.transform(m_trafo);
|
||||
m_trmesh_valid = true;
|
||||
return m_transformed_rmesh;
|
||||
}
|
||||
|
||||
std::vector<Vec3d> SLAPrintObject::transformed_support_points() const
|
||||
{
|
||||
assert(m_model_object != nullptr);
|
||||
auto& spts = m_model_object->sla_support_points;
|
||||
|
||||
// this could be cached as well
|
||||
std::vector<Vec3d> ret; ret.reserve(spts.size());
|
||||
|
||||
for(auto& sp : spts) ret.emplace_back( trafo() * Vec3d(sp.cast<double>()));
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
} // namespace Slic3r
|
||||
|
@ -55,6 +55,11 @@ public:
|
||||
// Support mesh is only valid if this->is_step_done(slaposPad) is true.
|
||||
TriangleMesh pad_mesh() const;
|
||||
|
||||
// This will return the transformed mesh which is cached
|
||||
const TriangleMesh& transformed_mesh() const;
|
||||
|
||||
std::vector<Vec3d> transformed_support_points() const;
|
||||
|
||||
// I refuse to grantee copying (Tamas)
|
||||
SLAPrintObject(const SLAPrintObject&) = delete;
|
||||
SLAPrintObject& operator=(const SLAPrintObject&) = delete;
|
||||
@ -69,7 +74,7 @@ protected:
|
||||
void config_apply(const ConfigBase &other, bool ignore_nonexistent = false) { this->m_config.apply(other, ignore_nonexistent); }
|
||||
void config_apply_only(const ConfigBase &other, const t_config_option_keys &keys, bool ignore_nonexistent = false)
|
||||
{ this->m_config.apply_only(other, keys, ignore_nonexistent); }
|
||||
void set_trafo(const Transform3d& trafo) { m_trafo = trafo; }
|
||||
void set_trafo(const Transform3d& trafo) { m_trafo = trafo; m_trmesh_valid = false; }
|
||||
|
||||
bool set_instances(const std::vector<Instance> &instances);
|
||||
// Invalidates the step, and its depending steps in SLAPrintObject and SLAPrint.
|
||||
@ -86,6 +91,10 @@ private:
|
||||
std::vector<bool> m_stepmask;
|
||||
std::vector<ExPolygons> m_model_slices;
|
||||
|
||||
// Caching the transformed (m_trafo) raw mesh of the object
|
||||
mutable TriangleMesh m_transformed_rmesh;
|
||||
mutable bool m_trmesh_valid = false;
|
||||
|
||||
class SupportData;
|
||||
std::unique_ptr<SupportData> m_supportdata;
|
||||
};
|
||||
|
@ -6,7 +6,7 @@
|
||||
//============
|
||||
|
||||
// Shows camera target in the 3D scene
|
||||
#define ENABLE_SHOW_CAMERA_TARGET 1
|
||||
#define ENABLE_SHOW_CAMERA_TARGET 0
|
||||
|
||||
//=============
|
||||
// 1.42.0 techs
|
||||
@ -23,8 +23,12 @@
|
||||
#define ENABLE_MODIFIED_CAMERA_TARGET (1 && ENABLE_1_42_0)
|
||||
// Add Geometry::Transformation class and use it into ModelInstance, ModelVolume and GLVolume
|
||||
#define ENABLE_MODELVOLUME_TRANSFORM (1 && ENABLE_1_42_0)
|
||||
// Keeps objects on bed while scaling them using the scale gizmo
|
||||
#define ENABLE_ENSURE_ON_BED_WHILE_SCALING (1 && ENABLE_MODELVOLUME_TRANSFORM)
|
||||
// Gizmos always rendered on top of objects
|
||||
#define ENABLE_GIZMOS_ON_TOP (1 && ENABLE_1_42_0)
|
||||
// New menu layout (open/save/save as project + import/export)
|
||||
#define ENABLE_NEW_MENU_LAYOUT (1 && ENABLE_1_42_0)
|
||||
|
||||
#endif // _technologies_h_
|
||||
|
||||
|
@ -1103,6 +1103,9 @@ GLCanvas3D::Mouse::Drag::Drag()
|
||||
GLCanvas3D::Mouse::Mouse()
|
||||
: dragging(false)
|
||||
, position(DBL_MAX, DBL_MAX)
|
||||
#if ENABLE_GIZMOS_ON_TOP
|
||||
, scene_position(DBL_MAX, DBL_MAX, DBL_MAX)
|
||||
#endif // ENABLE_GIZMOS_ON_TOP
|
||||
#if ENABLE_GIZMOS_RESET
|
||||
, ignore_up_event(false)
|
||||
#endif // ENABLE_GIZMOS_RESET
|
||||
@ -1677,6 +1680,10 @@ void GLCanvas3D::Selection::scale(const Vec3d& scale)
|
||||
_synchronize_unselected_volumes();
|
||||
#endif // !DISABLE_INSTANCES_SYNCH
|
||||
|
||||
#if ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
_ensure_on_bed();
|
||||
#endif // ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
|
||||
m_bounding_box_dirty = true;
|
||||
}
|
||||
|
||||
@ -2336,6 +2343,19 @@ void GLCanvas3D::Selection::_synchronize_unselected_volumes()
|
||||
}
|
||||
}
|
||||
|
||||
#if ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
void GLCanvas3D::Selection::_ensure_on_bed()
|
||||
{
|
||||
for (unsigned int i : m_list)
|
||||
{
|
||||
GLVolume* volume = (*m_volumes)[i];
|
||||
double min_z = volume->transformed_convex_hull_bounding_box().min(2);
|
||||
if (min_z != 0.0)
|
||||
volume->set_instance_offset(Z, volume->get_instance_offset(Z) - min_z);
|
||||
}
|
||||
}
|
||||
#endif // ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
|
||||
const float GLCanvas3D::Gizmos::OverlayTexturesScale = 0.75f;
|
||||
const float GLCanvas3D::Gizmos::OverlayOffsetX = 10.0f * OverlayTexturesScale;
|
||||
const float GLCanvas3D::Gizmos::OverlayGapY = 5.0f * OverlayTexturesScale;
|
||||
@ -3638,6 +3658,13 @@ void GLCanvas3D::render()
|
||||
_render_bed(theta);
|
||||
}
|
||||
|
||||
#if ENABLE_GIZMOS_ON_TOP
|
||||
// we need to set the mouse's scene position here because the depth buffer
|
||||
// could be invalidated by the following gizmo render methods
|
||||
// this position is used later into on_mouse() to drag the objects
|
||||
m_mouse.scene_position = _mouse_to_3d(m_mouse.position.cast<int>());
|
||||
#endif // ENABLE_GIZMOS_ON_TOP
|
||||
|
||||
_render_current_gizmo();
|
||||
_render_cutting_plane();
|
||||
#if ENABLE_SHOW_CAMERA_TARGET
|
||||
@ -4389,19 +4416,29 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
|
||||
{
|
||||
if (evt.LeftDown() && m_moving_enabled && (m_mouse.drag.move_volume_idx == -1))
|
||||
{
|
||||
#if !ENABLE_GIZMOS_ON_TOP
|
||||
// The mouse_to_3d gets the Z coordinate from the Z buffer at the screen coordinate pos x, y,
|
||||
// an converts the screen space coordinate to unscaled object space.
|
||||
Vec3d pos3d = _mouse_to_3d(pos);
|
||||
#endif // !ENABLE_GIZMOS_ON_TOP
|
||||
|
||||
// Only accept the initial position, if it is inside the volume bounding box.
|
||||
BoundingBoxf3 volume_bbox = m_volumes.volumes[m_hover_volume_id]->transformed_bounding_box();
|
||||
volume_bbox.offset(1.0);
|
||||
#if ENABLE_GIZMOS_ON_TOP
|
||||
if (volume_bbox.contains(m_mouse.scene_position))
|
||||
#else
|
||||
if (volume_bbox.contains(pos3d))
|
||||
#endif // ENABLE_GIZMOS_ON_TOP
|
||||
{
|
||||
// The dragging operation is initiated.
|
||||
m_mouse.drag.move_volume_idx = m_hover_volume_id;
|
||||
m_selection.start_dragging();
|
||||
#if ENABLE_GIZMOS_ON_TOP
|
||||
m_mouse.drag.start_position_3D = m_mouse.scene_position;
|
||||
#else
|
||||
m_mouse.drag.start_position_3D = pos3d;
|
||||
#endif // ENABLE_GIZMOS_ON_TOP
|
||||
}
|
||||
}
|
||||
else if (evt.RightDown())
|
||||
|
@ -337,6 +337,9 @@ class GLCanvas3D
|
||||
|
||||
bool dragging;
|
||||
Vec2d position;
|
||||
#if ENABLE_GIZMOS_ON_TOP
|
||||
Vec3d scene_position;
|
||||
#endif // ENABLE_GIZMOS_ON_TOP
|
||||
Drag drag;
|
||||
#if ENABLE_GIZMOS_RESET
|
||||
bool ignore_up_event;
|
||||
@ -559,6 +562,9 @@ public:
|
||||
void _render_bounding_box(const BoundingBoxf3& box, float* color) const;
|
||||
void _synchronize_unselected_instances();
|
||||
void _synchronize_unselected_volumes();
|
||||
#if ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
void _ensure_on_bed();
|
||||
#endif // ENABLE_ENSURE_ON_BED_WHILE_SCALING
|
||||
};
|
||||
|
||||
private:
|
||||
|
@ -5,6 +5,7 @@
|
||||
#include "GUI_App.hpp"
|
||||
|
||||
#include "../../libslic3r/Utils.hpp"
|
||||
#include "PresetBundle.hpp"
|
||||
|
||||
#include <Eigen/Dense>
|
||||
#include "../../libslic3r/Geometry.hpp"
|
||||
@ -1759,6 +1760,10 @@ void GLGizmoSlaSupports::render_tooltip_texture() const {
|
||||
::glEnable(GL_DEPTH_TEST);
|
||||
}
|
||||
|
||||
bool GLGizmoSlaSupports::on_is_activable(const GLCanvas3D::Selection& selection) const
|
||||
{
|
||||
return (wxGetApp().preset_bundle->printers.get_edited_preset().printer_technology() == ptSLA);
|
||||
}
|
||||
|
||||
std::string GLGizmoSlaSupports::on_get_name() const
|
||||
{
|
||||
|
@ -447,6 +447,7 @@ protected:
|
||||
}
|
||||
|
||||
std::string on_get_name() const override;
|
||||
bool on_is_activable(const GLCanvas3D::Selection& selection) const override;
|
||||
};
|
||||
|
||||
} // namespace GUI
|
||||
|
@ -115,6 +115,16 @@ bool GUI_App::OnInit()
|
||||
update_mode();
|
||||
SetTopWindow(mainframe);
|
||||
|
||||
CallAfter([this]() {
|
||||
// temporary workaround for the correct behavior of the Scrolled sidebar panel
|
||||
auto& panel = sidebar();
|
||||
if (panel.obj_list()->GetMinHeight() > 200) {
|
||||
wxWindowUpdateLocker noUpdates_sidebar(&panel);
|
||||
panel.obj_list()->SetMinSize(wxSize(-1, 200));
|
||||
panel.Layout();
|
||||
}
|
||||
});
|
||||
|
||||
// This makes CallAfter() work
|
||||
Bind(wxEVT_IDLE, [this](wxIdleEvent& event)
|
||||
{
|
||||
@ -294,20 +304,32 @@ void GUI_App::update_ui_from_settings()
|
||||
mainframe->update_ui_from_settings();
|
||||
}
|
||||
|
||||
|
||||
void GUI_App::open_model(wxWindow *parent, wxArrayString& input_files)
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void GUI_App::load_project(wxWindow *parent, wxString& input_file)
|
||||
{
|
||||
auto dialog = new wxFileDialog(parent ? parent : GetTopWindow(),
|
||||
input_file.Clear();
|
||||
wxFileDialog dialog(parent ? parent : GetTopWindow(),
|
||||
_(L("Choose one file (3MF):")),
|
||||
app_config->get_last_dir(), "",
|
||||
file_wildcards[FT_3MF], wxFD_OPEN | wxFD_FILE_MUST_EXIST);
|
||||
|
||||
if (dialog.ShowModal() == wxID_OK)
|
||||
input_file = dialog.GetPath();
|
||||
}
|
||||
|
||||
void GUI_App::import_model(wxWindow *parent, wxArrayString& input_files)
|
||||
#else
|
||||
void GUI_App::open_model(wxWindow *parent, wxArrayString& input_files)
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
{
|
||||
input_files.Clear();
|
||||
wxFileDialog dialog(parent ? parent : GetTopWindow(),
|
||||
_(L("Choose one or more files (STL/OBJ/AMF/3MF/PRUSA):")),
|
||||
app_config->get_last_dir(), "",
|
||||
file_wildcards[FT_MODEL], wxFD_OPEN | wxFD_MULTIPLE | wxFD_FILE_MUST_EXIST);
|
||||
if (dialog->ShowModal() != wxID_OK) {
|
||||
dialog->Destroy();
|
||||
return;
|
||||
}
|
||||
|
||||
dialog->GetPaths(input_files);
|
||||
dialog->Destroy();
|
||||
if (dialog.ShowModal() == wxID_OK)
|
||||
dialog.GetPaths(input_files);
|
||||
}
|
||||
|
||||
void GUI_App::CallAfter(std::function<void()> cb)
|
||||
|
@ -102,7 +102,12 @@ public:
|
||||
|
||||
void recreate_GUI();
|
||||
void system_info();
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void load_project(wxWindow *parent, wxString& input_file);
|
||||
void import_model(wxWindow *parent, wxArrayString& input_files);
|
||||
#else
|
||||
void open_model(wxWindow *parent, wxArrayString& input_files);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
static bool catch_error(std::function<void()> cb,
|
||||
// wxMessageDialog* message_dialog,
|
||||
const std::string& err);
|
||||
|
@ -83,7 +83,10 @@ ObjectList::~ObjectList()
|
||||
|
||||
void ObjectList::create_objects_ctrl()
|
||||
{
|
||||
SetMinSize(wxSize(-1, 150)); // TODO - Set correct height according to the opened/closed objects
|
||||
// temporary workaround for the correct behavior of the Scrolled sidebar panel:
|
||||
// 1. set a height of the list to some big value
|
||||
// 2. change it to the normal min value (200) after first whole App updating/layouting
|
||||
SetMinSize(wxSize(-1, 1500)); // #ys_FIXME
|
||||
|
||||
m_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
m_sizer->Add(this, 1, wxGROW | wxLEFT, 20);
|
||||
@ -724,7 +727,11 @@ void ObjectList::load_part( ModelObject* model_object,
|
||||
|
||||
m_parts_changed = false;
|
||||
wxArrayString input_files;
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxGetApp().import_model(parent, input_files);
|
||||
#else
|
||||
wxGetApp().open_model(parent, input_files);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
for (int i = 0; i < input_files.size(); ++i) {
|
||||
std::string input_file = input_files.Item(i).ToStdString();
|
||||
|
||||
|
@ -23,11 +23,12 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
||||
m_og->set_process_enter(); // We need to update new values only after press ENTER
|
||||
|
||||
m_og->m_on_change = [this](t_config_option_key opt_key, boost::any value) {
|
||||
std::vector<std::string> axes{ "_x", "_y", "_z" };
|
||||
|
||||
if (opt_key == "scale_unit") {
|
||||
const wxString& selection = boost::any_cast<wxString>(value);
|
||||
std::vector<std::string> axes{ "x", "y", "z" };
|
||||
for (auto axis : axes) {
|
||||
std::string key = "scale_" + axis;
|
||||
std::string key = "scale" + axis;
|
||||
m_og->set_side_text(key, selection);
|
||||
}
|
||||
|
||||
@ -39,13 +40,17 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
||||
std::string param;
|
||||
std::copy(opt_key.begin(), opt_key.end() - 2, std::back_inserter(param));
|
||||
|
||||
if (param == "position") {
|
||||
Vec3d displacement;
|
||||
displacement(0) = boost::any_cast<double>(m_og->get_value("position_x"));
|
||||
displacement(1) = boost::any_cast<double>(m_og->get_value("position_y"));
|
||||
displacement(2) = boost::any_cast<double>(m_og->get_value("position_z"));
|
||||
change_position_value(displacement);
|
||||
}
|
||||
size_t i = 0;
|
||||
Vec3d new_value;
|
||||
for (auto axis : axes)
|
||||
new_value(i++) = boost::any_cast<double>(m_og->get_value(param+axis));
|
||||
|
||||
if (param == "position")
|
||||
change_position_value(new_value);
|
||||
else if (param == "rotation")
|
||||
change_rotation_value(new_value);
|
||||
else if (param == "scale")
|
||||
change_scale_value(new_value);
|
||||
};
|
||||
|
||||
ConfigOptionDef def;
|
||||
@ -132,7 +137,7 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
||||
m_og->append_line(add_og_to_object_settings(L("Rotation"), "°"));
|
||||
m_og->append_line(add_og_to_object_settings(L("Scale"), "mm"));
|
||||
|
||||
|
||||
/* Unused parameter at this time
|
||||
def.label = L("Place on bed");
|
||||
def.type = coBool;
|
||||
def.tooltip = L("Automatic placing of models on printing bed in Y axis");
|
||||
@ -140,6 +145,7 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
||||
def.sidetext = "";
|
||||
def.default_value = new ConfigOptionBool{ false };
|
||||
m_og->append_single_option_line(Option(def, "place_on_bed"));
|
||||
*/
|
||||
}
|
||||
|
||||
void ObjectManipulation::Show(const bool show)
|
||||
@ -241,6 +247,8 @@ void ObjectManipulation::update_settings_value(const GLCanvas3D::Selection& sele
|
||||
}
|
||||
else
|
||||
reset_settings_value();
|
||||
|
||||
m_og->get_field("scale_unit")->disable();// temporary decision
|
||||
}
|
||||
|
||||
void ObjectManipulation::reset_settings_value()
|
||||
@ -317,9 +325,9 @@ void ObjectManipulation::update_scale_values()
|
||||
m_og->set_value("scale_z", double_to_string(instance->get_scaling_factor(Z) * 100, 2));
|
||||
}
|
||||
else {
|
||||
m_og->set_value("scale_x", double_to_string(instance->get_scaling_factor(X) * size(0) + 0.5, 2));
|
||||
m_og->set_value("scale_y", double_to_string(instance->get_scaling_factor(Y) * size(1) + 0.5, 2));
|
||||
m_og->set_value("scale_z", double_to_string(instance->get_scaling_factor(Z) * size(2) + 0.5, 2));
|
||||
m_og->set_value("scale_x", double_to_string(size(0), 2));
|
||||
m_og->set_value("scale_y", double_to_string(size(1), 2));
|
||||
m_og->set_value("scale_z", double_to_string(size(2), 2));
|
||||
}
|
||||
}
|
||||
|
||||
@ -347,8 +355,10 @@ void ObjectManipulation::update_scale_value(const Vec3d& scaling_factor)
|
||||
// to be able to update the values as size
|
||||
// we need to store somewhere the original size
|
||||
// or have it passed as parameter
|
||||
if (!m_is_percent_scale)
|
||||
if (!m_is_percent_scale) {
|
||||
m_is_percent_scale = true;
|
||||
m_og->set_value("scale_unit", _("%"));
|
||||
}
|
||||
|
||||
auto scale = scaling_factor * 100.0;
|
||||
m_og->set_value("scale_x", double_to_string(scale(0), 2));
|
||||
@ -399,11 +409,40 @@ void ObjectManipulation::change_position_value(const Vec3d& position)
|
||||
cache_position = position;
|
||||
}
|
||||
|
||||
|
||||
|
||||
void ObjectManipulation::print_cashe_value(const std::string& label, const Vec3d& value)
|
||||
void ObjectManipulation::change_rotation_value(const Vec3d& rotation)
|
||||
{
|
||||
std::cout << label << " => " << " X:" << value(0) << " Y:" << value(1) << " Z:" << value(2) << std::endl;
|
||||
Vec3d rad_rotation;
|
||||
for (size_t i = 0; i < 3; ++i)
|
||||
rad_rotation(i) = Geometry::deg2rad(rotation(i));
|
||||
auto canvas = _3DScene::get_canvas(wxGetApp().canvas3D());
|
||||
canvas->get_selection().start_dragging();
|
||||
canvas->get_selection().rotate(rad_rotation);
|
||||
canvas->_on_rotate();
|
||||
}
|
||||
|
||||
void ObjectManipulation::change_scale_value(const Vec3d& scale)
|
||||
{
|
||||
Vec3d scaling_factor;
|
||||
if (m_is_percent_scale)
|
||||
scaling_factor = scale*0.01;
|
||||
else {
|
||||
int selection = ol_selection();
|
||||
ModelObjectPtrs& objects = *wxGetApp().model_objects();
|
||||
|
||||
auto size = objects[selection]->instance_bounding_box(0).size();
|
||||
for (size_t i = 0; i < 3; ++i)
|
||||
scaling_factor(i) = scale(i) / size(i);
|
||||
}
|
||||
|
||||
auto canvas = _3DScene::get_canvas(wxGetApp().canvas3D());
|
||||
canvas->get_selection().start_dragging();
|
||||
canvas->get_selection().scale(scaling_factor);
|
||||
canvas->_on_scale();
|
||||
}
|
||||
|
||||
void ObjectManipulation::print_cashe_value(const std::string& label, const Vec3d& v)
|
||||
{
|
||||
std::cout << label << " => " << " X:" << v(0) << " Y:" << v(1) << " Z:" << v(2) << std::endl;
|
||||
}
|
||||
|
||||
} //namespace GUI
|
||||
|
@ -18,8 +18,6 @@ class ObjectManipulation : public OG_Settings
|
||||
bool m_is_uniform_scale = false; // It indicates if scale is uniform
|
||||
|
||||
Vec3d cache_position { 0., 0., 0. };
|
||||
Vec3d cache_rotation { 0., 0., 0. };
|
||||
Vec3d cache_scale { 0., 0., 0. };
|
||||
|
||||
public:
|
||||
ObjectManipulation(wxWindow* parent);
|
||||
@ -55,6 +53,8 @@ public:
|
||||
|
||||
// change values
|
||||
void change_position_value(const Vec3d& position);
|
||||
void change_rotation_value(const Vec3d& rotation);
|
||||
void change_scale_value(const Vec3d& scale);
|
||||
|
||||
|
||||
private:
|
||||
|
@ -217,11 +217,85 @@ void MainFrame::add_created_tab(Tab* panel)
|
||||
m_tabpanel->AddPage(panel, panel->title());
|
||||
}
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
bool MainFrame::can_save() const
|
||||
{
|
||||
return (m_plater != nullptr) ? !m_plater->model().objects.empty() : false;
|
||||
}
|
||||
|
||||
bool MainFrame::can_export_model() const
|
||||
{
|
||||
return (m_plater != nullptr) ? !m_plater->model().objects.empty() : false;
|
||||
}
|
||||
|
||||
bool MainFrame::can_export_gcode() const
|
||||
{
|
||||
if (m_plater == nullptr)
|
||||
return false;
|
||||
|
||||
if (m_plater->model().objects.empty())
|
||||
return false;
|
||||
|
||||
if (m_plater->is_export_gcode_scheduled())
|
||||
return false;
|
||||
|
||||
// TODO:: add other filters
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool MainFrame::can_change_view() const
|
||||
{
|
||||
int page_id = m_tabpanel->GetSelection();
|
||||
return (page_id != wxNOT_FOUND) ? m_tabpanel->GetPageText((size_t)page_id).Lower() == "plater" : false;
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
void MainFrame::init_menubar()
|
||||
{
|
||||
// File menu
|
||||
wxMenu* fileMenu = new wxMenu;
|
||||
{
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxMenuItem* item_open = append_menu_item(fileMenu, wxID_ANY, _(L("Open…\tCtrl+O")), _(L("Open a project file")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->load_project(); }, "brick_add.png");
|
||||
wxMenuItem* item_save = append_menu_item(fileMenu, wxID_ANY, _(L("Save\tCtrl+S")), _(L("Save current project file")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->export_3mf(m_plater->get_project_filename().wx_str()); }, "disk.png");
|
||||
wxMenuItem* item_save_as = append_menu_item(fileMenu, wxID_ANY, _(L("Save as…\tCtrl+Alt+S")), _(L("Save current project file as")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->export_3mf(); }, "disk.png");
|
||||
|
||||
fileMenu->AppendSeparator();
|
||||
|
||||
wxMenu* import_menu = new wxMenu();
|
||||
wxMenuItem* item_import_model = append_menu_item(import_menu, wxID_ANY, _(L("Import STL/OBJ/AMF/3MF…\tCtrl+I")), _(L("Load a model")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->add_model(); }, "brick_add.png");
|
||||
import_menu->AppendSeparator();
|
||||
append_menu_item(import_menu, wxID_ANY, _(L("Import Config…\tCtrl+L")), _(L("Load exported configuration file")),
|
||||
[this](wxCommandEvent&) { load_config_file(); }, "plugin_add.png");
|
||||
append_menu_item(import_menu, wxID_ANY, _(L("Import Config from project…\tCtrl+Alt+L")), _(L("Load configuration from project file")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->extract_config_from_project(); }, "plugin_add.png");
|
||||
import_menu->AppendSeparator();
|
||||
append_menu_item(import_menu, wxID_ANY, _(L("Import Config Bundle…")), _(L("Load presets from a bundle")),
|
||||
[this](wxCommandEvent&) { load_configbundle(); }, "lorry_add.png");
|
||||
append_submenu(fileMenu, import_menu, wxID_ANY, _(L("Import")), _(L("")));
|
||||
|
||||
wxMenu* export_menu = new wxMenu();
|
||||
wxMenuItem* item_export_gcode = append_menu_item(export_menu, wxID_ANY, _(L("Export G-code…")), _(L("Export current plate as G-code")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->export_gcode(); }, "cog_go.png");
|
||||
export_menu->AppendSeparator();
|
||||
wxMenuItem* item_export_stl = append_menu_item(export_menu, wxID_ANY, _(L("Export plate as STL…")), _(L("Export current plate as STL")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->export_stl(); }, "brick_go.png");
|
||||
wxMenuItem* item_export_amf = append_menu_item(export_menu, wxID_ANY, _(L("Export plate as AMF…")), _(L("Export current plate as AMF")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->export_amf(); }, "brick_go.png");
|
||||
export_menu->AppendSeparator();
|
||||
append_menu_item(export_menu, wxID_ANY, _(L("Export Config…\tCtrl+E")), _(L("Export current configuration to file")),
|
||||
[this](wxCommandEvent&) { export_config(); }, "plugin_go.png");
|
||||
append_menu_item(export_menu, wxID_ANY, _(L("Export Config Bundle…")), _(L("Export all presets to file")),
|
||||
[this](wxCommandEvent&) { export_configbundle(); }, "lorry_go.png");
|
||||
append_submenu(fileMenu, export_menu, wxID_ANY, _(L("Export")), _(L("")));
|
||||
|
||||
fileMenu->AppendSeparator();
|
||||
#else
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Open STL/OBJ/AMF/3MF…\tCtrl+O")), _(L("Open a model")),
|
||||
[this](wxCommandEvent&) { if (m_plater) m_plater->add(); }, "brick_add.png");
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("&Load Config…\tCtrl+L")), _(L("Load exported configuration file")),
|
||||
@ -233,25 +307,27 @@ void MainFrame::init_menubar()
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("&Export Config Bundle…")), _(L("Export all presets to file")),
|
||||
[this](wxCommandEvent&) { export_configbundle(); }, "lorry_go.png");
|
||||
fileMenu->AppendSeparator();
|
||||
wxMenuItem* repeat = nullptr;
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Q&uick Slice…\tCtrl+U")), _(L("Slice a file into a G-code")),
|
||||
[this, repeat](wxCommandEvent&) {
|
||||
wxTheApp->CallAfter([this, repeat]() {
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
m_menu_item_repeat = nullptr;
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Q&uick Slice…\tCtrl+U")), _(L("Slice a file into a G-code")),
|
||||
[this](wxCommandEvent&) {
|
||||
wxTheApp->CallAfter([this]() {
|
||||
quick_slice();
|
||||
repeat->Enable(is_last_input_file());
|
||||
}); }, "cog_go.png");
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Quick Slice and Save &As…\tCtrl+Alt+U")), _(L("Slice a file into a G-code, save as")),
|
||||
[this, repeat](wxCommandEvent&) {
|
||||
wxTheApp->CallAfter([this, repeat]() {
|
||||
m_menu_item_repeat->Enable(is_last_input_file());
|
||||
}); }, "cog_go.png");
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Quick Slice and Save &As…\tCtrl+Alt+U")), _(L("Slice a file into a G-code, save as")),
|
||||
[this](wxCommandEvent&) {
|
||||
wxTheApp->CallAfter([this]() {
|
||||
quick_slice(qsSaveAs);
|
||||
repeat->Enable(is_last_input_file());
|
||||
}); }, "cog_go.png");
|
||||
repeat = append_menu_item(fileMenu, wxID_ANY, _(L("&Repeat Last Quick Slice\tCtrl+Shift+U")), _(L("Repeat last quick slice")),
|
||||
m_menu_item_repeat->Enable(is_last_input_file());
|
||||
}); }, "cog_go.png");
|
||||
m_menu_item_repeat = append_menu_item(fileMenu, wxID_ANY, _(L("&Repeat Last Quick Slice\tCtrl+Shift+U")), _(L("Repeat last quick slice")),
|
||||
[this](wxCommandEvent&) {
|
||||
wxTheApp->CallAfter([this]() {
|
||||
quick_slice(qsReslice);
|
||||
}); }, "cog_go.png");
|
||||
repeat->Enable(0);
|
||||
m_menu_item_repeat->Enable(false);
|
||||
fileMenu->AppendSeparator();
|
||||
append_menu_item(fileMenu, wxID_ANY, _(L("Slice to SV&G…\tCtrl+G")), _(L("Slice file to a multi-layer SVG")),
|
||||
[this](wxCommandEvent&) { quick_slice(qsSaveAs | qsExportSVG); }, "shape_handles.png");
|
||||
@ -263,8 +339,19 @@ void MainFrame::init_menubar()
|
||||
fileMenu->AppendSeparator();
|
||||
append_menu_item(fileMenu, wxID_EXIT, _(L("&Quit")), _(L("Quit Slic3r")),
|
||||
[this](wxCommandEvent&) { Close(false); } );
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(m_plater != nullptr); }, item_open->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable((m_plater != nullptr) && can_save()); }, item_save->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable((m_plater != nullptr) && can_save()); }, item_save_as->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(m_plater != nullptr); }, item_import_model->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable((m_plater != nullptr) && can_export_gcode()); }, item_export_gcode->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable((m_plater != nullptr) && can_export_model()); }, item_export_stl->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable((m_plater != nullptr) && can_export_model()); }, item_export_amf->GetId());
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
|
||||
#if !ENABLE_NEW_MENU_LAYOUT
|
||||
// Plater menu
|
||||
if (m_plater) {
|
||||
m_plater_menu = new wxMenu();
|
||||
@ -277,6 +364,7 @@ void MainFrame::init_menubar()
|
||||
append_menu_item(m_plater_menu, wxID_ANY, _(L("Export plate as 3MF...")), _(L("Export current plate as 3MF")),
|
||||
[this](wxCommandEvent&) { m_plater->export_3mf(); }, "brick_go.png");
|
||||
}
|
||||
#endif // !ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
// Window menu
|
||||
auto windowMenu = new wxMenu();
|
||||
@ -299,6 +387,31 @@ void MainFrame::init_menubar()
|
||||
}
|
||||
|
||||
// View menu
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxMenu* viewMenu = nullptr;
|
||||
if (m_plater) {
|
||||
viewMenu = new wxMenu();
|
||||
// \xA0 is a non-breaing space. It is entered here to spoil the automatic accelerators,
|
||||
// as the simple numeric accelerators spoil all numeric data entry.
|
||||
// The camera control accelerators are captured by GLCanvas3D::on_char().
|
||||
wxMenuItem* item_iso = append_menu_item(viewMenu, wxID_ANY, _(L("Iso")) + "\t\xA0" + "0", _(L("Iso View")), [this](wxCommandEvent&) { select_view("iso"); });
|
||||
viewMenu->AppendSeparator();
|
||||
wxMenuItem* item_top = append_menu_item(viewMenu, wxID_ANY, _(L("Top")) + "\t\xA0" + "1", _(L("Top View")), [this](wxCommandEvent&) { select_view("top"); });
|
||||
wxMenuItem* item_bottom = append_menu_item(viewMenu, wxID_ANY, _(L("Bottom")) + "\t\xA0" + "2", _(L("Bottom View")), [this](wxCommandEvent&) { select_view("bottom"); });
|
||||
wxMenuItem* item_front = append_menu_item(viewMenu, wxID_ANY, _(L("Front")) + "\t\xA0" + "3", _(L("Front View")), [this](wxCommandEvent&) { select_view("front"); });
|
||||
wxMenuItem* item_rear = append_menu_item(viewMenu, wxID_ANY, _(L("Rear")) + "\t\xA0" + "4", _(L("Rear View")), [this](wxCommandEvent&) { select_view("rear"); });
|
||||
wxMenuItem* item_left = append_menu_item(viewMenu, wxID_ANY, _(L("Left")) + "\t\xA0" + "5", _(L("Left View")), [this](wxCommandEvent&) { select_view("left"); });
|
||||
wxMenuItem* item_right = append_menu_item(viewMenu, wxID_ANY, _(L("Right")) + "\t\xA0" + "6", _(L("Right View")), [this](wxCommandEvent&) { select_view("right"); });
|
||||
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_iso->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_top->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_bottom->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_front->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_rear->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_left->GetId());
|
||||
Bind(wxEVT_UPDATE_UI, [this](wxUpdateUIEvent& evt) { evt.Enable(can_change_view()); }, item_right->GetId());
|
||||
}
|
||||
#else
|
||||
if (m_plater) {
|
||||
m_viewMenu = new wxMenu();
|
||||
// \xA0 is a non-breaing space. It is entered here to spoil the automatic accelerators,
|
||||
@ -313,6 +426,7 @@ void MainFrame::init_menubar()
|
||||
append_menu_item(m_viewMenu, wxID_ANY, _(L("Left")) + "\t\xA0" + "5", _(L("Left View")), [this](wxCommandEvent&) { select_view("left"); });
|
||||
append_menu_item(m_viewMenu, wxID_ANY, _(L("Right")) + "\t\xA0" + "6", _(L("Right View")), [this](wxCommandEvent&) { select_view("right"); });
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
// Help menu
|
||||
auto helpMenu = new wxMenu();
|
||||
@ -346,9 +460,15 @@ void MainFrame::init_menubar()
|
||||
{
|
||||
auto menubar = new wxMenuBar();
|
||||
menubar->Append(fileMenu, L("&File"));
|
||||
if (m_plater_menu) menubar->Append(m_plater_menu, L("&Plater")) ;
|
||||
#if !ENABLE_NEW_MENU_LAYOUT
|
||||
if (m_plater_menu) menubar->Append(m_plater_menu, L("&Plater"));
|
||||
#endif // !ENABLE_NEW_MENU_LAYOUT
|
||||
menubar->Append(windowMenu, L("&Window"));
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (viewMenu) menubar->Append(viewMenu, L("&View"));
|
||||
#else
|
||||
if (m_viewMenu) menubar->Append(m_viewMenu, L("&View"));
|
||||
#endif // !ENABLE_NEW_MENU_LAYOUT
|
||||
// Add additional menus from C++
|
||||
wxGetApp().add_config_menu(menubar);
|
||||
menubar->Append(helpMenu, L("&Help"));
|
||||
@ -677,7 +797,7 @@ void MainFrame::on_presets_changed(SimpleEvent &event)
|
||||
// Update preset combo boxes(Print settings, Filament, Material, Printer) from their respective tabs.
|
||||
auto presets = tab->get_presets();
|
||||
if (m_plater != nullptr && presets != nullptr) {
|
||||
auto reload_dependent_tabs = tab->get_dependent_tabs();
|
||||
// auto reload_dependent_tabs = tab->get_dependent_tabs();
|
||||
|
||||
// FIXME: The preset type really should be a property of Tab instead
|
||||
Slic3r::Preset::Type preset_type = tab->type();
|
||||
@ -685,7 +805,7 @@ void MainFrame::on_presets_changed(SimpleEvent &event)
|
||||
wxASSERT(false);
|
||||
return;
|
||||
}
|
||||
|
||||
/*
|
||||
m_plater->sidebar().update_presets(preset_type);
|
||||
|
||||
if (preset_type == Slic3r::Preset::TYPE_PRINTER) {
|
||||
@ -703,7 +823,9 @@ void MainFrame::on_presets_changed(SimpleEvent &event)
|
||||
cur_tab->load_current_preset();
|
||||
}
|
||||
}
|
||||
*/
|
||||
m_plater->on_config_change(*tab->get_config());
|
||||
m_plater->sidebar().update_presets(preset_type);
|
||||
}
|
||||
}
|
||||
|
||||
@ -736,9 +858,13 @@ void MainFrame::update_ui_from_settings()
|
||||
{
|
||||
m_menu_item_reslice_now->Enable(wxGetApp().app_config->get("background_processing") == "1");
|
||||
// if (m_plater) m_plater->update_ui_from_settings();
|
||||
/*
|
||||
std::vector<std::string> tab_names = { "print", "filament", "printer" };
|
||||
for (auto tab_name: tab_names)
|
||||
m_options_tabs[tab_name]->update_ui_from_settings();
|
||||
*/
|
||||
for (auto tab: wxGetApp().tabs_list)
|
||||
tab->update_ui_from_settings();
|
||||
}
|
||||
|
||||
|
||||
|
@ -55,9 +55,12 @@ class MainFrame : public wxFrame
|
||||
|
||||
std::map<std::string, Tab*> m_options_tabs;
|
||||
|
||||
wxMenuItem* m_menu_item_repeat { nullptr };
|
||||
wxMenuItem* m_menu_item_reslice_now { nullptr };
|
||||
wxMenu* m_plater_menu { nullptr };
|
||||
#if !ENABLE_NEW_MENU_LAYOUT
|
||||
wxMenu* m_plater_menu{ nullptr };
|
||||
wxMenu* m_viewMenu{ nullptr };
|
||||
#endif // !ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
std::string get_base_name(const wxString full_name) const ;
|
||||
std::string get_dir_name(const wxString full_name) const ;
|
||||
@ -66,6 +69,13 @@ class MainFrame : public wxFrame
|
||||
void on_value_changed(wxCommandEvent&);
|
||||
Tab* get_tab(const std::string& name);
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
bool can_save() const;
|
||||
bool can_export_model() const;
|
||||
bool can_export_gcode() const;
|
||||
bool can_change_view() const;
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
public:
|
||||
MainFrame() {}
|
||||
MainFrame(const bool no_plater, const bool loaded);
|
||||
|
@ -405,7 +405,7 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
||||
void FreqChangedParams::Show(const bool show)
|
||||
{
|
||||
bool is_wdb_shown = m_wiping_dialog_button->IsShown();
|
||||
m_og->sizer->Show(show);
|
||||
m_og->Show(show);
|
||||
|
||||
// correct showing of the FreqChangedParams sizer when m_wiping_dialog_button is hidden
|
||||
if (show && !is_wdb_shown)
|
||||
@ -449,24 +449,20 @@ void Sidebar::priv::show_preset_comboboxes()
|
||||
{
|
||||
const bool showSLA = plater->printer_technology() == ptSLA;
|
||||
|
||||
wxWindowUpdateLocker noUpdates_scrolled(scrolled);
|
||||
// scrolled->Freeze();
|
||||
wxWindowUpdateLocker noUpdates_scrolled(scrolled->GetParent());
|
||||
|
||||
for (size_t i = 0; i < 4; ++i) {
|
||||
if (sizer_presets->IsShown(i) == showSLA)
|
||||
sizer_presets->Show(i, !showSLA);
|
||||
}
|
||||
for (size_t i = 0; i < 4; ++i)
|
||||
sizer_presets->Show(i, !showSLA);
|
||||
|
||||
for (size_t i = 4; i < 6; ++i) {
|
||||
if (sizer_presets->IsShown(i) != showSLA)
|
||||
sizer_presets->Show(i, showSLA);
|
||||
}
|
||||
|
||||
if (frequently_changed_parameters->IsShown() == showSLA)
|
||||
frequently_changed_parameters->Show(!showSLA);
|
||||
frequently_changed_parameters->Show(!showSLA);
|
||||
|
||||
scrolled->Layout();
|
||||
// scrolled->Thaw();
|
||||
scrolled->GetParent()->Layout();
|
||||
scrolled->Refresh();
|
||||
}
|
||||
|
||||
|
||||
@ -710,7 +706,7 @@ void Sidebar::show_info_sizer()
|
||||
|
||||
const ModelInstance* model_instance = !model_object->instances.empty() ? model_object->instances.front() : nullptr;
|
||||
|
||||
auto size = model_object->instance_bounding_box(0).size();
|
||||
auto size = model_object->bounding_box().size();
|
||||
p->object_info->info_size->SetLabel(wxString::Format("%.2f x %.2f x %.2f",size(0), size(1), size(2)));
|
||||
p->object_info->info_materials->SetLabel(wxString::Format("%d", static_cast<int>(model_object->materials_count())));
|
||||
|
||||
@ -776,6 +772,7 @@ void Sidebar::show_sliced_info_sizer(const bool show)
|
||||
}
|
||||
|
||||
Layout();
|
||||
p->scrolled->Refresh();
|
||||
}
|
||||
|
||||
void Sidebar::show_buttons(const bool show)
|
||||
@ -886,6 +883,11 @@ struct Plater::priv
|
||||
Sidebar *sidebar;
|
||||
wxGLCanvas *canvas3D; // TODO: Use GLCanvas3D when we can
|
||||
Preview *preview;
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxString project_filename;
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
BackgroundSlicingProcess background_process;
|
||||
std::atomic<bool> arranging;
|
||||
|
||||
@ -904,7 +906,11 @@ struct Plater::priv
|
||||
std::string get_config(const std::string &key) const;
|
||||
BoundingBoxf bed_shape_bb() const;
|
||||
BoundingBox scaled_bed_shape_bb() const;
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
std::vector<size_t> load_files(const std::vector<fs::path>& input_files, bool load_model, bool load_config);
|
||||
#else
|
||||
std::vector<size_t> load_files(const std::vector<fs::path> &input_files);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
std::vector<size_t> load_model_objects(const ModelObjectPtrs &model_objects);
|
||||
std::unique_ptr<CheckboxFileDialog> get_export_file(GUI::FileType file_type);
|
||||
|
||||
@ -995,6 +1001,9 @@ Plater::priv::priv(Plater *q, MainFrame *main_frame) :
|
||||
notebook(new wxNotebook(q, wxID_ANY, wxDefaultPosition, wxDefaultSize, wxNB_BOTTOM)),
|
||||
sidebar(new Sidebar(q)),
|
||||
canvas3D(GLCanvas3DManager::create_wxglcanvas(notebook))
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
, project_filename(wxEmptyString)
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
{
|
||||
arranging.store(false);
|
||||
background_process.set_fff_print(&print);
|
||||
@ -1168,7 +1177,11 @@ BoundingBox Plater::priv::scaled_bed_shape_bb() const
|
||||
return bed_shape.bounding_box();
|
||||
}
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path>& input_files, bool load_model, bool load_config)
|
||||
#else
|
||||
std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path> &input_files)
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
{
|
||||
if (input_files.empty()) { return std::vector<size_t>(); }
|
||||
|
||||
@ -1188,7 +1201,11 @@ std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path> &input_
|
||||
wxProgressDialog dlg(loading, loading);
|
||||
dlg.Pulse();
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
auto *new_model = (!load_model || one_by_one) ? nullptr : new Slic3r::Model();
|
||||
#else
|
||||
auto *new_model = one_by_one ? nullptr : new Slic3r::Model();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
std::vector<size_t> obj_idxs;
|
||||
|
||||
for (size_t i = 0; i < input_files.size(); i++) {
|
||||
@ -1207,23 +1224,35 @@ std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path> &input_
|
||||
{
|
||||
DynamicPrintConfig config_loaded;
|
||||
model = Slic3r::Model::read_from_archive(path.string(), &config_loaded, false);
|
||||
if (! config_loaded.empty()) {
|
||||
// Based on the printer technology field found in the loaded config, select the base for the config,
|
||||
PrinterTechnology printer_technology = Preset::printer_technology(config_loaded);
|
||||
config.apply(printer_technology == ptFFF ?
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (load_config && !config_loaded.empty()) {
|
||||
#else
|
||||
if (!config_loaded.empty()) {
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
// Based on the printer technology field found in the loaded config, select the base for the config,
|
||||
PrinterTechnology printer_technology = Preset::printer_technology(config_loaded);
|
||||
config.apply(printer_technology == ptFFF ?
|
||||
static_cast<const ConfigBase&>(FullPrintConfig::defaults()) :
|
||||
static_cast<const ConfigBase&>(SLAFullPrintConfig::defaults()));
|
||||
// and place the loaded config over the base.
|
||||
config += std::move(config_loaded);
|
||||
}
|
||||
}
|
||||
if (! config.empty()) {
|
||||
Preset::normalize(config);
|
||||
wxGetApp().preset_bundle->load_config_model(filename.string(), std::move(config));
|
||||
wxGetApp().load_current_presets();
|
||||
}
|
||||
wxGetApp().app_config->update_config_dir(path.parent_path().string());
|
||||
} else {
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (load_config)
|
||||
{
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
if (!config.empty()) {
|
||||
Preset::normalize(config);
|
||||
wxGetApp().preset_bundle->load_config_model(filename.string(), std::move(config));
|
||||
wxGetApp().load_current_presets();
|
||||
}
|
||||
wxGetApp().app_config->update_config_dir(path.parent_path().string());
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
else {
|
||||
model = Slic3r::Model::read_from_file(path.string(), nullptr, false);
|
||||
for (auto obj : model.objects)
|
||||
if (obj->name.empty())
|
||||
@ -1235,35 +1264,42 @@ std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path> &input_
|
||||
continue;
|
||||
}
|
||||
|
||||
// The model should now be initialized
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (load_model)
|
||||
{
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
// The model should now be initialized
|
||||
|
||||
if (model.looks_like_multipart_object()) {
|
||||
wxMessageDialog dlg(q, _(L(
|
||||
"This file contains several objects positioned at multiple heights. "
|
||||
"Instead of considering them as multiple objects, should I consider\n"
|
||||
"this file as a single object having multiple parts?\n"
|
||||
)), _(L("Multi-part object detected")), wxICON_WARNING | wxYES | wxNO);
|
||||
if (dlg.ShowModal() == wxID_YES) {
|
||||
model.convert_multipart_object(nozzle_dmrs->values.size());
|
||||
if (model.looks_like_multipart_object()) {
|
||||
wxMessageDialog dlg(q, _(L(
|
||||
"This file contains several objects positioned at multiple heights. "
|
||||
"Instead of considering them as multiple objects, should I consider\n"
|
||||
"this file as a single object having multiple parts?\n"
|
||||
)), _(L("Multi-part object detected")), wxICON_WARNING | wxYES | wxNO);
|
||||
if (dlg.ShowModal() == wxID_YES) {
|
||||
model.convert_multipart_object(nozzle_dmrs->values.size());
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (type_3mf) {
|
||||
for (ModelObject* model_object : model.objects) {
|
||||
model_object->center_around_origin();
|
||||
model_object->ensure_on_bed();
|
||||
if (type_3mf) {
|
||||
for (ModelObject* model_object : model.objects) {
|
||||
model_object->center_around_origin();
|
||||
model_object->ensure_on_bed();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (one_by_one) {
|
||||
auto loaded_idxs = load_model_objects(model.objects);
|
||||
obj_idxs.insert(obj_idxs.end(), loaded_idxs.begin(), loaded_idxs.end());
|
||||
} else {
|
||||
// This must be an .stl or .obj file, which may contain a maximum of one volume.
|
||||
for (const ModelObject* model_object : model.objects) {
|
||||
new_model->add_object(*model_object);
|
||||
if (one_by_one) {
|
||||
auto loaded_idxs = load_model_objects(model.objects);
|
||||
obj_idxs.insert(obj_idxs.end(), loaded_idxs.begin(), loaded_idxs.end());
|
||||
} else {
|
||||
// This must be an .stl or .obj file, which may contain a maximum of one volume.
|
||||
for (const ModelObject* model_object : model.objects) {
|
||||
new_model->add_object(*model_object);
|
||||
}
|
||||
}
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
|
||||
if (new_model != nullptr) {
|
||||
@ -1280,9 +1316,16 @@ std::vector<size_t> Plater::priv::load_files(const std::vector<fs::path> &input_
|
||||
obj_idxs.insert(obj_idxs.end(), loaded_idxs.begin(), loaded_idxs.end());
|
||||
}
|
||||
|
||||
wxGetApp().app_config->update_skein_dir(input_files[input_files.size() - 1].parent_path().string());
|
||||
// XXX: Plater.pm had @loaded_files, but didn't seem to fill them with the filenames...
|
||||
statusbar()->set_status_text(_(L("Loaded")));
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (load_model)
|
||||
{
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
wxGetApp().app_config->update_skein_dir(input_files[input_files.size() - 1].parent_path().string());
|
||||
// XXX: Plater.pm had @loaded_files, but didn't seem to fill them with the filenames...
|
||||
statusbar()->set_status_text(_(L("Loaded")));
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
return obj_idxs;
|
||||
}
|
||||
|
||||
@ -1390,7 +1433,7 @@ std::unique_ptr<CheckboxFileDialog> Plater::priv::get_export_file(GUI::FileType
|
||||
wxGetApp().preset_bundle->export_selections(print.placeholder_parser());
|
||||
|
||||
auto dlg = Slic3r::make_unique<CheckboxFileDialog>(q,
|
||||
_(L("Export print config")),
|
||||
((file_type == FT_AMF) || (file_type == FT_3MF)) ? _(L("Export print config")) : "",
|
||||
true,
|
||||
_(L("Save file as:")),
|
||||
output_file.parent_path().string(),
|
||||
@ -1478,6 +1521,10 @@ void Plater::priv::delete_object_from_model(size_t obj_idx)
|
||||
|
||||
void Plater::priv::reset()
|
||||
{
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
project_filename.Clear();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
// Prevent toolpaths preview from rendering while we modify the Print object
|
||||
preview->set_enabled(false);
|
||||
|
||||
@ -1875,21 +1922,13 @@ void Plater::priv::on_process_completed(wxCommandEvent &evt)
|
||||
case ptSLA:
|
||||
// Update the SLAPrint from the current Model, so that the reload_scene()
|
||||
// pulls the correct data.
|
||||
|
||||
// FIXME: SLAPrint::apply is not ready for this. At this stage it would
|
||||
// invalidate the previous result and the supports would not be available
|
||||
// for rendering.
|
||||
// if (this->update_background_process() & UPDATE_BACKGROUND_PROCESS_RESTART)
|
||||
// this->schedule_background_process();
|
||||
|
||||
{
|
||||
// for(SLAPrintObject * po: sla_print.objects()) {
|
||||
// TriangleMesh&& suppmesh = po->support_mesh();
|
||||
// if(suppmesh.facets_count() > 0) {
|
||||
// ModelObject* mo = model.add_object();
|
||||
// for(const SLAPrintObject::Instance& inst : po->instances() ) {
|
||||
// mo->add_instance(*(mo->instances[inst.instance_id.id]));
|
||||
// mo->add_volume(suppmesh);
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
}
|
||||
_3DScene::reload_scene(canvas3D, true);
|
||||
break;
|
||||
}
|
||||
@ -1914,7 +1953,11 @@ void Plater::priv::on_schedule_background_process(SimpleEvent&)
|
||||
void Plater::priv::on_action_add(SimpleEvent&)
|
||||
{
|
||||
if (q != nullptr)
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
q->add_model();
|
||||
#else
|
||||
q->add();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
|
||||
void Plater::priv::on_action_split_objects(SimpleEvent&)
|
||||
@ -2115,19 +2158,70 @@ Sidebar& Plater::sidebar() { return *p->sidebar; }
|
||||
Model& Plater::model() { return p->model; }
|
||||
Print& Plater::print() { return p->print; }
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void Plater::load_project()
|
||||
{
|
||||
wxString input_file;
|
||||
wxGetApp().load_project(this, input_file);
|
||||
|
||||
if (input_file.empty())
|
||||
return;
|
||||
|
||||
p->reset();
|
||||
p->project_filename = input_file;
|
||||
|
||||
std::vector<fs::path> input_paths;
|
||||
input_paths.push_back(input_file.wx_str());
|
||||
load_files(input_paths);
|
||||
}
|
||||
|
||||
void Plater::add_model()
|
||||
#else
|
||||
void Plater::add()
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
{
|
||||
wxArrayString input_files;
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxGetApp().import_model(this, input_files);
|
||||
#else
|
||||
wxGetApp().open_model(this, input_files);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (input_files.empty())
|
||||
return;
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
std::vector<fs::path> input_paths;
|
||||
for (const auto &file : input_files) {
|
||||
input_paths.push_back(file.wx_str());
|
||||
}
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
load_files(input_paths, true, false);
|
||||
#else
|
||||
load_files(input_paths);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
}
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void Plater::extract_config_from_project()
|
||||
{
|
||||
wxString input_file;
|
||||
wxGetApp().load_project(this, input_file);
|
||||
|
||||
if (input_file.empty())
|
||||
return;
|
||||
|
||||
std::vector<fs::path> input_paths;
|
||||
input_paths.push_back(input_file.wx_str());
|
||||
load_files(input_paths, false, true);
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void Plater::load_files(const std::vector<fs::path>& input_files, bool load_model, bool load_config) { p->load_files(input_files, load_model, load_config); }
|
||||
#else
|
||||
void Plater::load_files(const std::vector<fs::path> &input_files) { p->load_files(input_files); }
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
void Plater::update(bool force_autocenter) { p->update(force_autocenter); }
|
||||
|
||||
@ -2329,18 +2423,42 @@ void Plater::export_amf()
|
||||
}
|
||||
}
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void Plater::export_3mf(const boost::filesystem::path& output_path)
|
||||
#else
|
||||
void Plater::export_3mf()
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
{
|
||||
if (p->model.objects.empty()) { return; }
|
||||
|
||||
auto dialog = p->get_export_file(FT_3MF);
|
||||
if (! dialog) { return; }
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
wxString path;
|
||||
bool export_config = true;
|
||||
if (output_path.empty())
|
||||
{
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
auto dialog = p->get_export_file(FT_3MF);
|
||||
if (!dialog) { return; }
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
path = dialog->GetPath();
|
||||
export_config = dialog->get_checkbox_value();
|
||||
}
|
||||
else
|
||||
path = output_path.string();
|
||||
|
||||
wxString path = dialog->GetPath();
|
||||
auto path_cstr = path.c_str();
|
||||
if (!path.Lower().EndsWith(".3mf"))
|
||||
return;
|
||||
#else
|
||||
wxString path = dialog->GetPath();
|
||||
auto path_cstr = path.c_str();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
DynamicPrintConfig cfg = wxGetApp().preset_bundle->full_config();
|
||||
if (Slic3r::store_3mf(path_cstr, &p->model, dialog->get_checkbox_value() ? &cfg : nullptr)) {
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
if (Slic3r::store_3mf(path.c_str(), &p->model, export_config ? &cfg : nullptr)) {
|
||||
#else
|
||||
if (Slic3r::store_3mf(path_cstr, &p->model, dialog->get_checkbox_value() ? &cfg : nullptr)) {
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
// Success
|
||||
p->statusbar()->set_status_text(wxString::Format(_(L("3MF file exported to %s")), path));
|
||||
} else {
|
||||
@ -2378,7 +2496,7 @@ void Plater::on_extruders_change(int num_extruders)
|
||||
{
|
||||
auto& choices = sidebar().combos_filament();
|
||||
|
||||
wxWindowUpdateLocker noUpdates_scrolled_panel(sidebar().scrolled_panel());
|
||||
wxWindowUpdateLocker noUpdates_scrolled_panel(&sidebar()/*.scrolled_panel()*/);
|
||||
// sidebar().scrolled_panel()->Freeze();
|
||||
|
||||
int i = choices.size();
|
||||
@ -2396,8 +2514,8 @@ void Plater::on_extruders_change(int num_extruders)
|
||||
// remove unused choices if any
|
||||
sidebar().remove_unused_filament_combos(num_extruders);
|
||||
|
||||
sidebar().scrolled_panel()->Layout();
|
||||
// sidebar().scrolled_panel()->Thaw();
|
||||
sidebar().Layout();
|
||||
sidebar().scrolled_panel()->Refresh();
|
||||
}
|
||||
|
||||
void Plater::on_config_change(const DynamicPrintConfig &config)
|
||||
@ -2457,6 +2575,18 @@ void Plater::on_config_change(const DynamicPrintConfig &config)
|
||||
this->p->schedule_background_process();
|
||||
}
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
const wxString& Plater::get_project_filename() const
|
||||
{
|
||||
return p->project_filename;
|
||||
}
|
||||
|
||||
bool Plater::is_export_gcode_scheduled() const
|
||||
{
|
||||
return p->background_process.is_export_scheduled();
|
||||
}
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
int Plater::get_selected_object_idx()
|
||||
{
|
||||
return p->get_selected_object_idx();
|
||||
|
@ -111,9 +111,19 @@ public:
|
||||
Model& model();
|
||||
Print& print();
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void load_project();
|
||||
void add_model();
|
||||
void extract_config_from_project();
|
||||
#else
|
||||
void add();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void load_files(const std::vector<boost::filesystem::path>& input_files, bool load_model = true, bool load_config = true);
|
||||
#else
|
||||
void load_files(const std::vector<boost::filesystem::path> &input_files);
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
void update(bool force_autocenter = false);
|
||||
void select_view(const std::string& direction);
|
||||
@ -129,7 +139,11 @@ public:
|
||||
void export_gcode(boost::filesystem::path output_path = boost::filesystem::path());
|
||||
void export_stl();
|
||||
void export_amf();
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
void export_3mf(const boost::filesystem::path& output_path = boost::filesystem::path());
|
||||
#else
|
||||
void export_3mf();
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
void reslice();
|
||||
void changed_object(int obj_idx);
|
||||
void fix_through_netfabb(const int obj_idx);
|
||||
@ -138,6 +152,11 @@ public:
|
||||
void on_extruders_change(int extruders_count);
|
||||
void on_config_change(const DynamicPrintConfig &config);
|
||||
|
||||
#if ENABLE_NEW_MENU_LAYOUT
|
||||
const wxString& get_project_filename() const;
|
||||
bool is_export_gcode_scheduled() const;
|
||||
#endif // ENABLE_NEW_MENU_LAYOUT
|
||||
|
||||
int get_selected_object_idx();
|
||||
bool is_single_full_object_selection() const;
|
||||
wxGLCanvas* canvas3D();
|
||||
|
@ -759,6 +759,18 @@ void Tab::update_wiping_button_visibility() {
|
||||
// to uddate number of "filament" selection boxes when the number of extruders change.
|
||||
void Tab::on_presets_changed()
|
||||
{
|
||||
if (m_type == Slic3r::Preset::TYPE_PRINTER && !m_dependent_tabs.empty()) {
|
||||
// Printer selected at the Printer tab, update "compatible" marks at the print and filament selectors.
|
||||
for (auto t: m_dependent_tabs)
|
||||
{
|
||||
// If the printer tells us that the print or filament/sla_material preset has been switched or invalidated,
|
||||
// refresh the print or filament/sla_material tab page.
|
||||
Tab* tab = wxGetApp().get_tab(t);
|
||||
if (tab)
|
||||
tab->load_current_preset();
|
||||
}
|
||||
}
|
||||
|
||||
wxCommandEvent event(EVT_TAB_PRESETS_CHANGED);
|
||||
event.SetEventObject(this);
|
||||
wxPostEvent(this, event);
|
||||
@ -2335,7 +2347,7 @@ void Tab::select_preset(std::string preset_name)
|
||||
auto current_dirty = m_presets->current_is_dirty();
|
||||
auto printer_tab = m_presets->name() == "printer";
|
||||
auto canceled = false;
|
||||
m_reload_dependent_tabs = {};
|
||||
m_dependent_tabs = {};
|
||||
if (current_dirty && !may_discard_current_dirty_preset()) {
|
||||
canceled = true;
|
||||
} else if (printer_tab) {
|
||||
@ -2350,16 +2362,16 @@ void Tab::select_preset(std::string preset_name)
|
||||
PrinterTechnology old_printer_technology = m_presets->get_edited_preset().printer_technology();
|
||||
PrinterTechnology new_printer_technology = new_printer_preset.printer_technology();
|
||||
struct PresetUpdate {
|
||||
std::string name;
|
||||
Preset::Type tab_type;
|
||||
PresetCollection *presets;
|
||||
PrinterTechnology technology;
|
||||
bool old_preset_dirty;
|
||||
bool new_preset_compatible;
|
||||
};
|
||||
std::vector<PresetUpdate> updates = {
|
||||
{ "print", &m_preset_bundle->prints, ptFFF },
|
||||
{ "filament", &m_preset_bundle->filaments, ptFFF },
|
||||
{ "sla_material", &m_preset_bundle->sla_materials, ptSLA }
|
||||
{ Preset::Type::TYPE_PRINT, &m_preset_bundle->prints, ptFFF },
|
||||
{ Preset::Type::TYPE_FILAMENT, &m_preset_bundle->filaments, ptFFF },
|
||||
{ Preset::Type::TYPE_SLA_MATERIAL,&m_preset_bundle->sla_materials, ptSLA }
|
||||
};
|
||||
for (PresetUpdate &pu : updates) {
|
||||
pu.old_preset_dirty = (old_printer_technology == pu.technology) && pu.presets->current_is_dirty();
|
||||
@ -2371,7 +2383,7 @@ void Tab::select_preset(std::string preset_name)
|
||||
for (PresetUpdate &pu : updates) {
|
||||
// The preset will be switched to a different, compatible preset, or the '-- default --'.
|
||||
if (pu.technology == new_printer_technology)
|
||||
m_reload_dependent_tabs.emplace_back(pu.name);
|
||||
m_dependent_tabs.emplace_back(pu.tab_type);
|
||||
if (pu.old_preset_dirty)
|
||||
pu.presets->discard_current_changes();
|
||||
}
|
||||
@ -2597,6 +2609,7 @@ void Tab::update_ui_from_settings()
|
||||
// in application preferences.
|
||||
m_show_btn_incompatible_presets = wxGetApp().app_config->get("show_incompatible_presets")[0] == '1' ? true : false;
|
||||
bool show = m_show_btn_incompatible_presets && m_presets->name().compare("printer") != 0;
|
||||
Layout();
|
||||
show ? m_btn_hide_incompatible_presets->Show() : m_btn_hide_incompatible_presets->Hide();
|
||||
// If the 'show / hide presets' button is hidden, hide the incompatible presets.
|
||||
if (show) {
|
||||
|
@ -175,6 +175,7 @@ protected:
|
||||
bool m_show_incompatible_presets;
|
||||
|
||||
std::vector<std::string> m_reload_dependent_tabs = {};
|
||||
std::vector<Preset::Type> m_dependent_tabs = {};
|
||||
enum OptStatus { osSystemValue = 1, osInitValue = 2 };
|
||||
std::map<std::string, int> m_options_list;
|
||||
int m_opt_status_value = 0;
|
||||
@ -187,7 +188,7 @@ protected:
|
||||
|
||||
size_t m_selected_preset_item{ 0 };
|
||||
|
||||
void set_type();
|
||||
void set_type();
|
||||
|
||||
public:
|
||||
PresetBundle* m_preset_bundle;
|
||||
|
Loading…
Reference in New Issue
Block a user