Merge branch 'master' of https://github.com/prusa3d/Slic3r
This commit is contained in:
commit
882de2843e
45 changed files with 1014 additions and 436 deletions
|
@ -1,2 +1,2 @@
|
|||
add_executable(slabasebed EXCLUDE_FROM_ALL slabasebed.cpp)
|
||||
target_link_libraries(slabasebed libslic3r)
|
||||
target_link_libraries(slabasebed libslic3r ${Boost_LIBRARIES} ${TBB_LIBRARIES} ${Boost_LIBRARIES} ${CMAKE_DL_LIBS})
|
||||
|
|
|
@ -1,15 +1,29 @@
|
|||
#include <iostream>
|
||||
#include <fstream>
|
||||
#include <string>
|
||||
|
||||
#include <libslic3r/libslic3r.h>
|
||||
#include <libslic3r/TriangleMesh.hpp>
|
||||
#include <libslic3r/SLA/SLABasePool.hpp>
|
||||
#include <libslic3r/SLA/SLABoilerPlate.hpp>
|
||||
#include <libnest2d/tools/benchmark.h>
|
||||
|
||||
const std::string USAGE_STR = {
|
||||
"Usage: slabasebed stlfilename.stl"
|
||||
};
|
||||
|
||||
namespace Slic3r { namespace sla {
|
||||
|
||||
Contour3D convert(const Polygons& triangles, coord_t z, bool dir);
|
||||
Contour3D walls(const Polygon& floor_plate, const Polygon& ceiling,
|
||||
double floor_z_mm, double ceiling_z_mm,
|
||||
double offset_difference_mm, ThrowOnCancel thr);
|
||||
|
||||
void offset(ExPolygon& sh, coord_t distance);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
int main(const int argc, const char *argv[]) {
|
||||
using namespace Slic3r;
|
||||
using std::cout; using std::endl;
|
||||
|
@ -26,18 +40,43 @@ int main(const int argc, const char *argv[]) {
|
|||
model.align_to_origin();
|
||||
|
||||
ExPolygons ground_slice;
|
||||
TriangleMesh basepool;
|
||||
sla::Contour3D mesh;
|
||||
// TriangleMesh basepool;
|
||||
|
||||
sla::base_plate(model, ground_slice, 0.1f);
|
||||
|
||||
if(ground_slice.empty()) return EXIT_FAILURE;
|
||||
|
||||
ExPolygon bottom_plate = ground_slice.front();
|
||||
ExPolygon top_plate = bottom_plate;
|
||||
sla::offset(top_plate, coord_t(3.0/SCALING_FACTOR));
|
||||
sla::offset(bottom_plate, coord_t(1.0/SCALING_FACTOR));
|
||||
|
||||
bench.start();
|
||||
sla::create_base_pool(ground_slice, basepool);
|
||||
|
||||
Polygons top_plate_triangles, bottom_plate_triangles;
|
||||
top_plate.triangulate_p2t(&top_plate_triangles);
|
||||
bottom_plate.triangulate_p2t(&bottom_plate_triangles);
|
||||
|
||||
auto top_plate_mesh = sla::convert(top_plate_triangles, coord_t(3.0/SCALING_FACTOR), false);
|
||||
auto bottom_plate_mesh = sla::convert(bottom_plate_triangles, 0, true);
|
||||
|
||||
mesh.merge(bottom_plate_mesh);
|
||||
mesh.merge(top_plate_mesh);
|
||||
|
||||
sla::Contour3D w = sla::walls(bottom_plate.contour, top_plate.contour, 0, 3, 2.0, [](){});
|
||||
|
||||
mesh.merge(w);
|
||||
// sla::create_base_pool(ground_slice, basepool);
|
||||
bench.stop();
|
||||
|
||||
cout << "Base pool creation time: " << std::setprecision(10)
|
||||
<< bench.getElapsedSec() << " seconds." << endl;
|
||||
|
||||
basepool.write_ascii("out.stl");
|
||||
// basepool.write_ascii("out.stl");
|
||||
|
||||
std::fstream outstream("out.obj", std::fstream::out);
|
||||
mesh.to_obj(outstream);
|
||||
|
||||
return EXIT_SUCCESS;
|
||||
}
|
||||
|
|
|
@ -49,6 +49,8 @@ struct ModelID
|
|||
bool operator<=(const ModelID &rhs) const { return this->id <= rhs.id; }
|
||||
bool operator>=(const ModelID &rhs) const { return this->id >= rhs.id; }
|
||||
|
||||
bool valid() const { return id != 0; }
|
||||
|
||||
size_t id;
|
||||
};
|
||||
|
||||
|
|
|
@ -280,7 +280,7 @@ bool Print::is_step_done(PrintObjectStep step) const
|
|||
return false;
|
||||
tbb::mutex::scoped_lock lock(this->state_mutex());
|
||||
for (const PrintObject *object : m_objects)
|
||||
if (! object->m_state.is_done_unguarded(step))
|
||||
if (! object->is_step_done_unguarded(step))
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
@ -549,10 +549,14 @@ void Print::model_volume_list_update_supports(ModelObject &model_object_dst, con
|
|||
assert(! it->second); // not consumed yet
|
||||
it->second = true;
|
||||
ModelVolume *model_volume_dst = const_cast<ModelVolume*>(it->first);
|
||||
assert(model_volume_dst->type() == model_volume_src->type());
|
||||
// For support modifiers, the type may have been switched from blocker to enforcer and vice versa.
|
||||
assert((model_volume_dst->is_support_modifier() && model_volume_src->is_support_modifier()) || model_volume_dst->type() == model_volume_src->type());
|
||||
model_object_dst.volumes.emplace_back(model_volume_dst);
|
||||
if (model_volume_dst->is_support_modifier())
|
||||
model_volume_dst->set_transformation(model_volume_src->get_transformation());
|
||||
if (model_volume_dst->is_support_modifier()) {
|
||||
// For support modifiers, the type may have been switched from blocker to enforcer and vice versa.
|
||||
model_volume_dst->set_type(model_volume_src->type());
|
||||
model_volume_dst->set_transformation(model_volume_src->get_transformation());
|
||||
}
|
||||
assert(model_volume_dst->get_matrix().isApprox(model_volume_src->get_matrix()));
|
||||
} else {
|
||||
// The volume was not found in the old list. Create a new copy.
|
||||
|
|
|
@ -62,6 +62,10 @@ public:
|
|||
return state;
|
||||
}
|
||||
|
||||
bool is_started(StepType step, tbb::mutex &mtx) const {
|
||||
return this->state_with_timestamp(step, mtx).state == STARTED;
|
||||
}
|
||||
|
||||
bool is_done(StepType step, tbb::mutex &mtx) const {
|
||||
return this->state_with_timestamp(step, mtx).state == DONE;
|
||||
}
|
||||
|
@ -70,6 +74,10 @@ public:
|
|||
return m_state[step];
|
||||
}
|
||||
|
||||
bool is_started_unguarded(StepType step) const {
|
||||
return this->state_with_timestamp_unguarded(step).state == STARTED;
|
||||
}
|
||||
|
||||
bool is_done_unguarded(StepType step) const {
|
||||
return this->state_with_timestamp_unguarded(step).state == DONE;
|
||||
}
|
||||
|
@ -235,6 +243,18 @@ public:
|
|||
virtual ApplyStatus apply(const Model &model, const DynamicPrintConfig &config) = 0;
|
||||
const Model& model() const { return m_model; }
|
||||
|
||||
struct TaskParams {
|
||||
TaskParams() : single_model_object(0), single_model_instance_only(false), to_object_step(-1), to_print_step(-1) {}
|
||||
// If non-empty, limit the processing to this ModelObject.
|
||||
ModelID single_model_object;
|
||||
// If set, only process single_model_object. Otherwise process everything, but single_model_object first.
|
||||
bool single_model_instance_only;
|
||||
// If non-negative, stop processing at the successive object step.
|
||||
int to_object_step;
|
||||
// If non-negative, stop processing at the successive print step.
|
||||
int to_print_step;
|
||||
};
|
||||
|
||||
virtual void process() = 0;
|
||||
|
||||
struct SlicingStatus {
|
||||
|
@ -350,6 +370,9 @@ protected:
|
|||
bool invalidate_all_steps()
|
||||
{ return m_state.invalidate_all(this->cancel_callback()); }
|
||||
|
||||
bool is_step_started_unguarded(PrintStepEnum step) const { return m_state.is_started_unguarded(step); }
|
||||
bool is_step_done_unguarded(PrintStepEnum step) const { return m_state.is_done_unguarded(step); }
|
||||
|
||||
private:
|
||||
PrintState<PrintStepEnum, COUNT> m_state;
|
||||
};
|
||||
|
@ -383,6 +406,9 @@ protected:
|
|||
bool invalidate_all_steps()
|
||||
{ return m_state.invalidate_all(PrintObjectBase::cancel_callback(m_print)); }
|
||||
|
||||
bool is_step_started_unguarded(PrintObjectStepEnum step) const { return m_state.is_started_unguarded(step); }
|
||||
bool is_step_done_unguarded(PrintObjectStepEnum step) const { return m_state.is_done_unguarded(step); }
|
||||
|
||||
protected:
|
||||
// If the background processing stop was requested, throw CanceledException.
|
||||
// To be called by the worker thread and its sub-threads (mostly launched on the TBB thread pool) regularly.
|
||||
|
|
|
@ -4,78 +4,177 @@
|
|||
#include "boost/log/trivial.hpp"
|
||||
#include "SLABoostAdapter.hpp"
|
||||
#include "ClipperUtils.hpp"
|
||||
#include "Tesselate.hpp"
|
||||
|
||||
// For debugging:
|
||||
//#include <fstream>
|
||||
//#include <libnest2d/tools/benchmark.h>
|
||||
//#include "SVG.hpp"
|
||||
//#include "benchmark.h"
|
||||
|
||||
namespace Slic3r { namespace sla {
|
||||
|
||||
/// Convert the triangulation output to an intermediate mesh.
|
||||
Contour3D convert(const Polygons& triangles, coord_t z, bool dir) {
|
||||
|
||||
Pointf3s points;
|
||||
points.reserve(3*triangles.size());
|
||||
Indices indices;
|
||||
indices.reserve(points.size());
|
||||
|
||||
for(auto& tr : triangles) {
|
||||
auto c = coord_t(points.size()), b = c++, a = c++;
|
||||
if(dir) indices.emplace_back(a, b, c);
|
||||
else indices.emplace_back(c, b, a);
|
||||
for(auto& p : tr.points) {
|
||||
points.emplace_back(unscale(x(p), y(p), z));
|
||||
}
|
||||
}
|
||||
|
||||
return {points, indices};
|
||||
}
|
||||
|
||||
Contour3D walls(const ExPolygon& floor_plate, const ExPolygon& ceiling,
|
||||
double floor_z_mm, double ceiling_z_mm,
|
||||
ThrowOnCancel thr)
|
||||
/// This function will return a triangulation of a sheet connecting an upper
|
||||
/// and a lower plate given as input polygons. It will not triangulate the
|
||||
/// plates themselves only the sheet. The caller has to specify the lower and
|
||||
/// upper z levels in world coordinates as well as the offset difference
|
||||
/// between the sheets. If the lower_z_mm is higher than upper_z_mm or the
|
||||
/// offset difference is negative, the resulting triangle orientation will be
|
||||
/// reversed.
|
||||
///
|
||||
/// IMPORTANT: This is not a universal triangulation algorithm. It assumes
|
||||
/// that the lower and upper polygons are offsetted versions of the same
|
||||
/// original polygon. In general, it assumes that one of the polygons is
|
||||
/// completely inside the other. The offset difference is the reference
|
||||
/// distance from the inner polygon's perimeter to the outer polygon's
|
||||
/// perimeter. The real distance will be variable as the clipper offset has
|
||||
/// different strategies (rounding, etc...). This algorithm should have
|
||||
/// O(2n + 3m) complexity where n is the number of upper vertices and m is the
|
||||
/// number of lower vertices.
|
||||
Contour3D walls(const Polygon& lower, const Polygon& upper,
|
||||
double lower_z_mm, double upper_z_mm,
|
||||
double offset_difference_mm, ThrowOnCancel thr)
|
||||
{
|
||||
using std::transform; using std::back_inserter;
|
||||
|
||||
ExPolygon poly;
|
||||
poly.contour.points = floor_plate.contour.points;
|
||||
poly.holes.emplace_back(ceiling.contour);
|
||||
auto& h = poly.holes.front();
|
||||
std::reverse(h.points.begin(), h.points.end());
|
||||
Polygons tri = triangulate(poly);
|
||||
|
||||
Contour3D ret;
|
||||
ret.points.reserve(tri.size() * 3);
|
||||
|
||||
double fz = floor_z_mm;
|
||||
double cz = ceiling_z_mm;
|
||||
auto& rp = ret.points;
|
||||
auto& rpi = ret.indices;
|
||||
ret.indices.reserve(tri.size() * 3);
|
||||
if(upper.points.size() < 3 || lower.size() < 3) return ret;
|
||||
|
||||
coord_t idx = 0;
|
||||
// The concept of the algorithm is relatively simple. It will try to find
|
||||
// the closest vertices from the upper and the lower polygon and use those
|
||||
// as starting points. Then it will create the triangles sequentially using
|
||||
// an edge from the upper polygon and a vertex from the lower or vice versa,
|
||||
// depending on the resulting triangle's quality.
|
||||
// The quality is measured by a scalar value. So far it looks like it is
|
||||
// enough to derive it from the slope of the triangle's two edges connecting
|
||||
// the upper and the lower part. A reference slope is calculated from the
|
||||
// height and the offset difference.
|
||||
|
||||
auto hlines = h.lines();
|
||||
auto is_upper = [&hlines](const Point& p) {
|
||||
return std::any_of(hlines.begin(), hlines.end(),
|
||||
[&p](const Line& l) {
|
||||
return l.distance_to(p) < mm(1e-6);
|
||||
});
|
||||
// Offset in the index array for the ceiling
|
||||
const auto offs = upper.points.size();
|
||||
|
||||
// Shorthand for the vertex arrays
|
||||
auto& upoints = upper.points, &lpoints = lower.points;
|
||||
auto& rpts = ret.points; auto& rfaces = ret.indices;
|
||||
|
||||
// If the Z levels are flipped, or the offset difference is negative, we
|
||||
// will interpret that as the triangles normals should be inverted.
|
||||
bool inverted = upper_z_mm < lower_z_mm || offset_difference_mm < 0;
|
||||
|
||||
// Copy the points into the mesh, convert them from 2D to 3D
|
||||
rpts.reserve(upoints.size() + lpoints.size());
|
||||
rfaces.reserve(2*upoints.size() + 2*lpoints.size());
|
||||
const double sf = SCALING_FACTOR;
|
||||
for(auto& p : upoints) rpts.emplace_back(p.x()*sf, p.y()*sf, upper_z_mm);
|
||||
for(auto& p : lpoints) rpts.emplace_back(p.x()*sf, p.y()*sf, lower_z_mm);
|
||||
|
||||
// Create pointing indices into vertex arrays. u-upper, l-lower
|
||||
size_t uidx = 0, lidx = offs, unextidx = 1, lnextidx = offs + 1;
|
||||
|
||||
// Simple squared distance calculation.
|
||||
auto distfn = [](const Vec3d& p1, const Vec3d& p2) {
|
||||
auto p = p1 - p2; return p.transpose() * p;
|
||||
};
|
||||
|
||||
std::for_each(tri.begin(), tri.end(),
|
||||
[&rp, &rpi, thr, &idx, is_upper, fz, cz](const Polygon& pp)
|
||||
{
|
||||
thr(); // may throw if cancellation was requested
|
||||
// We need to find the closest point on lower polygon to the first point on
|
||||
// the upper polygon. These will be our starting points.
|
||||
double distmin = std::numeric_limits<double>::max();
|
||||
for(size_t l = lidx; l < rpts.size(); ++l) {
|
||||
thr();
|
||||
double d = distfn(rpts[l], rpts[uidx]);
|
||||
if(d < distmin) { lidx = l; distmin = d; }
|
||||
}
|
||||
|
||||
for(auto& p : pp.points)
|
||||
if(is_upper(p))
|
||||
rp.emplace_back(unscale(x(p), y(p), mm(cz)));
|
||||
else rp.emplace_back(unscale(x(p), y(p), mm(fz)));
|
||||
// Set up lnextidx to be ahead of lidx in cyclic mode
|
||||
lnextidx = lidx + 1;
|
||||
if(lnextidx == rpts.size()) lnextidx = offs;
|
||||
|
||||
coord_t a = idx++, b = idx++, c = idx++;
|
||||
if(fz > cz) rpi.emplace_back(c, b, a);
|
||||
else rpi.emplace_back(a, b, c);
|
||||
});
|
||||
// This will be the flip switch to toggle between upper and lower triangle
|
||||
// creation mode
|
||||
enum class Proceed {
|
||||
UPPER, // A segment from the upper polygon and one vertex from the lower
|
||||
LOWER // A segment from the lower polygon and one vertex from the upper
|
||||
} proceed = Proceed::UPPER;
|
||||
|
||||
// Flags to help evaluating loop termination.
|
||||
bool ustarted = false, lstarted = false;
|
||||
|
||||
// The variables for the fitness values, one for the actual and one for the
|
||||
// previous.
|
||||
double current_fit = 0, prev_fit = 0;
|
||||
|
||||
// Every triangle of the wall has two edges connecting the upper plate with
|
||||
// the lower plate. From the length of these two edges and the zdiff we
|
||||
// can calculate the momentary squared offset distance at a particular
|
||||
// position on the wall. The average of the differences from the reference
|
||||
// (squared) offset distance will give us the driving fitness value.
|
||||
const double offsdiff2 = std::pow(offset_difference_mm, 2);
|
||||
const double zdiff2 = std::pow(upper_z_mm - lower_z_mm, 2);
|
||||
|
||||
// Mark the current vertex iterator positions. If the iterators return to
|
||||
// the same position, the loop can be terminated.
|
||||
size_t uendidx = uidx, lendidx = lidx;
|
||||
|
||||
do { thr(); // check throw if canceled
|
||||
|
||||
prev_fit = current_fit;
|
||||
|
||||
switch(proceed) { // proceed depending on the current state
|
||||
case Proceed::UPPER:
|
||||
if(!ustarted || uidx != uendidx) { // there are vertices remaining
|
||||
// Get the 3D vertices in order
|
||||
const Vec3d& p_up1 = rpts[size_t(uidx)];
|
||||
const Vec3d& p_low = rpts[size_t(lidx)];
|
||||
const Vec3d& p_up2 = rpts[size_t(unextidx)];
|
||||
|
||||
// Calculate fitness: the average of the two connecting edges
|
||||
double a = offsdiff2 - (distfn(p_up1, p_low) - zdiff2);
|
||||
double b = offsdiff2 - (distfn(p_up2, p_low) - zdiff2);
|
||||
current_fit = (std::abs(a) + std::abs(b)) / 2;
|
||||
|
||||
if(current_fit > prev_fit) { // fit is worse than previously
|
||||
proceed = Proceed::LOWER;
|
||||
} else { // good to go, create the triangle
|
||||
inverted? rfaces.emplace_back(unextidx, lidx, uidx) :
|
||||
rfaces.emplace_back(uidx, lidx, unextidx) ;
|
||||
|
||||
// Increment the iterators, rotate if necessary
|
||||
++uidx; ++unextidx;
|
||||
if(unextidx == offs) unextidx = 0;
|
||||
if(uidx == offs) uidx = 0;
|
||||
|
||||
ustarted = true; // mark the movement of the iterators
|
||||
// so that the comparison to uendidx can be made correctly
|
||||
}
|
||||
} else proceed = Proceed::LOWER;
|
||||
|
||||
break;
|
||||
case Proceed::LOWER:
|
||||
// Mode with lower segment, upper vertex. Same structure:
|
||||
if(!lstarted || lidx != lendidx) {
|
||||
const Vec3d& p_low1 = rpts[size_t(lidx)];
|
||||
const Vec3d& p_low2 = rpts[size_t(lnextidx)];
|
||||
const Vec3d& p_up = rpts[size_t(uidx)];
|
||||
|
||||
double a = offsdiff2 - (distfn(p_up, p_low1) - zdiff2);
|
||||
double b = offsdiff2 - (distfn(p_up, p_low2) - zdiff2);
|
||||
current_fit = (std::abs(a) + std::abs(b)) / 2;
|
||||
|
||||
if(current_fit > prev_fit) {
|
||||
proceed = Proceed::UPPER;
|
||||
} else {
|
||||
inverted? rfaces.emplace_back(uidx, lnextidx, lidx) :
|
||||
rfaces.emplace_back(lidx, lnextidx, uidx);
|
||||
|
||||
++lidx; ++lnextidx;
|
||||
if(lnextidx == rpts.size()) lnextidx = offs;
|
||||
if(lidx == rpts.size()) lidx = offs;
|
||||
|
||||
lstarted = true;
|
||||
}
|
||||
} else proceed = Proceed::UPPER;
|
||||
|
||||
break;
|
||||
} // end of switch
|
||||
} while(!ustarted || !lstarted || uidx != uendidx || lidx != lendidx);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
@ -207,20 +306,31 @@ ExPolygons unify(const ExPolygons& shapes) {
|
|||
/// Only a debug function to generate top and bottom plates from a 2D shape.
|
||||
/// It is not used in the algorithm directly.
|
||||
inline Contour3D roofs(const ExPolygon& poly, coord_t z_distance) {
|
||||
Polygons triangles = triangulate(poly);
|
||||
|
||||
auto lower = convert(triangles, 0, false);
|
||||
auto upper = convert(triangles, z_distance, true);
|
||||
lower.merge(upper);
|
||||
return lower;
|
||||
auto lower = triangulate_expolygon_3d(poly);
|
||||
auto upper = triangulate_expolygon_3d(poly, z_distance*SCALING_FACTOR, true);
|
||||
Contour3D ret;
|
||||
ret.merge(lower); ret.merge(upper);
|
||||
return ret;
|
||||
}
|
||||
|
||||
/// This method will create a rounded edge around a flat polygon in 3d space.
|
||||
/// 'base_plate' parameter is the target plate.
|
||||
/// 'radius' is the radius of the edges.
|
||||
/// 'degrees' is tells how much of a circle should be created as the rounding.
|
||||
/// It should be in degrees, not radians.
|
||||
/// 'ceilheight_mm' is the Z coordinate of the flat polygon in 3D space.
|
||||
/// 'dir' Is the direction of the round edges: inward or outward
|
||||
/// 'thr' Throws if a cancel signal was received
|
||||
/// 'last_offset' An auxiliary output variable to save the last offsetted
|
||||
/// version of 'base_plate'
|
||||
/// 'last_height' An auxiliary output to save the last z coordinate of the
|
||||
/// offsetted base_plate. In other words, where the rounded edges end.
|
||||
Contour3D round_edges(const ExPolygon& base_plate,
|
||||
double radius_mm,
|
||||
double degrees,
|
||||
double ceilheight_mm,
|
||||
bool dir,
|
||||
ThrowOnCancel throw_on_cancel,
|
||||
ThrowOnCancel thr,
|
||||
ExPolygon& last_offset, double& last_height)
|
||||
{
|
||||
auto ob = base_plate;
|
||||
|
@ -236,10 +346,10 @@ Contour3D round_edges(const ExPolygon& base_plate,
|
|||
// we use sin for x distance because we interpret the angle starting from
|
||||
// PI/2
|
||||
int tos = degrees < 90?
|
||||
int(radius_mm*std::cos(degrees * PI / 180 - PI/2) / stepx) : steps;
|
||||
int(radius_mm*std::cos(degrees * PI / 180 - PI/2) / stepx) : steps;
|
||||
|
||||
for(int i = 1; i <= tos; ++i) {
|
||||
throw_on_cancel();
|
||||
thr();
|
||||
|
||||
ob = base_plate;
|
||||
|
||||
|
@ -252,7 +362,8 @@ Contour3D round_edges(const ExPolygon& base_plate,
|
|||
wh = ceilheight_mm - radius_mm + stepy;
|
||||
|
||||
Contour3D pwalls;
|
||||
pwalls = walls(ob, ob_prev, wh, wh_prev, throw_on_cancel);
|
||||
double prev_x = xx - (i - 1) * stepx;
|
||||
pwalls = walls(ob.contour, ob_prev.contour, wh, wh_prev, s*prev_x, thr);
|
||||
|
||||
curvedwalls.merge(pwalls);
|
||||
ob_prev = ob;
|
||||
|
@ -264,7 +375,7 @@ Contour3D round_edges(const ExPolygon& base_plate,
|
|||
int tos = int(tox / stepx);
|
||||
|
||||
for(int i = 1; i <= tos; ++i) {
|
||||
throw_on_cancel();
|
||||
thr();
|
||||
ob = base_plate;
|
||||
|
||||
double r2 = radius_mm * radius_mm;
|
||||
|
@ -275,7 +386,9 @@ Contour3D round_edges(const ExPolygon& base_plate,
|
|||
wh = ceilheight_mm - radius_mm - stepy;
|
||||
|
||||
Contour3D pwalls;
|
||||
pwalls = walls(ob_prev, ob, wh_prev, wh, throw_on_cancel);
|
||||
double prev_x = xx - radius_mm + (i - 1)*stepx;
|
||||
pwalls =
|
||||
walls(ob_prev.contour, ob.contour, wh_prev, wh, s*prev_x, thr);
|
||||
|
||||
curvedwalls.merge(pwalls);
|
||||
ob_prev = ob;
|
||||
|
@ -291,15 +404,17 @@ Contour3D round_edges(const ExPolygon& base_plate,
|
|||
|
||||
/// Generating the concave part of the 3D pool with the bottom plate and the
|
||||
/// side walls.
|
||||
Contour3D inner_bed(const ExPolygon& poly, double depth_mm,
|
||||
double begin_h_mm = 0) {
|
||||
|
||||
Polygons triangles = triangulate(poly);
|
||||
Contour3D inner_bed(const ExPolygon& poly,
|
||||
double depth_mm,
|
||||
double begin_h_mm = 0)
|
||||
{
|
||||
Contour3D bottom;
|
||||
Pointf3s triangles = triangulate_expolygon_3d(poly, -depth_mm + begin_h_mm);
|
||||
bottom.merge(triangles);
|
||||
|
||||
coord_t depth = mm(depth_mm);
|
||||
coord_t begin_h = mm(begin_h_mm);
|
||||
|
||||
auto bottom = convert(triangles, -depth + begin_h, false);
|
||||
auto lines = poly.lines();
|
||||
|
||||
// Generate outer walls
|
||||
|
@ -469,6 +584,9 @@ void base_plate(const TriangleMesh &mesh, ExPolygons &output, float h,
|
|||
void create_base_pool(const ExPolygons &ground_layer, TriangleMesh& out,
|
||||
const PoolConfig& cfg)
|
||||
{
|
||||
// for debugging:
|
||||
// Benchmark bench;
|
||||
// bench.start();
|
||||
|
||||
double mergedist = 2*(1.8*cfg.min_wall_thickness_mm + 4*cfg.edge_radius_mm)+
|
||||
cfg.max_merge_distance_mm;
|
||||
|
@ -478,27 +596,28 @@ void create_base_pool(const ExPolygons &ground_layer, TriangleMesh& out,
|
|||
// serve as the bottom plate of the pad. We will offset this concave hull
|
||||
// and then offset back the result with clipper with rounding edges ON. This
|
||||
// trick will create a nice rounded pad shape.
|
||||
auto concavehs = concave_hull(ground_layer, mergedist, cfg.throw_on_cancel);
|
||||
ExPolygons concavehs = concave_hull(ground_layer, mergedist, cfg.throw_on_cancel);
|
||||
|
||||
const double thickness = cfg.min_wall_thickness_mm;
|
||||
const double wingheight = cfg.min_wall_height_mm;
|
||||
const double fullheight = wingheight + thickness;
|
||||
const double tilt = PI/4;
|
||||
const double tilt = PI/4;
|
||||
const double wingdist = wingheight / std::tan(tilt);
|
||||
|
||||
// scaled values
|
||||
const coord_t s_thickness = mm(thickness);
|
||||
const coord_t s_eradius = mm(cfg.edge_radius_mm);
|
||||
const coord_t s_safety_dist = 2*s_eradius + coord_t(0.8*s_thickness);
|
||||
// const coord_t wheight = mm(cfg.min_wall_height_mm);
|
||||
coord_t s_wingdist = mm(wingdist);
|
||||
const coord_t s_wingdist = mm(wingdist);
|
||||
|
||||
auto& thrcl = cfg.throw_on_cancel;
|
||||
|
||||
Contour3D pool;
|
||||
|
||||
for(ExPolygon& concaveh : concavehs) {
|
||||
if(concaveh.contour.points.empty()) return;
|
||||
|
||||
// Get rif of any holes in the concave hull output.
|
||||
// Get rid of any holes in the concave hull output.
|
||||
concaveh.holes.clear();
|
||||
|
||||
// Here lies the trick that does the smooting only with clipper offset
|
||||
|
@ -524,8 +643,6 @@ void create_base_pool(const ExPolygons &ground_layer, TriangleMesh& out,
|
|||
std::reverse(tph.begin(), tph.end());
|
||||
}
|
||||
|
||||
Contour3D pool;
|
||||
|
||||
ExPolygon ob = outer_base; double wh = 0;
|
||||
|
||||
// now we will calculate the angle or portion of the circle from
|
||||
|
@ -557,60 +674,53 @@ void create_base_pool(const ExPolygons &ground_layer, TriangleMesh& out,
|
|||
|
||||
|
||||
// Generate the smoothed edge geometry
|
||||
auto walledges = round_edges(ob,
|
||||
r,
|
||||
phi,
|
||||
0, // z position of the input plane
|
||||
true,
|
||||
thrcl,
|
||||
ob, wh);
|
||||
pool.merge(walledges);
|
||||
pool.merge(round_edges(ob,
|
||||
r,
|
||||
phi,
|
||||
0, // z position of the input plane
|
||||
true,
|
||||
thrcl,
|
||||
ob, wh));
|
||||
|
||||
// Now that we have the rounded edge connencting the top plate with
|
||||
// the outer side walls, we can generate and merge the sidewall geometry
|
||||
auto pwalls = walls(ob, inner_base, wh, -fullheight, thrcl);
|
||||
pool.merge(pwalls);
|
||||
pool.merge(walls(ob.contour, inner_base.contour, wh, -fullheight,
|
||||
(s_thickness + s_wingdist) * SCALING_FACTOR, thrcl));
|
||||
|
||||
if(wingheight > 0) {
|
||||
// Generate the smoothed edge geometry
|
||||
auto cavityedges = round_edges(middle_base,
|
||||
r,
|
||||
phi - 90, // from tangent lines
|
||||
0,
|
||||
false,
|
||||
thrcl,
|
||||
ob, wh);
|
||||
pool.merge(cavityedges);
|
||||
pool.merge(round_edges(middle_base,
|
||||
r,
|
||||
phi - 90, // from tangent lines
|
||||
0, // z position of the input plane
|
||||
false,
|
||||
thrcl,
|
||||
ob, wh));
|
||||
|
||||
// Next is the cavity walls connecting to the top plate's
|
||||
// artificially created hole.
|
||||
auto cavitywalls = walls(inner_base, ob, -wingheight, wh, thrcl);
|
||||
pool.merge(cavitywalls);
|
||||
pool.merge(walls(inner_base.contour, ob.contour, -wingheight,
|
||||
wh, -s_safety_dist * SCALING_FACTOR, thrcl));
|
||||
}
|
||||
|
||||
// Now we need to triangulate the top and bottom plates as well as the
|
||||
// cavity bottom plate which is the same as the bottom plate but it is
|
||||
// eleveted by the thickness.
|
||||
Polygons top_triangles, bottom_triangles;
|
||||
// elevated by the thickness.
|
||||
pool.merge(triangulate_expolygon_3d(top_poly));
|
||||
pool.merge(triangulate_expolygon_3d(inner_base, -fullheight, true));
|
||||
|
||||
triangulate(top_poly, top_triangles);
|
||||
triangulate(inner_base, bottom_triangles);
|
||||
if(wingheight > 0)
|
||||
pool.merge(triangulate_expolygon_3d(inner_base, -wingheight));
|
||||
|
||||
auto top_plate = convert(top_triangles, 0, false);
|
||||
auto bottom_plate = convert(bottom_triangles, -mm(fullheight), true);
|
||||
|
||||
pool.merge(top_plate);
|
||||
pool.merge(bottom_plate);
|
||||
|
||||
if(wingheight > 0) {
|
||||
Polygons middle_triangles;
|
||||
triangulate(inner_base, middle_triangles);
|
||||
auto middle_plate = convert(middle_triangles, -mm(wingheight), false);
|
||||
pool.merge(middle_plate);
|
||||
}
|
||||
|
||||
out.merge(mesh(pool));
|
||||
}
|
||||
|
||||
// For debugging:
|
||||
// bench.stop();
|
||||
// std::cout << "Pad creation time: " << bench.getElapsedSec() << std::endl;
|
||||
// std::fstream fout("pad_debug.obj", std::fstream::out);
|
||||
// if(fout.good()) pool.to_obj(fout);
|
||||
|
||||
out.merge(mesh(pool));
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -36,14 +36,6 @@ inline coord_t x(const Vec3crd& p) { return p(0); }
|
|||
inline coord_t y(const Vec3crd& p) { return p(1); }
|
||||
inline coord_t z(const Vec3crd& p) { return p(2); }
|
||||
|
||||
inline void triangulate(const ExPolygon& expoly, Polygons& triangles) {
|
||||
expoly.triangulate_p2t(&triangles);
|
||||
}
|
||||
|
||||
inline Polygons triangulate(const ExPolygon& expoly) {
|
||||
Polygons tri; triangulate(expoly, tri); return tri;
|
||||
}
|
||||
|
||||
using Indices = std::vector<Vec3crd>;
|
||||
|
||||
/// Intermediate struct for a 3D mesh
|
||||
|
@ -63,6 +55,15 @@ struct Contour3D {
|
|||
}
|
||||
}
|
||||
|
||||
void merge(const Pointf3s& triangles) {
|
||||
const size_t offs = points.size();
|
||||
points.insert(points.end(), triangles.begin(), triangles.end());
|
||||
indices.reserve(indices.size() + points.size() / 3);
|
||||
|
||||
for(int i = (int)offs; i < (int)points.size(); i += 3)
|
||||
indices.emplace_back(i, i + 1, i + 2);
|
||||
}
|
||||
|
||||
// Write the index triangle structure to OBJ file for debugging purposes.
|
||||
void to_obj(std::ostream& stream) {
|
||||
for(auto& p : points) {
|
||||
|
@ -75,13 +76,9 @@ struct Contour3D {
|
|||
}
|
||||
};
|
||||
|
||||
//using PointSet = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::DontAlign>; //Eigen::MatrixXd;
|
||||
using ClusterEl = std::vector<unsigned>;
|
||||
using ClusteredPoints = std::vector<ClusterEl>;
|
||||
|
||||
/// Convert the triangulation output to an intermediate mesh.
|
||||
Contour3D convert(const Polygons& triangles, coord_t z, bool dir);
|
||||
|
||||
/// Mesh from an existing contour.
|
||||
inline TriangleMesh mesh(const Contour3D& ctour) {
|
||||
return {ctour.points, ctour.indices};
|
||||
|
|
|
@ -51,7 +51,7 @@ const std::array<std::string, slaposCount> OBJ_STEP_LABELS =
|
|||
L("Slicing model"), // slaposObjectSlice,
|
||||
L("Generating support points"), // slaposSupportPoints,
|
||||
L("Generating support tree"), // slaposSupportTree,
|
||||
L("Generating base pool"), // slaposBasePool,
|
||||
L("Generating pad"), // slaposBasePool,
|
||||
L("Slicing supports"), // slaposSliceSupports,
|
||||
L("Slicing supports") // slaposIndexSlices,
|
||||
};
|
||||
|
@ -402,6 +402,61 @@ SLAPrint::ApplyStatus SLAPrint::apply(const Model &model, const DynamicPrintConf
|
|||
return static_cast<ApplyStatus>(apply_status);
|
||||
}
|
||||
|
||||
void SLAPrint::set_task(const TaskParams ¶ms)
|
||||
{
|
||||
// Grab the lock for the Print / PrintObject milestones.
|
||||
tbb::mutex::scoped_lock lock(this->state_mutex());
|
||||
|
||||
int n_object_steps = params.to_object_step + 1;
|
||||
if (n_object_steps = 0)
|
||||
n_object_steps = (int)slaposCount;
|
||||
|
||||
if (params.single_model_object.valid()) {
|
||||
SLAPrintObject *print_object = nullptr;
|
||||
size_t idx_print_object = 0;
|
||||
for (; idx_print_object < m_objects.size(); ++idx_print_object)
|
||||
if (m_objects[idx_print_object]->model_object()->id() == params.single_model_object) {
|
||||
print_object = m_objects[idx_print_object];
|
||||
break;
|
||||
}
|
||||
assert(print_object != nullptr);
|
||||
bool shall_cancel = false;
|
||||
for (int istep = 0; istep < n_object_steps; ++istep)
|
||||
if (! print_object->m_stepmask[istep]) {
|
||||
shall_cancel = true;
|
||||
break;
|
||||
}
|
||||
bool running = false;
|
||||
if (!shall_cancel) {
|
||||
for (int istep = 0; istep < n_object_steps; ++ istep)
|
||||
if (print_object->is_step_started_unguarded(SLAPrintObjectStep(istep))) {
|
||||
running = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (!running)
|
||||
this->cancel_callback();
|
||||
|
||||
// Now the background process is either stopped, or it is inside one of the print object steps to be calculated anyway.
|
||||
if (params.single_model_instance_only) {
|
||||
// Suppress all the steps of other instances.
|
||||
for (SLAPrintObject *po : m_objects)
|
||||
for (int istep = 0; istep < (int)slaposCount; ++istep)
|
||||
print_object->m_stepmask[istep] = false;
|
||||
}
|
||||
else if (!running) {
|
||||
// Swap the print objects, so that the selected print_object is first in the row.
|
||||
// At this point the background processing must be stopped, so it is safe to shuffle print objects.
|
||||
if (idx_print_object != 0)
|
||||
std::swap(m_objects.front(), m_objects[idx_print_object]);
|
||||
}
|
||||
for (int istep = 0; istep < n_object_steps; ++ istep)
|
||||
print_object->m_stepmask[istep] = true;
|
||||
for (int istep = 0; istep < (int)slaposCount; ++ istep)
|
||||
print_object->m_stepmask[istep] = false;
|
||||
}
|
||||
}
|
||||
|
||||
namespace {
|
||||
// Compile the argument for support creation from the static print config.
|
||||
sla::SupportConfig make_support_cfg(const SLAPrintObjectConfig& c) {
|
||||
|
@ -1035,7 +1090,7 @@ bool SLAPrint::is_step_done(SLAPrintObjectStep step) const
|
|||
return false;
|
||||
tbb::mutex::scoped_lock lock(this->state_mutex());
|
||||
for (const SLAPrintObject *object : m_objects)
|
||||
if (! object->m_state.is_done_unguarded(step))
|
||||
if (! object->is_step_done_unguarded(step))
|
||||
return false;
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -139,6 +139,10 @@ protected:
|
|||
// Invalidate steps based on a set of parameters changed.
|
||||
bool invalidate_state_by_config_options(const std::vector<t_config_option_key> &opt_keys);
|
||||
|
||||
// Which steps have to be performed. Implicitly: all
|
||||
// to be accessible from SLAPrint
|
||||
std::vector<bool> m_stepmask;
|
||||
|
||||
private:
|
||||
// Object specific configuration, pulled from the configuration layer.
|
||||
SLAPrintObjectConfig m_config;
|
||||
|
@ -146,9 +150,6 @@ private:
|
|||
Transform3d m_trafo = Transform3d::Identity();
|
||||
std::vector<Instance> m_instances;
|
||||
|
||||
// Which steps have to be performed. Implicitly: all
|
||||
std::vector<bool> m_stepmask;
|
||||
|
||||
// Individual 2d slice polygons from lower z to higher z levels
|
||||
std::vector<ExPolygons> m_model_slices;
|
||||
|
||||
|
@ -194,6 +195,7 @@ public:
|
|||
void clear() override;
|
||||
bool empty() const override { return m_objects.empty(); }
|
||||
ApplyStatus apply(const Model &model, const DynamicPrintConfig &config) override;
|
||||
void set_task(const TaskParams ¶ms);
|
||||
void process() override;
|
||||
// Returns true if an object step is done on all objects and there's at least one object.
|
||||
bool is_step_done(SLAPrintObjectStep step) const;
|
||||
|
|
|
@ -1,4 +1,5 @@
|
|||
#include "2DBed.hpp"
|
||||
#include "GUI_App.hpp"
|
||||
|
||||
#include <wx/dcbuffer.h>
|
||||
|
||||
|
@ -9,6 +10,19 @@
|
|||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
||||
|
||||
Bed_2D::Bed_2D(wxWindow* parent) :
|
||||
wxPanel(parent, wxID_ANY, wxDefaultPosition, wxSize(25 * wxGetApp().em_unit(), -1), wxTAB_TRAVERSAL)
|
||||
{
|
||||
SetBackgroundStyle(wxBG_STYLE_PAINT); // to avoid assert message after wxAutoBufferedPaintDC
|
||||
#ifdef __APPLE__
|
||||
m_user_drawn_background = false;
|
||||
#endif /*__APPLE__*/
|
||||
Bind(wxEVT_PAINT, ([this](wxPaintEvent e) { repaint(); }));
|
||||
Bind(wxEVT_LEFT_DOWN, ([this](wxMouseEvent event) { mouse_event(event); }));
|
||||
Bind(wxEVT_MOTION, ([this](wxMouseEvent event) { mouse_event(event); }));
|
||||
Bind(wxEVT_SIZE, ([this](wxSizeEvent e) { Refresh(); }));
|
||||
}
|
||||
void Bed_2D::repaint()
|
||||
{
|
||||
wxAutoBufferedPaintDC dc(this);
|
||||
|
|
|
@ -25,21 +25,7 @@ class Bed_2D : public wxPanel
|
|||
void set_pos(Vec2d pos);
|
||||
|
||||
public:
|
||||
Bed_2D(wxWindow* parent)
|
||||
{
|
||||
Create(parent, wxID_ANY, wxDefaultPosition, wxSize(250, -1), wxTAB_TRAVERSAL);
|
||||
SetBackgroundStyle(wxBG_STYLE_PAINT); // to avoid assert message after wxAutoBufferedPaintDC
|
||||
// m_user_drawn_background = $^O ne 'darwin';
|
||||
#ifdef __APPLE__
|
||||
m_user_drawn_background = false;
|
||||
#endif /*__APPLE__*/
|
||||
Bind(wxEVT_PAINT, ([this](wxPaintEvent e) { repaint(); }));
|
||||
// EVT_ERASE_BACKGROUND($self, sub{}) if $self->{user_drawn_background};
|
||||
// Bind(EVT_MOUSE_EVENTS, ([this](wxMouseEvent event) {/*mouse_event()*/; }));
|
||||
Bind(wxEVT_LEFT_DOWN, ([this](wxMouseEvent event) { mouse_event(event); }));
|
||||
Bind(wxEVT_MOTION, ([this](wxMouseEvent event) { mouse_event(event); }));
|
||||
Bind(wxEVT_SIZE, ([this](wxSizeEvent e) { Refresh(); }));
|
||||
}
|
||||
Bed_2D(wxWindow* parent);
|
||||
~Bed_2D() {}
|
||||
|
||||
std::vector<Vec2d> m_bed_shape;
|
||||
|
|
|
@ -2,6 +2,8 @@
|
|||
#include "I18N.hpp"
|
||||
|
||||
#include "libslic3r/Utils.hpp"
|
||||
#include "GUI_App.hpp"
|
||||
#include "wxExtensions.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
@ -40,17 +42,13 @@ AboutDialog::AboutDialog()
|
|||
main_sizer->Add(hsizer, 0, wxEXPAND | wxALL, 20);
|
||||
|
||||
// logo
|
||||
wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG);
|
||||
auto *logo = new wxStaticBitmap(this, wxID_ANY, std::move(logo_bmp));
|
||||
hsizer->Add(logo, 1, wxEXPAND | wxTOP | wxBOTTOM, 35);
|
||||
// wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG);
|
||||
// auto *logo = new wxStaticBitmap(this, wxID_ANY, std::move(logo_bmp));
|
||||
auto *logo = new wxStaticBitmap(this, wxID_ANY, create_scaled_bitmap("Slic3r_192px.png"));
|
||||
hsizer->Add(logo, 1, wxALIGN_CENTER_VERTICAL);
|
||||
|
||||
wxBoxSizer* vsizer = new wxBoxSizer(wxVERTICAL);
|
||||
#ifdef __WXMSW__
|
||||
int proportion = 2;
|
||||
#else
|
||||
int proportion = 3;
|
||||
#endif
|
||||
hsizer->Add(vsizer, proportion, wxEXPAND|wxLEFT, 20);
|
||||
wxBoxSizer* vsizer = new wxBoxSizer(wxVERTICAL);
|
||||
hsizer->Add(vsizer, 2, wxEXPAND|wxLEFT, 20);
|
||||
|
||||
// title
|
||||
{
|
||||
|
@ -80,6 +78,7 @@ AboutDialog::AboutDialog()
|
|||
// text
|
||||
wxHtmlWindow* html = new wxHtmlWindow(this, wxID_ANY, wxDefaultPosition, wxDefaultSize, wxHW_SCROLLBAR_AUTO/*NEVER*/);
|
||||
{
|
||||
html->SetMinSize(wxSize(-1, 16 * wxGetApp().em_unit()));
|
||||
wxFont font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT);
|
||||
const auto text_clr = wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOWTEXT);
|
||||
auto text_clr_str = wxString::Format(wxT("#%02X%02X%02X"), text_clr.Red(), text_clr.Green(), text_clr.Blue());
|
||||
|
|
|
@ -44,7 +44,8 @@ void BedShapePanel::build_panel(ConfigOptionPoints* default_pt)
|
|||
auto sbsizer = new wxStaticBoxSizer(box, wxVERTICAL);
|
||||
|
||||
// shape options
|
||||
m_shape_options_book = new wxChoicebook(this, wxID_ANY, wxDefaultPosition, wxSize(300, -1), wxCHB_TOP);
|
||||
m_shape_options_book = new wxChoicebook(this, wxID_ANY, wxDefaultPosition,
|
||||
wxSize(25*wxGetApp().em_unit(), -1), wxCHB_TOP);
|
||||
sbsizer->Add(m_shape_options_book);
|
||||
|
||||
auto optgroup = init_shape_options_page(_(L("Rectangular")));
|
||||
|
@ -124,7 +125,7 @@ ConfigOptionsGroupShp BedShapePanel::init_shape_options_page(wxString title)
|
|||
ConfigOptionsGroupShp optgroup;
|
||||
optgroup = std::make_shared<ConfigOptionsGroup>(panel, _(L("Settings")));
|
||||
|
||||
optgroup->label_width = 100;
|
||||
optgroup->label_width = 10*wxGetApp().em_unit();//100;
|
||||
optgroup->m_on_change = [this](t_config_option_key opt_key, boost::any value) {
|
||||
update_shape();
|
||||
};
|
||||
|
|
|
@ -42,7 +42,7 @@ class BedShapeDialog : public wxDialog
|
|||
BedShapePanel* m_panel;
|
||||
public:
|
||||
BedShapeDialog(wxWindow* parent) : wxDialog(parent, wxID_ANY, _(L("Bed Shape")),
|
||||
wxDefaultPosition, wxSize(350, 700), wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER) {}
|
||||
wxDefaultPosition, wxDefaultSize, wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER) {}
|
||||
~BedShapeDialog() {}
|
||||
|
||||
void build_dialog(ConfigOptionPoints* default_pt);
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include "../Utils/Time.hpp"
|
||||
|
||||
#include "libslic3r/Utils.hpp"
|
||||
#include "GUI_App.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
@ -94,7 +95,9 @@ static wxString generate_html_page(const Config::SnapshotDB &snapshot_db, const
|
|||
}
|
||||
|
||||
ConfigSnapshotDialog::ConfigSnapshotDialog(const Config::SnapshotDB &snapshot_db, const wxString &on_snapshot)
|
||||
: wxDialog(NULL, wxID_ANY, _(L("Configuration Snapshots")), wxDefaultPosition, wxSize(600, 500), wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER | wxMAXIMIZE_BOX)
|
||||
: wxDialog(NULL, wxID_ANY, _(L("Configuration Snapshots")), wxDefaultPosition,
|
||||
wxSize(45 * wxGetApp().em_unit(), 40 * wxGetApp().em_unit()),
|
||||
wxDEFAULT_DIALOG_STYLE | wxRESIZE_BORDER | wxMAXIMIZE_BOX)
|
||||
{
|
||||
this->SetBackgroundColour(*wxWHITE);
|
||||
|
||||
|
|
|
@ -785,14 +785,9 @@ boost::any& ColourPicker::get_value()
|
|||
|
||||
void PointCtrl::BUILD()
|
||||
{
|
||||
auto size = wxSize(wxDefaultSize);
|
||||
if (m_opt.height >= 0) size.SetHeight(m_opt.height);
|
||||
if (m_opt.width >= 0) size.SetWidth(m_opt.width);
|
||||
|
||||
auto temp = new wxBoxSizer(wxHORIZONTAL);
|
||||
// $self->wxSizer($sizer);
|
||||
//
|
||||
wxSize field_size(40, -1);
|
||||
|
||||
const wxSize field_size(4 * wxGetApp().em_unit(), -1);
|
||||
|
||||
auto default_pt = static_cast<const ConfigOptionPoints*>(m_opt.default_value)->values.at(0);
|
||||
double val = default_pt(0);
|
||||
|
|
|
@ -3879,7 +3879,8 @@ bool GLCanvas3D::LegendTexture::generate(const GCodePreviewData& preview_data, c
|
|||
wxMemoryDC mask_memDC;
|
||||
|
||||
// calculate scaling
|
||||
const float scale = canvas.get_canvas_size().get_scale_factor();
|
||||
// const float scale = canvas.get_canvas_size().get_scale_factor();
|
||||
const float scale = wxGetApp().em_unit()*0.1; // get scale from em_unit() value, because of get_scale_factor() return 1
|
||||
const int scaled_square = std::floor((float)Px_Square * scale);
|
||||
const int scaled_title_offset = Px_Title_Offset * scale;
|
||||
const int scaled_text_offset = Px_Text_Offset * scale;
|
||||
|
@ -3887,7 +3888,7 @@ bool GLCanvas3D::LegendTexture::generate(const GCodePreviewData& preview_data, c
|
|||
const int scaled_border = Px_Border * scale;
|
||||
|
||||
// select default font
|
||||
const wxFont font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT).Scale(scale);
|
||||
const wxFont font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT)/*.Scale(scale)*/; // font is no need to scale now
|
||||
memDC.SetFont(font);
|
||||
mask_memDC.SetFont(font);
|
||||
|
||||
|
@ -5161,7 +5162,8 @@ void GLCanvas3D::bind_event_handlers()
|
|||
m_canvas->Bind(wxEVT_SIZE, &GLCanvas3D::on_size, this);
|
||||
m_canvas->Bind(wxEVT_IDLE, &GLCanvas3D::on_idle, this);
|
||||
m_canvas->Bind(wxEVT_CHAR, &GLCanvas3D::on_char, this);
|
||||
m_canvas->Bind(wxEVT_KEY_UP, &GLCanvas3D::on_key_up, this);
|
||||
m_canvas->Bind(wxEVT_KEY_DOWN, &GLCanvas3D::on_key, this);
|
||||
m_canvas->Bind(wxEVT_KEY_UP, &GLCanvas3D::on_key, this);
|
||||
m_canvas->Bind(wxEVT_MOUSEWHEEL, &GLCanvas3D::on_mouse_wheel, this);
|
||||
m_canvas->Bind(wxEVT_TIMER, &GLCanvas3D::on_timer, this);
|
||||
m_canvas->Bind(wxEVT_LEFT_DOWN, &GLCanvas3D::on_mouse, this);
|
||||
|
@ -5187,7 +5189,8 @@ void GLCanvas3D::unbind_event_handlers()
|
|||
m_canvas->Unbind(wxEVT_SIZE, &GLCanvas3D::on_size, this);
|
||||
m_canvas->Unbind(wxEVT_IDLE, &GLCanvas3D::on_idle, this);
|
||||
m_canvas->Unbind(wxEVT_CHAR, &GLCanvas3D::on_char, this);
|
||||
m_canvas->Unbind(wxEVT_KEY_UP, &GLCanvas3D::on_key_up, this);
|
||||
m_canvas->Unbind(wxEVT_KEY_DOWN, &GLCanvas3D::on_key, this);
|
||||
m_canvas->Unbind(wxEVT_KEY_UP, &GLCanvas3D::on_key, this);
|
||||
m_canvas->Unbind(wxEVT_MOUSEWHEEL, &GLCanvas3D::on_mouse_wheel, this);
|
||||
m_canvas->Unbind(wxEVT_TIMER, &GLCanvas3D::on_timer, this);
|
||||
m_canvas->Unbind(wxEVT_LEFT_DOWN, &GLCanvas3D::on_mouse, this);
|
||||
|
@ -5224,6 +5227,15 @@ void GLCanvas3D::on_char(wxKeyEvent& evt)
|
|||
// see include/wx/defs.h enum wxKeyCode
|
||||
int keyCode = evt.GetKeyCode();
|
||||
int ctrlMask = wxMOD_CONTROL;
|
||||
|
||||
#if ENABLE_IMGUI
|
||||
auto imgui = wxGetApp().imgui();
|
||||
if (imgui->update_key_data(evt)) {
|
||||
render();
|
||||
return;
|
||||
}
|
||||
#endif // ENABLE_IMGUI
|
||||
|
||||
//#ifdef __APPLE__
|
||||
// ctrlMask |= wxMOD_RAW_CONTROL;
|
||||
//#endif /* __APPLE__ */
|
||||
|
@ -5299,14 +5311,23 @@ void GLCanvas3D::on_char(wxKeyEvent& evt)
|
|||
}
|
||||
}
|
||||
|
||||
void GLCanvas3D::on_key_up(wxKeyEvent& evt)
|
||||
void GLCanvas3D::on_key(wxKeyEvent& evt)
|
||||
{
|
||||
// see include/wx/defs.h enum wxKeyCode
|
||||
int keyCode = evt.GetKeyCode();
|
||||
#if ENABLE_IMGUI
|
||||
auto imgui = wxGetApp().imgui();
|
||||
if (imgui->update_key_data(evt)) {
|
||||
render();
|
||||
} else
|
||||
#endif // ENABLE_IMGUI
|
||||
if (evt.GetEventType() == wxEVT_KEY_UP) {
|
||||
const int keyCode = evt.GetKeyCode();
|
||||
|
||||
// shift has been just released - SLA gizmo might want to close rectangular selection.
|
||||
if (m_gizmos.get_current_type() == Gizmos::SlaSupports && keyCode == WXK_SHIFT && m_gizmos.mouse_event(SLAGizmoEventType::ShiftUp))
|
||||
m_dirty = true;
|
||||
}
|
||||
|
||||
// shift has been just released - SLA gizmo might want to close rectangular selection.
|
||||
if (m_gizmos.get_current_type() == Gizmos::SlaSupports && keyCode == WXK_SHIFT && m_gizmos.mouse_event(SLAGizmoEventType::ShiftUp))
|
||||
m_dirty = true;
|
||||
evt.Skip(); // Needed to have EVT_CHAR generated as well
|
||||
}
|
||||
|
||||
void GLCanvas3D::on_mouse_wheel(wxMouseEvent& evt)
|
||||
|
@ -5363,9 +5384,7 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
|
|||
auto imgui = wxGetApp().imgui();
|
||||
if (imgui->update_mouse_data(evt)) {
|
||||
render();
|
||||
if (imgui->want_any_input()) {
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
#endif // ENABLE_IMGUI
|
||||
|
||||
|
|
|
@ -1075,7 +1075,7 @@ public:
|
|||
void on_size(wxSizeEvent& evt);
|
||||
void on_idle(wxIdleEvent& evt);
|
||||
void on_char(wxKeyEvent& evt);
|
||||
void on_key_up(wxKeyEvent& evt);
|
||||
void on_key(wxKeyEvent& evt);
|
||||
void on_mouse_wheel(wxMouseEvent& evt);
|
||||
void on_timer(wxTimerEvent& evt);
|
||||
void on_mouse(wxMouseEvent& evt);
|
||||
|
|
|
@ -233,7 +233,7 @@ wxGLCanvas* GLCanvas3DManager::create_wxglcanvas(wxWindow *parent)
|
|||
attribList[4] = 0;
|
||||
}
|
||||
|
||||
return new wxGLCanvas(parent, wxID_ANY, attribList);
|
||||
return new wxGLCanvas(parent, wxID_ANY, attribList, wxDefaultPosition, wxDefaultSize, wxWANTS_CHARS);
|
||||
}
|
||||
|
||||
GLCanvas3DManager::CanvasesMap::iterator GLCanvas3DManager::_get_canvas(wxGLCanvas* canvas)
|
||||
|
|
|
@ -1445,8 +1445,8 @@ void GLGizmoFlatten::on_render(const GLCanvas3D::Selection& selection) const
|
|||
{
|
||||
const Transform3d& m = selection.get_volume(*selection.get_volume_idxs().begin())->get_instance_transformation().get_matrix();
|
||||
::glPushMatrix();
|
||||
::glMultMatrixd(m.data());
|
||||
::glTranslatef(0.f, 0.f, selection.get_volume(*selection.get_volume_idxs().begin())->get_sla_shift_z());
|
||||
::glMultMatrixd(m.data());
|
||||
if (this->is_plane_update_necessary())
|
||||
const_cast<GLGizmoFlatten*>(this)->update_planes();
|
||||
for (int i = 0; i < (int)m_planes.size(); ++i)
|
||||
|
@ -1479,8 +1479,8 @@ void GLGizmoFlatten::on_render_for_picking(const GLCanvas3D::Selection& selectio
|
|||
{
|
||||
const Transform3d& m = selection.get_volume(*selection.get_volume_idxs().begin())->get_instance_transformation().get_matrix();
|
||||
::glPushMatrix();
|
||||
::glMultMatrixd(m.data());
|
||||
::glTranslatef(0.f, 0.f, selection.get_volume(*selection.get_volume_idxs().begin())->get_sla_shift_z());
|
||||
::glMultMatrixd(m.data());
|
||||
if (this->is_plane_update_necessary())
|
||||
const_cast<GLGizmoFlatten*>(this)->update_planes();
|
||||
for (int i = 0; i < (int)m_planes.size(); ++i)
|
||||
|
@ -2064,18 +2064,21 @@ bool GLGizmoSlaSupports::mouse_event(SLAGizmoEventType action, const Vec2d& mous
|
|||
if (instance_id == -1)
|
||||
return false;
|
||||
|
||||
// Regardless of whether the user clicked the object or not, we will unselect all points:
|
||||
select_point(NoPoints);
|
||||
// If there is some selection, don't add new point and deselect everything instead.
|
||||
if (m_selection_empty) {
|
||||
Vec3f new_pos;
|
||||
try {
|
||||
new_pos = unproject_on_mesh(mouse_position); // this can throw - we don't want to create a new point in that case
|
||||
m_editing_mode_cache.emplace_back(std::make_pair(sla::SupportPoint(new_pos, m_new_point_head_diameter/2.f, false), false));
|
||||
m_unsaved_changes = true;
|
||||
}
|
||||
catch (...) { // not clicked on object
|
||||
return true; // prevents deselection of the gizmo by GLCanvas3D
|
||||
}
|
||||
}
|
||||
else
|
||||
select_point(NoPoints);
|
||||
|
||||
Vec3f new_pos;
|
||||
try {
|
||||
new_pos = unproject_on_mesh(mouse_position); // this can throw - we don't want to create a new point in that case
|
||||
m_editing_mode_cache.emplace_back(std::make_pair(sla::SupportPoint(new_pos, m_new_point_head_diameter/2.f, false), true));
|
||||
m_unsaved_changes = true;
|
||||
}
|
||||
catch (...) { // not clicked on object
|
||||
return true; // prevents deselection of the gizmo by GLCanvas3D
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
|
@ -2106,9 +2109,8 @@ bool GLGizmoSlaSupports::mouse_event(SLAGizmoEventType action, const Vec2d& mous
|
|||
direction_to_camera = instance_matrix_no_translation.inverse().cast<float>() * direction_to_camera.eval();
|
||||
|
||||
// Iterate over all points, check if they're in the rectangle and if so, check that they are not obscured by the mesh:
|
||||
for (std::pair<sla::SupportPoint, bool>& point_and_selection : m_editing_mode_cache) {
|
||||
const sla::SupportPoint& support_point = point_and_selection.first;
|
||||
Vec3f pos = instance_matrix.cast<float>() * support_point.pos;
|
||||
for (unsigned int i=0; i<m_editing_mode_cache.size(); ++i) {
|
||||
Vec3f pos = instance_matrix.cast<float>() * m_editing_mode_cache[i].first.pos;
|
||||
pos(2) += z_offset;
|
||||
GLdouble out_x, out_y, out_z;
|
||||
::gluProject((GLdouble)pos(0), (GLdouble)pos(1), (GLdouble)pos(2), modelview_matrix, projection_matrix, viewport, &out_x, &out_y, &out_z);
|
||||
|
@ -2118,14 +2120,14 @@ bool GLGizmoSlaSupports::mouse_event(SLAGizmoEventType action, const Vec2d& mous
|
|||
bool is_obscured = false;
|
||||
// Cast a ray in the direction of the camera and look for intersection with the mesh:
|
||||
std::vector<igl::Hit> hits;
|
||||
if (m_AABB.intersect_ray(m_V, m_F, support_point.pos, direction_to_camera, hits))
|
||||
if (m_AABB.intersect_ray(m_V, m_F, m_editing_mode_cache[i].first.pos, direction_to_camera, hits))
|
||||
// FIXME: the intersection could in theory be behind the camera, but as of now we only have camera direction.
|
||||
// Also, the threshold is in mesh coordinates, not in actual dimensions.
|
||||
if (hits.size() > 1 || hits.front().t > 0.001f)
|
||||
is_obscured = true;
|
||||
|
||||
if (!is_obscured)
|
||||
point_and_selection.second = true;
|
||||
select_point(i);
|
||||
}
|
||||
}
|
||||
m_selection_rectangle_active = false;
|
||||
|
@ -2170,6 +2172,8 @@ void GLGizmoSlaSupports::delete_selected_points()
|
|||
// wxGetApp().plater()->reslice();
|
||||
}
|
||||
|
||||
select_point(NoPoints);
|
||||
|
||||
//m_parent.post_event(SimpleEvent(EVT_GLCANVAS_SCHEDULE_BACKGROUND_PROCESS));
|
||||
}
|
||||
|
||||
|
@ -2269,7 +2273,9 @@ RENDER_AGAIN:
|
|||
m_imgui->checkbox(_(L("Lock supports under new islands")), m_lock_unique_islands);
|
||||
force_refresh |= changed != m_lock_unique_islands;
|
||||
|
||||
m_imgui->disabled_begin(m_selection_empty);
|
||||
remove_selected = m_imgui->button(_(L("Remove selected points")));
|
||||
m_imgui->disabled_end();
|
||||
|
||||
m_imgui->text(" "); // vertical gap
|
||||
|
||||
|
@ -2448,10 +2454,13 @@ void GLGizmoSlaSupports::select_point(int i)
|
|||
{
|
||||
if (i == AllPoints || i == NoPoints) {
|
||||
for (auto& point_and_selection : m_editing_mode_cache)
|
||||
point_and_selection.second = ( i == AllPoints ? true : false);
|
||||
point_and_selection.second = ( i == AllPoints );
|
||||
m_selection_empty = (i == NoPoints);
|
||||
}
|
||||
else
|
||||
else {
|
||||
m_editing_mode_cache[i].second = true;
|
||||
m_selection_empty = false;
|
||||
}
|
||||
}
|
||||
|
||||
void GLGizmoSlaSupports::editing_mode_discard_changes()
|
||||
|
|
|
@ -502,6 +502,7 @@ private:
|
|||
bool m_ignore_up_event = false;
|
||||
bool m_combo_box_open = false;
|
||||
bool m_unsaved_changes = false;
|
||||
bool m_selection_empty = true;
|
||||
EState m_old_state = Off; // to be able to see that the gizmo has just been closed (see on_set_state)
|
||||
#if SLAGIZMO_IMGUI_MODAL
|
||||
bool m_show_modal = false;
|
||||
|
|
|
@ -165,10 +165,10 @@ bool GUI_App::OnInit()
|
|||
|
||||
// ! Temporary workaround for the correct behavior of the Scrolled sidebar panel
|
||||
// Do this "manipulations" only once ( after (re)create of the application )
|
||||
if (plater_ && sidebar().obj_list()->GetMinHeight() > 200)
|
||||
if (plater_ && sidebar().obj_list()->GetMinHeight() > 15 * wxGetApp().em_unit())
|
||||
{
|
||||
wxWindowUpdateLocker noUpdates_sidebar(&sidebar());
|
||||
sidebar().obj_list()->SetMinSize(wxSize(-1, 200));
|
||||
sidebar().obj_list()->SetMinSize(wxSize(-1, 15 * wxGetApp().em_unit()));
|
||||
|
||||
// !!! to correct later layouts
|
||||
update_mode(); // update view mode after fix of the object_list size
|
||||
|
@ -251,6 +251,7 @@ void GUI_App::init_fonts()
|
|||
{
|
||||
m_small_font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT);
|
||||
m_bold_font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT).Bold();
|
||||
|
||||
#ifdef __WXMAC__
|
||||
m_small_font.SetPointSize(11);
|
||||
m_bold_font.SetPointSize(13);
|
||||
|
|
|
@ -81,6 +81,9 @@ class GUI_App : public wxApp
|
|||
wxFont m_small_font;
|
||||
wxFont m_bold_font;
|
||||
|
||||
size_t m_em_unit; // width of a "m"-symbol in pixels for current system font
|
||||
// Note: for 100% Scale m_em_unit = 10 -> it's a good enough coefficient for a size setting of controls
|
||||
|
||||
wxLocale* m_wxLocale{ nullptr };
|
||||
|
||||
#if ENABLE_IMGUI
|
||||
|
@ -108,6 +111,8 @@ public:
|
|||
|
||||
const wxFont& small_font() { return m_small_font; }
|
||||
const wxFont& bold_font() { return m_bold_font; }
|
||||
size_t em_unit() const { return m_em_unit; }
|
||||
void set_em_unit(const size_t em_unit) { m_em_unit = em_unit; }
|
||||
|
||||
void recreate_GUI();
|
||||
void system_info();
|
||||
|
|
|
@ -45,18 +45,18 @@ ObjectList::ObjectList(wxWindow* parent) :
|
|||
// Fill CATEGORY_ICON
|
||||
{
|
||||
// ptFFF
|
||||
CATEGORY_ICON[L("Layers and Perimeters")] = wxBitmap(from_u8(var("layers.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Infill")] = wxBitmap(from_u8(var("infill.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Support material")] = wxBitmap(from_u8(var("building.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Speed")] = wxBitmap(from_u8(var("time.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Extruders")] = wxBitmap(from_u8(var("funnel.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Extrusion Width")] = wxBitmap(from_u8(var("funnel.png")), wxBITMAP_TYPE_PNG);
|
||||
// CATEGORY_ICON[L("Skirt and brim")] = wxBitmap(from_u8(var("box.png")), wxBITMAP_TYPE_PNG);
|
||||
// CATEGORY_ICON[L("Speed > Acceleration")] = wxBitmap(from_u8(var("time.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Advanced")] = wxBitmap(from_u8(var("wand.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Layers and Perimeters")] = create_scaled_bitmap("layers.png"); // wxBitmap(from_u8(var("layers.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Infill")] = create_scaled_bitmap("infill.png"); // wxBitmap(from_u8(var("infill.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Support material")] = create_scaled_bitmap("building.png"); // wxBitmap(from_u8(var("building.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Speed")] = create_scaled_bitmap("time.png"); // wxBitmap(from_u8(var("time.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Extruders")] = create_scaled_bitmap("funnel.png"); // wxBitmap(from_u8(var("funnel.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Extrusion Width")] = create_scaled_bitmap("funnel.png"); // wxBitmap(from_u8(var("funnel.png")), wxBITMAP_TYPE_PNG);
|
||||
// CATEGORY_ICON[L("Skirt and brim")] = create_scaled_bitmap("box.png"); // wxBitmap(from_u8(var("box.png")), wxBITMAP_TYPE_PNG);
|
||||
// CATEGORY_ICON[L("Speed > Acceleration")] = create_scaled_bitmap("time.png"); // wxBitmap(from_u8(var("time.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Advanced")] = create_scaled_bitmap("wand.png"); // wxBitmap(from_u8(var("wand.png")), wxBITMAP_TYPE_PNG);
|
||||
// ptSLA
|
||||
CATEGORY_ICON[L("Supports")] = wxBitmap(from_u8(var("building.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Pad")] = wxBitmap(from_u8(var("brick.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Supports")] = create_scaled_bitmap("building.png"); // wxBitmap(from_u8(var("building.png")), wxBITMAP_TYPE_PNG);
|
||||
CATEGORY_ICON[L("Pad")] = create_scaled_bitmap("brick.png"); // wxBitmap(from_u8(var("brick.png")), wxBITMAP_TYPE_PNG);
|
||||
}
|
||||
|
||||
// create control
|
||||
|
@ -116,7 +116,7 @@ void ObjectList::create_objects_ctrl()
|
|||
SetMinSize(wxSize(-1, 3000)); // #ys_FIXME
|
||||
|
||||
m_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
m_sizer->Add(this, 1, wxGROW | wxLEFT, 20);
|
||||
m_sizer->Add(this, 1, wxGROW);
|
||||
|
||||
m_objects_model = new PrusaObjectDataViewModel;
|
||||
AssociateModel(m_objects_model);
|
||||
|
@ -129,13 +129,13 @@ void ObjectList::create_objects_ctrl()
|
|||
// column 0(Icon+Text) of the view control:
|
||||
// And Icon can be consisting of several bitmaps
|
||||
AppendColumn(new wxDataViewColumn(_(L("Name")), new PrusaBitmapTextRenderer(),
|
||||
0, 200, wxALIGN_LEFT, wxDATAVIEW_COL_RESIZABLE));
|
||||
0, 20*wxGetApp().em_unit()/*200*/, wxALIGN_LEFT, wxDATAVIEW_COL_RESIZABLE));
|
||||
|
||||
// column 1 of the view control:
|
||||
AppendColumn(create_objects_list_extruder_column(4));
|
||||
|
||||
// column 2 of the view control:
|
||||
AppendBitmapColumn(" ", 2, wxDATAVIEW_CELL_INERT, 25,
|
||||
AppendBitmapColumn(" ", 2, wxDATAVIEW_CELL_INERT, int(2.5 * wxGetApp().em_unit())/*25*/,
|
||||
wxALIGN_CENTER_HORIZONTAL, wxDATAVIEW_COL_RESIZABLE);
|
||||
}
|
||||
|
||||
|
@ -218,7 +218,8 @@ wxDataViewColumn* ObjectList::create_objects_list_extruder_column(int extruders_
|
|||
choices.Add(wxString::Format("%d", i));
|
||||
wxDataViewChoiceRenderer *c =
|
||||
new wxDataViewChoiceRenderer(choices, wxDATAVIEW_CELL_EDITABLE, wxALIGN_CENTER_HORIZONTAL);
|
||||
wxDataViewColumn* column = new wxDataViewColumn(_(L("Extruder")), c, 1, 80, wxALIGN_CENTER_HORIZONTAL, wxDATAVIEW_COL_RESIZABLE);
|
||||
wxDataViewColumn* column = new wxDataViewColumn(_(L("Extruder")), c, 1,
|
||||
8*wxGetApp().em_unit()/*80*/, wxALIGN_CENTER_HORIZONTAL, wxDATAVIEW_COL_RESIZABLE);
|
||||
return column;
|
||||
}
|
||||
|
||||
|
@ -334,11 +335,18 @@ void ObjectList::update_name_in_model(const wxDataViewItem& item) const
|
|||
|
||||
void ObjectList::init_icons()
|
||||
{
|
||||
m_bmp_modifiermesh = wxBitmap(from_u8(var("lambda.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("plugin.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_solidmesh = wxBitmap(from_u8(var("object.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("package.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_modifiermesh = wxBitmap(from_u8(var("lambda.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("plugin.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_solidmesh = wxBitmap(from_u8(var("object.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("package.png")), wxBITMAP_TYPE_PNG);
|
||||
|
||||
// m_bmp_support_enforcer = wxBitmap(from_u8(var("support_enforcer_.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_support_blocker = wxBitmap(from_u8(var("support_blocker_.png")), wxBITMAP_TYPE_PNG);
|
||||
|
||||
|
||||
m_bmp_modifiermesh = create_scaled_bitmap("lambda.png");
|
||||
m_bmp_solidmesh = create_scaled_bitmap("object.png");
|
||||
m_bmp_support_enforcer = create_scaled_bitmap("support_enforcer_.png");
|
||||
m_bmp_support_blocker = create_scaled_bitmap("support_blocker_.png");
|
||||
|
||||
m_bmp_support_enforcer = wxBitmap(from_u8(var("support_enforcer_.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_support_blocker = wxBitmap(from_u8(var("support_blocker_.png")), wxBITMAP_TYPE_PNG);
|
||||
|
||||
m_bmp_vector.reserve(4); // bitmaps for different types of parts
|
||||
m_bmp_vector.push_back(&m_bmp_solidmesh); // Add part
|
||||
|
@ -348,13 +356,16 @@ void ObjectList::init_icons()
|
|||
m_objects_model->SetVolumeBitmaps(m_bmp_vector);
|
||||
|
||||
// init icon for manifold warning
|
||||
m_bmp_manifold_warning = wxBitmap(from_u8(var("exclamation_mark_.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("error.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_manifold_warning = wxBitmap(from_u8(var("exclamation_mark_.png")), wxBITMAP_TYPE_PNG);//(Slic3r::var("error.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_manifold_warning = create_scaled_bitmap("exclamation_mark_.png");
|
||||
|
||||
// init bitmap for "Split to sub-objects" context menu
|
||||
m_bmp_split = wxBitmap(from_u8(var("split.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_split = wxBitmap(from_u8(var("split.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_split = create_scaled_bitmap("split.png");
|
||||
|
||||
// init bitmap for "Add Settings" context menu
|
||||
m_bmp_cog = wxBitmap(from_u8(var("cog.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_cog = wxBitmap(from_u8(var("cog.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_cog = create_scaled_bitmap("cog.png");
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -22,7 +22,7 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
|||
#endif // __APPLE__
|
||||
{
|
||||
m_og->set_name(_(L("Object Manipulation")));
|
||||
m_og->label_width = 125;
|
||||
m_og->label_width = 12 * wxGetApp().em_unit();//125;
|
||||
m_og->set_grid_vgap(5);
|
||||
|
||||
m_og->m_on_change = std::bind(&ObjectManipulation::on_change, this, std::placeholders::_1, std::placeholders::_2);
|
||||
|
@ -48,11 +48,13 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
|||
def.default_value = new ConfigOptionString{ " " };
|
||||
m_og->append_single_option_line(Option(def, "object_name"));
|
||||
|
||||
const int field_width = 5 * wxGetApp().em_unit()/*50*/;
|
||||
|
||||
// Legend for object modification
|
||||
auto line = Line{ "", "" };
|
||||
def.label = "";
|
||||
def.type = coString;
|
||||
def.width = 50;
|
||||
def.width = field_width/*50*/;
|
||||
|
||||
std::vector<std::string> axes{ "x", "y", "z" };
|
||||
for (const auto axis : axes) {
|
||||
|
@ -64,13 +66,13 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
|||
m_og->append_line(line);
|
||||
|
||||
|
||||
auto add_og_to_object_settings = [this](const std::string& option_name, const std::string& sidetext)
|
||||
auto add_og_to_object_settings = [this, field_width](const std::string& option_name, const std::string& sidetext)
|
||||
{
|
||||
Line line = { _(option_name), "" };
|
||||
ConfigOptionDef def;
|
||||
def.type = coFloat;
|
||||
def.default_value = new ConfigOptionFloat(0.0);
|
||||
def.width = 50;
|
||||
def.width = field_width/*50*/;
|
||||
|
||||
// Add "uniform scaling" button in front of "Scale" option
|
||||
if (option_name == "Scale") {
|
||||
|
@ -88,8 +90,9 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
|
|||
// Add empty bmp (Its size have to be equal to PrusaLockButton) in front of "Size" option to label alignment
|
||||
else if (option_name == "Size") {
|
||||
line.near_label_widget = [this](wxWindow* parent) {
|
||||
return new wxStaticBitmap(parent, wxID_ANY, wxNullBitmap, wxDefaultPosition,
|
||||
wxBitmap(from_u8(var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG).GetSize());
|
||||
return new wxStaticBitmap(parent, wxID_ANY, wxNullBitmap, wxDefaultPosition,
|
||||
// wxBitmap(from_u8(var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG).GetSize());
|
||||
create_scaled_bitmap("one_layer_lock_on.png").GetSize());
|
||||
};
|
||||
}
|
||||
|
||||
|
|
|
@ -75,7 +75,8 @@ void ObjectSettings::update_settings_list()
|
|||
{
|
||||
auto opt_key = (line.get_options())[0].opt_id; //we assume that we have one option per line
|
||||
|
||||
auto btn = new wxBitmapButton(parent, wxID_ANY, wxBitmap(from_u8(var("colorchange_delete_on.png")), wxBITMAP_TYPE_PNG),
|
||||
// auto btn = new wxBitmapButton(parent, wxID_ANY, wxBitmap(from_u8(var("colorchange_delete_on.png")), wxBITMAP_TYPE_PNG),
|
||||
auto btn = new wxBitmapButton(parent, wxID_ANY, create_scaled_bitmap("colorchange_delete_on.png"),
|
||||
wxDefaultPosition, wxDefaultSize, wxBORDER_NONE);
|
||||
#ifdef __WXMSW__
|
||||
btn->SetBackgroundColour(wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW));
|
||||
|
@ -98,7 +99,7 @@ void ObjectSettings::update_settings_list()
|
|||
std::vector<std::string> categories;
|
||||
if (!(opt_keys.size() == 1 && opt_keys[0] == "extruder"))// return;
|
||||
{
|
||||
auto extruders_cnt = wxGetApp().preset_bundle->printers.get_selected_preset().printer_technology() == ptSLA ? 1 :
|
||||
const int extruders_cnt = wxGetApp().preset_bundle->printers.get_selected_preset().printer_technology() == ptSLA ? 1 :
|
||||
wxGetApp().preset_bundle->printers.get_edited_preset().config.option<ConfigOptionFloats>("nozzle_diameter")->values.size();
|
||||
|
||||
for (auto& opt_key : opt_keys) {
|
||||
|
@ -119,8 +120,8 @@ void ObjectSettings::update_settings_list()
|
|||
continue;
|
||||
|
||||
auto optgroup = std::make_shared<ConfigOptionsGroup>(m_parent, cat.first, config, false, extra_column);
|
||||
optgroup->label_width = 150;
|
||||
optgroup->sidetext_width = 70;
|
||||
optgroup->label_width = 15 * wxGetApp().em_unit();//150;
|
||||
optgroup->sidetext_width = 7 * wxGetApp().em_unit();//70;
|
||||
|
||||
optgroup->m_on_change = [](const t_config_option_key& opt_id, const boost::any& value) {
|
||||
wxGetApp().obj_list()->part_settings_changed(); };
|
||||
|
@ -130,7 +131,7 @@ void ObjectSettings::update_settings_list()
|
|||
if (opt == "extruder")
|
||||
continue;
|
||||
Option option = optgroup->get_option(opt);
|
||||
option.opt.width = 70;
|
||||
option.opt.width = 7 * wxGetApp().em_unit();//70;
|
||||
optgroup->append_single_option_line(option);
|
||||
}
|
||||
optgroup->reload_config();
|
||||
|
|
|
@ -259,7 +259,7 @@ bool Preview::init(wxWindow* parent, DynamicPrintConfig* config, BackgroundSlici
|
|||
m_label_show_features = new wxStaticText(this, wxID_ANY, _(L("Show")));
|
||||
|
||||
m_combochecklist_features = new wxComboCtrl();
|
||||
m_combochecklist_features->Create(this, wxID_ANY, _(L("Feature types")), wxDefaultPosition, wxSize(200, -1), wxCB_READONLY);
|
||||
m_combochecklist_features->Create(this, wxID_ANY, _(L("Feature types")), wxDefaultPosition, wxSize(15 * wxGetApp().em_unit(), -1), wxCB_READONLY);
|
||||
std::string feature_text = GUI::into_u8(_(L("Feature types")));
|
||||
std::string feature_items = GUI::into_u8(
|
||||
_(L("Perimeter")) + "|" +
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
|
||||
#include <wx/string.h>
|
||||
#include <wx/event.h>
|
||||
#include <wx/clipbrd.h>
|
||||
#include <wx/debug.h>
|
||||
|
||||
#include <GL/glew.h>
|
||||
|
@ -30,6 +31,7 @@ ImGuiWrapper::ImGuiWrapper()
|
|||
, m_style_scaling(1.0)
|
||||
, m_mouse_buttons(0)
|
||||
, m_disabled(false)
|
||||
, m_new_frame_open(false)
|
||||
{
|
||||
}
|
||||
|
||||
|
@ -44,6 +46,8 @@ bool ImGuiWrapper::init()
|
|||
ImGui::CreateContext();
|
||||
|
||||
init_default_font(m_style_scaling);
|
||||
init_input();
|
||||
init_style();
|
||||
|
||||
ImGui::GetIO().IniFilename = nullptr;
|
||||
|
||||
|
@ -104,23 +108,62 @@ bool ImGuiWrapper::update_mouse_data(wxMouseEvent& evt)
|
|||
io.MouseDown[2] = evt.MiddleDown();
|
||||
|
||||
unsigned buttons = (evt.LeftDown() ? 1 : 0) | (evt.RightDown() ? 2 : 0) | (evt.MiddleDown() ? 4 : 0);
|
||||
bool res = buttons != m_mouse_buttons;
|
||||
m_mouse_buttons = buttons;
|
||||
return res;
|
||||
|
||||
new_frame();
|
||||
return want_mouse();
|
||||
}
|
||||
|
||||
bool ImGuiWrapper::update_key_data(wxKeyEvent &evt)
|
||||
{
|
||||
ImGuiIO& io = ImGui::GetIO();
|
||||
|
||||
if (evt.GetEventType() == wxEVT_CHAR) {
|
||||
// Char event
|
||||
const auto key = evt.GetUnicodeKey();
|
||||
if (key != 0) {
|
||||
io.AddInputCharacter(key);
|
||||
}
|
||||
|
||||
new_frame();
|
||||
return want_keyboard() || want_text_input();
|
||||
} else {
|
||||
// Key up/down event
|
||||
int key = evt.GetKeyCode();
|
||||
wxCHECK_MSG(key >= 0 && key < IM_ARRAYSIZE(io.KeysDown), false, "Received invalid key code");
|
||||
|
||||
io.KeysDown[key] = evt.GetEventType() == wxEVT_KEY_DOWN;
|
||||
io.KeyShift = evt.ShiftDown();
|
||||
io.KeyCtrl = evt.ControlDown();
|
||||
io.KeyAlt = evt.AltDown();
|
||||
io.KeySuper = evt.MetaDown();
|
||||
|
||||
// XXX: Unfortunatelly this seems broken due to some interference with wxWidgets,
|
||||
// we have to return true always (perform re-render).
|
||||
// new_frame();
|
||||
// return want_keyboard() || want_text_input();
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
void ImGuiWrapper::new_frame()
|
||||
{
|
||||
if (m_new_frame_open) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (m_font_texture == 0)
|
||||
create_device_objects();
|
||||
|
||||
ImGui::NewFrame();
|
||||
m_new_frame_open = true;
|
||||
}
|
||||
|
||||
void ImGuiWrapper::render()
|
||||
{
|
||||
ImGui::Render();
|
||||
render_draw_data(ImGui::GetDrawData());
|
||||
m_new_frame_open = false;
|
||||
}
|
||||
|
||||
void ImGuiWrapper::set_next_window_pos(float x, float y, int flag)
|
||||
|
@ -307,6 +350,82 @@ void ImGuiWrapper::create_fonts_texture()
|
|||
glBindTexture(GL_TEXTURE_2D, last_texture);
|
||||
}
|
||||
|
||||
void ImGuiWrapper::init_input()
|
||||
{
|
||||
ImGuiIO& io = ImGui::GetIO();
|
||||
|
||||
// Keyboard mapping. ImGui will use those indices to peek into the io.KeysDown[] array.
|
||||
io.KeyMap[ImGuiKey_Tab] = WXK_TAB;
|
||||
io.KeyMap[ImGuiKey_LeftArrow] = WXK_LEFT;
|
||||
io.KeyMap[ImGuiKey_RightArrow] = WXK_RIGHT;
|
||||
io.KeyMap[ImGuiKey_UpArrow] = WXK_UP;
|
||||
io.KeyMap[ImGuiKey_DownArrow] = WXK_DOWN;
|
||||
io.KeyMap[ImGuiKey_PageUp] = WXK_PAGEUP;
|
||||
io.KeyMap[ImGuiKey_PageDown] = WXK_PAGEDOWN;
|
||||
io.KeyMap[ImGuiKey_Home] = WXK_HOME;
|
||||
io.KeyMap[ImGuiKey_End] = WXK_END;
|
||||
io.KeyMap[ImGuiKey_Insert] = WXK_INSERT;
|
||||
io.KeyMap[ImGuiKey_Delete] = WXK_DELETE;
|
||||
io.KeyMap[ImGuiKey_Backspace] = WXK_BACK;
|
||||
io.KeyMap[ImGuiKey_Space] = WXK_SPACE;
|
||||
io.KeyMap[ImGuiKey_Enter] = WXK_RETURN;
|
||||
io.KeyMap[ImGuiKey_Escape] = WXK_ESCAPE;
|
||||
io.KeyMap[ImGuiKey_A] = 'A';
|
||||
io.KeyMap[ImGuiKey_C] = 'C';
|
||||
io.KeyMap[ImGuiKey_V] = 'V';
|
||||
io.KeyMap[ImGuiKey_X] = 'X';
|
||||
io.KeyMap[ImGuiKey_Y] = 'Y';
|
||||
io.KeyMap[ImGuiKey_Z] = 'Z';
|
||||
|
||||
// Don't let imgui special-case Mac, wxWidgets already do that
|
||||
io.ConfigMacOSXBehaviors = false;
|
||||
|
||||
// Setup clipboard interaction callbacks
|
||||
io.SetClipboardTextFn = clipboard_set;
|
||||
io.GetClipboardTextFn = clipboard_get;
|
||||
io.ClipboardUserData = this;
|
||||
}
|
||||
|
||||
void ImGuiWrapper::init_style()
|
||||
{
|
||||
ImGuiStyle &style = ImGui::GetStyle();
|
||||
|
||||
auto set_color = [&](ImGuiCol_ col, unsigned hex_color) {
|
||||
style.Colors[col] = ImVec4(
|
||||
((hex_color >> 24) & 0xff) / 255.0f,
|
||||
((hex_color >> 16) & 0xff) / 255.0f,
|
||||
((hex_color >> 8) & 0xff) / 255.0f,
|
||||
(hex_color & 0xff) / 255.0f);
|
||||
};
|
||||
|
||||
static const unsigned COL_GREY_DARK = 0x444444ff;
|
||||
static const unsigned COL_GREY_LIGHT = 0x666666ff;
|
||||
static const unsigned COL_ORANGE_DARK = 0xba5418ff;
|
||||
static const unsigned COL_ORANGE_LIGHT = 0xff6f22ff;
|
||||
|
||||
// Generics
|
||||
set_color(ImGuiCol_TitleBgActive, COL_ORANGE_DARK);
|
||||
set_color(ImGuiCol_FrameBg, COL_GREY_DARK);
|
||||
set_color(ImGuiCol_FrameBgHovered, COL_GREY_LIGHT);
|
||||
set_color(ImGuiCol_FrameBgActive, COL_GREY_LIGHT);
|
||||
|
||||
// Text selection
|
||||
set_color(ImGuiCol_TextSelectedBg, COL_ORANGE_DARK);
|
||||
|
||||
// Buttons
|
||||
set_color(ImGuiCol_Button, COL_ORANGE_DARK);
|
||||
set_color(ImGuiCol_ButtonHovered, COL_ORANGE_LIGHT);
|
||||
set_color(ImGuiCol_ButtonActive, COL_ORANGE_LIGHT);
|
||||
|
||||
// Checkbox
|
||||
set_color(ImGuiCol_CheckMark, COL_ORANGE_LIGHT);
|
||||
|
||||
// ComboBox items
|
||||
set_color(ImGuiCol_Header, COL_ORANGE_DARK);
|
||||
set_color(ImGuiCol_HeaderHovered, COL_ORANGE_LIGHT);
|
||||
set_color(ImGuiCol_HeaderActive, COL_ORANGE_LIGHT);
|
||||
}
|
||||
|
||||
void ImGuiWrapper::render_draw_data(ImDrawData *draw_data)
|
||||
{
|
||||
// Avoid rendering when minimized, scale coordinates for retina displays (screen coordinates != framebuffer coordinates)
|
||||
|
@ -420,6 +539,37 @@ void ImGuiWrapper::destroy_fonts_texture()
|
|||
}
|
||||
}
|
||||
|
||||
const char* ImGuiWrapper::clipboard_get(void* user_data)
|
||||
{
|
||||
ImGuiWrapper *self = reinterpret_cast<ImGuiWrapper*>(user_data);
|
||||
|
||||
const char* res = "";
|
||||
|
||||
if (wxTheClipboard->Open()) {
|
||||
if (wxTheClipboard->IsSupported(wxDF_TEXT)) {
|
||||
wxTextDataObject data;
|
||||
wxTheClipboard->GetData(data);
|
||||
|
||||
if (data.GetTextLength() > 0) {
|
||||
self->m_clipboard_text = into_u8(data.GetText());
|
||||
res = self->m_clipboard_text.c_str();
|
||||
}
|
||||
}
|
||||
|
||||
wxTheClipboard->Close();
|
||||
}
|
||||
|
||||
return res;
|
||||
}
|
||||
|
||||
void ImGuiWrapper::clipboard_set(void* /* user_data */, const char* text)
|
||||
{
|
||||
if (wxTheClipboard->Open()) {
|
||||
wxTheClipboard->SetData(new wxTextDataObject(wxString::FromUTF8(text))); // object owned by the clipboard
|
||||
wxTheClipboard->Close();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
} // namespace GUI
|
||||
} // namespace Slic3r
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
|
||||
class wxString;
|
||||
class wxMouseEvent;
|
||||
class wxKeyEvent;
|
||||
|
||||
|
||||
namespace Slic3r {
|
||||
|
@ -25,6 +26,8 @@ class ImGuiWrapper
|
|||
float m_style_scaling;
|
||||
unsigned m_mouse_buttons;
|
||||
bool m_disabled;
|
||||
bool m_new_frame_open;
|
||||
std::string m_clipboard_text;
|
||||
|
||||
public:
|
||||
ImGuiWrapper();
|
||||
|
@ -37,6 +40,7 @@ public:
|
|||
void set_display_size(float w, float h);
|
||||
void set_style_scaling(float scaling);
|
||||
bool update_mouse_data(wxMouseEvent &evt);
|
||||
bool update_key_data(wxKeyEvent &evt);
|
||||
|
||||
void new_frame();
|
||||
void render();
|
||||
|
@ -68,9 +72,14 @@ private:
|
|||
void init_default_font(float scaling);
|
||||
void create_device_objects();
|
||||
void create_fonts_texture();
|
||||
void init_input();
|
||||
void init_style();
|
||||
void render_draw_data(ImDrawData *draw_data);
|
||||
void destroy_device_objects();
|
||||
void destroy_fonts_texture();
|
||||
|
||||
static const char* clipboard_get(void* user_data);
|
||||
static void clipboard_set(void* user_data, const char* text);
|
||||
};
|
||||
|
||||
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#include "GUI.hpp"
|
||||
#include <wx/scrolwin.h>
|
||||
#include "GUI_App.hpp"
|
||||
#include "wxExtensions.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
@ -16,7 +17,8 @@ KBShortcutsDialog::KBShortcutsDialog()
|
|||
auto main_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
|
||||
// logo
|
||||
wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_32px.png")), wxBITMAP_TYPE_PNG);
|
||||
// wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_32px.png")), wxBITMAP_TYPE_PNG);
|
||||
const wxBitmap logo_bmp = create_scaled_bitmap("Slic3r_32px.png");
|
||||
|
||||
// fonts
|
||||
wxFont head_font = wxSystemSettings::GetFont(wxSYS_DEFAULT_GUI_FONT).Bold();
|
||||
|
@ -54,7 +56,7 @@ KBShortcutsDialog::KBShortcutsDialog()
|
|||
hsizer->Add(logo, 0, wxEXPAND | wxLEFT | wxRIGHT, 15);
|
||||
|
||||
// head
|
||||
wxStaticText* head = new wxStaticText(panel, wxID_ANY, sc.first, wxDefaultPosition, wxSize(200,-1));
|
||||
wxStaticText* head = new wxStaticText(panel, wxID_ANY, sc.first, wxDefaultPosition, wxSize(20 * wxGetApp().em_unit(), -1));
|
||||
head->SetFont(head_font);
|
||||
hsizer->Add(head, 0, wxALIGN_CENTER_VERTICAL);
|
||||
|
||||
|
|
|
@ -53,6 +53,11 @@ wxFrame(NULL, wxID_ANY, SLIC3R_BUILD, wxDefaultPosition, wxDefaultSize, wxDEFAUL
|
|||
SLIC3R_VERSION +
|
||||
_(L(" - Remember to check for updates at http://github.com/prusa3d/slic3r/releases")));
|
||||
|
||||
|
||||
// initialize default width_unit according to the width of the one symbol ("x") of the current system font
|
||||
const wxSize size = GetTextExtent("m");
|
||||
wxGetApp().set_em_unit(size.x-1);
|
||||
|
||||
// initialize tabpanel and menubar
|
||||
init_tabpanel();
|
||||
init_menubar();
|
||||
|
|
|
@ -13,13 +13,16 @@
|
|||
#include "GUI.hpp"
|
||||
#include "I18N.hpp"
|
||||
#include "ConfigWizard.hpp"
|
||||
#include "wxExtensions.hpp"
|
||||
#include "GUI_App.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
||||
|
||||
MsgDialog::MsgDialog(wxWindow *parent, const wxString &title, const wxString &headline, wxWindowID button_id) :
|
||||
MsgDialog(parent, title, headline, wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG), button_id)
|
||||
// MsgDialog(parent, title, headline, wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG), button_id)
|
||||
MsgDialog(parent, title, headline, create_scaled_bitmap("Slic3r_192px.png"), button_id)
|
||||
{}
|
||||
|
||||
MsgDialog::MsgDialog(wxWindow *parent, const wxString &title, const wxString &headline, wxBitmap bitmap, wxWindowID button_id) :
|
||||
|
@ -35,7 +38,7 @@ MsgDialog::MsgDialog(wxWindow *parent, const wxString &title, const wxString &he
|
|||
|
||||
auto *headtext = new wxStaticText(this, wxID_ANY, headline);
|
||||
headtext->SetFont(boldfont);
|
||||
headtext->Wrap(CONTENT_WIDTH);
|
||||
headtext->Wrap(CONTENT_WIDTH*wxGetApp().em_unit());
|
||||
rightsizer->Add(headtext);
|
||||
rightsizer->AddSpacer(VERT_SPACING);
|
||||
|
||||
|
@ -64,7 +67,8 @@ MsgDialog::~MsgDialog() {}
|
|||
|
||||
ErrorDialog::ErrorDialog(wxWindow *parent, const wxString &msg)
|
||||
: MsgDialog(parent, _(L("Slic3r error")), _(L("Slic3r has encountered an error")),
|
||||
wxBitmap(from_u8(Slic3r::var("Slic3r_192px_grayscale.png")), wxBITMAP_TYPE_PNG),
|
||||
// wxBitmap(from_u8(Slic3r::var("Slic3r_192px_grayscale.png")), wxBITMAP_TYPE_PNG),
|
||||
create_scaled_bitmap("Slic3r_192px_grayscale.png"),
|
||||
wxID_NONE)
|
||||
, msg(msg)
|
||||
{
|
||||
|
@ -73,10 +77,10 @@ ErrorDialog::ErrorDialog(wxWindow *parent, const wxString &msg)
|
|||
panel->SetSizer(p_sizer);
|
||||
|
||||
auto *text = new wxStaticText(panel, wxID_ANY, msg);
|
||||
text->Wrap(CONTENT_WIDTH);
|
||||
text->Wrap(CONTENT_WIDTH*wxGetApp().em_unit());
|
||||
p_sizer->Add(text, 1, wxEXPAND);
|
||||
|
||||
panel->SetMinSize(wxSize(CONTENT_WIDTH, 0));
|
||||
panel->SetMinSize(wxSize(CONTENT_WIDTH*wxGetApp().em_unit(), 0));
|
||||
panel->SetScrollRate(0, 5);
|
||||
|
||||
content_sizer->Add(panel, 1, wxEXPAND);
|
||||
|
@ -95,7 +99,7 @@ ErrorDialog::ErrorDialog(wxWindow *parent, const wxString &msg)
|
|||
btn_sizer->Add(btn_copy, 0, wxRIGHT, HORIZ_SPACING);
|
||||
btn_sizer->Add(btn_ok);
|
||||
|
||||
SetMaxSize(wxSize(-1, CONTENT_MAX_HEIGHT));
|
||||
SetMaxSize(wxSize(-1, CONTENT_MAX_HEIGHT*wxGetApp().em_unit()));
|
||||
Fit();
|
||||
}
|
||||
|
||||
|
|
|
@ -32,8 +32,8 @@ struct MsgDialog : wxDialog
|
|||
|
||||
protected:
|
||||
enum {
|
||||
CONTENT_WIDTH = 500,
|
||||
CONTENT_MAX_HEIGHT = 600,
|
||||
CONTENT_WIDTH = 50,//500,
|
||||
CONTENT_MAX_HEIGHT = 60,//600,
|
||||
BORDER = 30,
|
||||
VERT_SPACING = 15,
|
||||
HORIZ_SPACING = 5,
|
||||
|
|
|
@ -113,7 +113,6 @@ void OptionsGroup::add_undo_buttuns_to_sizer(wxSizer* sizer, const t_field& fiel
|
|||
}
|
||||
|
||||
void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = nullptr*/) {
|
||||
//! if (line.sizer != nullptr || (line.widget != nullptr && line.full_width > 0)) {
|
||||
if ( (line.sizer != nullptr || line.widget != nullptr) && line.full_width) {
|
||||
if (line.sizer != nullptr) {
|
||||
sizer->Add(line.sizer, 0, wxEXPAND | wxALL, wxOSX ? 0 : 15);
|
||||
|
@ -135,6 +134,7 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
|
||||
// if we have a single option with no label, no sidetext just add it directly to sizer
|
||||
if (option_set.size() == 1 && label_width == 0 && option_set.front().opt.full_width &&
|
||||
option_set.front().opt.label.empty() &&
|
||||
option_set.front().opt.sidetext.size() == 0 && option_set.front().side_widget == nullptr &&
|
||||
line.get_extra_widgets().size() == 0) {
|
||||
wxSizer* tmp_sizer;
|
||||
|
@ -179,12 +179,12 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
// Text is properly aligned only when Ellipsize is checked.
|
||||
label_style |= staticbox ? 0 : wxST_ELLIPSIZE_END;
|
||||
#endif /* __WXGTK__ */
|
||||
label = new wxStaticText(parent(), wxID_ANY, line.label + (line.label.IsEmpty() ? "" : ":"),
|
||||
label = new wxStaticText(parent(), wxID_ANY, line.label + (line.label.IsEmpty() ? "" : ": "),
|
||||
wxDefaultPosition, wxSize(label_width, -1), label_style);
|
||||
label->SetFont(label_font);
|
||||
label->Wrap(label_width); // avoid a Linux/GTK bug
|
||||
if (!line.near_label_widget)
|
||||
grid_sizer->Add(label, 0, (staticbox ? 0 : wxALIGN_RIGHT | wxRIGHT) | wxALIGN_CENTER_VERTICAL, 5);
|
||||
grid_sizer->Add(label, 0, (staticbox ? 0 : wxALIGN_RIGHT | wxRIGHT) | wxALIGN_CENTER_VERTICAL, line.label.IsEmpty() ? 0 : 5);
|
||||
else {
|
||||
// If we're here, we have some widget near the label
|
||||
// so we need a horizontal sizer to arrange these things
|
||||
|
@ -213,6 +213,7 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
grid_sizer->Add(sizer, 0, wxEXPAND | (staticbox ? wxALL : wxBOTTOM | wxTOP | wxLEFT), staticbox ? 0 : 1);
|
||||
// If we have a single option with no sidetext just add it directly to the grid sizer
|
||||
if (option_set.size() == 1 && option_set.front().opt.sidetext.size() == 0 &&
|
||||
option_set.front().opt.label.empty() &&
|
||||
option_set.front().side_widget == nullptr && line.get_extra_widgets().size() == 0) {
|
||||
const auto& option = option_set.front();
|
||||
const auto& field = build_field(option, label);
|
||||
|
@ -236,7 +237,7 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
wxString str_label = (option.label == "Top" || option.label == "Bottom") ?
|
||||
_CTX(option.label, "Layers") :
|
||||
_(option.label);
|
||||
label = new wxStaticText(parent(), wxID_ANY, str_label + ":", wxDefaultPosition, wxDefaultSize);
|
||||
label = new wxStaticText(parent(), wxID_ANY, str_label + ": ", wxDefaultPosition, wxDefaultSize);
|
||||
label->SetFont(label_font);
|
||||
sizer_tmp->Add(label, 0, /*wxALIGN_RIGHT |*/ wxALIGN_CENTER_VERTICAL, 0);
|
||||
}
|
||||
|
@ -245,6 +246,16 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
const Option& opt_ref = opt;
|
||||
auto& field = build_field(opt_ref, label);
|
||||
add_undo_buttuns_to_sizer(sizer_tmp, field);
|
||||
if (option_set.size() == 1 && option_set.front().opt.full_width)
|
||||
{
|
||||
const auto v_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
sizer_tmp->Add(v_sizer, 1, wxEXPAND);
|
||||
is_sizer_field(field) ?
|
||||
v_sizer->Add(field->getSizer(), 0, wxEXPAND) :
|
||||
v_sizer->Add(field->getWindow(), 0, wxEXPAND);
|
||||
return;
|
||||
}
|
||||
|
||||
is_sizer_field(field) ?
|
||||
sizer_tmp->Add(field->getSizer(), 0, wxALIGN_CENTER_VERTICAL, 0) :
|
||||
sizer_tmp->Add(field->getWindow(), 0, wxALIGN_CENTER_VERTICAL, 0);
|
||||
|
@ -269,7 +280,17 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
|
|||
}
|
||||
}
|
||||
// add extra sizers if any
|
||||
for (auto extra_widget : line.get_extra_widgets()) {
|
||||
for (auto extra_widget : line.get_extra_widgets())
|
||||
{
|
||||
if (line.get_extra_widgets().size() == 1 && !staticbox)
|
||||
{
|
||||
// extra widget for non-staticbox option group (like for the frequently used parameters on the sidebar) should be wxALIGN_RIGHT
|
||||
const auto v_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
sizer->Add(v_sizer, 1, wxEXPAND);
|
||||
v_sizer->Add(extra_widget(parent()), 0, wxALIGN_RIGHT);
|
||||
return;
|
||||
}
|
||||
|
||||
sizer->Add(extra_widget(parent())/*!.target<wxWindow>()*/, 0, wxLEFT | wxALIGN_CENTER_VERTICAL, 4); //! requires verification
|
||||
}
|
||||
}
|
||||
|
@ -593,7 +614,7 @@ Field* ConfigOptionsGroup::get_fieldc(const t_config_option_key& opt_key, int op
|
|||
void ogStaticText::SetText(const wxString& value, bool wrap/* = true*/)
|
||||
{
|
||||
SetLabel(value);
|
||||
if (wrap) Wrap(400);
|
||||
if (wrap) Wrap(40 * wxGetApp().em_unit());
|
||||
GetParent()->Layout();
|
||||
}
|
||||
|
||||
|
|
|
@ -82,7 +82,7 @@ class OptionsGroup {
|
|||
public:
|
||||
const bool staticbox {true};
|
||||
const wxString title {wxString("")};
|
||||
size_t label_width {200};
|
||||
size_t label_width = 20 * wxGetApp().em_unit();// {200};
|
||||
wxSizer* sizer {nullptr};
|
||||
column_t extra_column {nullptr};
|
||||
t_change m_on_change { nullptr };
|
||||
|
|
|
@ -212,7 +212,7 @@ void SlicedInfo::SetTextAndShow(SlisedInfoIdx idx, const wxString& text, const w
|
|||
}
|
||||
|
||||
PresetComboBox::PresetComboBox(wxWindow *parent, Preset::Type preset_type) :
|
||||
wxBitmapComboBox(parent, wxID_ANY, wxEmptyString, wxDefaultPosition, wxSize(200,-1), 0, nullptr, wxCB_READONLY),
|
||||
wxBitmapComboBox(parent, wxID_ANY, wxEmptyString, wxDefaultPosition, wxSize(15 * wxGetApp().em_unit(), -1), 0, nullptr, wxCB_READONLY),
|
||||
preset_type(preset_type),
|
||||
last_selected(wxNOT_FOUND)
|
||||
{
|
||||
|
@ -305,7 +305,7 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
|||
|
||||
// Frequently changed parameters for FFF_technology
|
||||
m_og->set_config(config);
|
||||
m_og->label_width = label_width;
|
||||
m_og->label_width = label_width == 0 ? 1 : label_width;
|
||||
|
||||
m_og->m_on_change = [config, this](t_config_option_key opt_key, boost::any value) {
|
||||
Tab* tab_print = wxGetApp().get_tab(Preset::TYPE_PRINT);
|
||||
|
@ -350,29 +350,35 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
|||
tab_print->update_dirty();
|
||||
};
|
||||
|
||||
Option option = m_og->get_option("fill_density");
|
||||
option.opt.sidetext = "";
|
||||
option.opt.full_width = true;
|
||||
m_og->append_single_option_line(option);
|
||||
|
||||
Line line = Line { "", "" };
|
||||
|
||||
ConfigOptionDef def;
|
||||
|
||||
def.label = L("Support");
|
||||
def.label = L("Supports");
|
||||
def.type = coStrings;
|
||||
def.gui_type = "select_open";
|
||||
def.tooltip = L("Select what kind of support do you need");
|
||||
def.enum_labels.push_back(L("None"));
|
||||
def.enum_labels.push_back(L("Support on build plate only"));
|
||||
def.enum_labels.push_back(L("Everywhere"));
|
||||
std::string selection = !config->opt_bool("support_material") ?
|
||||
"None" :
|
||||
config->opt_bool("support_material_buildplate_only") ?
|
||||
"Support on build plate only" :
|
||||
"Everywhere";
|
||||
const std::string selection = !config->opt_bool("support_material") ?
|
||||
"None" : config->opt_bool("support_material_buildplate_only") ?
|
||||
"Support on build plate only" :
|
||||
"Everywhere";
|
||||
def.default_value = new ConfigOptionStrings{ selection };
|
||||
option = Option(def, "support");
|
||||
Option option = Option(def, "support");
|
||||
option.opt.full_width = true;
|
||||
m_og->append_single_option_line(option);
|
||||
line.append_option(option);
|
||||
m_og->append_line(line);
|
||||
|
||||
|
||||
line = Line { "", "" };
|
||||
|
||||
option = m_og->get_option("fill_density");
|
||||
option.opt.label = L("Infill");
|
||||
option.opt.width = 7 * wxGetApp().em_unit();
|
||||
option.opt.sidetext = " ";
|
||||
line.append_option(option);
|
||||
|
||||
m_brim_width = config->opt_float("brim_width");
|
||||
def.label = L("Brim");
|
||||
|
@ -381,11 +387,10 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
|||
def.gui_type = "";
|
||||
def.default_value = new ConfigOptionBool{ m_brim_width > 0.0 ? true : false };
|
||||
option = Option(def, "brim");
|
||||
m_og->append_single_option_line(option);
|
||||
option.opt.sidetext = " ";
|
||||
line.append_option(option);
|
||||
|
||||
|
||||
Line line = { "", "" };
|
||||
line.widget = [config, this](wxWindow* parent) {
|
||||
auto wiping_dialog_btn = [config, this](wxWindow* parent) {
|
||||
m_wiping_dialog_button = new wxButton(parent, wxID_ANY, _(L("Purging volumes")) + dots, wxDefaultPosition, wxDefaultSize, wxBU_EXACTFIT);
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(m_wiping_dialog_button);
|
||||
|
@ -402,19 +407,20 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
|||
std::vector<float> extruders = dlg.get_extruders();
|
||||
(config.option<ConfigOptionFloats>("wiping_volumes_matrix"))->values = std::vector<double>(matrix.begin(), matrix.end());
|
||||
(config.option<ConfigOptionFloats>("wiping_volumes_extruders"))->values = std::vector<double>(extruders.begin(), extruders.end());
|
||||
wxPostEvent(parent, SimpleEvent(EVT_SCHEDULE_BACKGROUND_PROCESS, parent));
|
||||
wxPostEvent(parent, SimpleEvent(EVT_SCHEDULE_BACKGROUND_PROCESS, parent));
|
||||
}
|
||||
}));
|
||||
return sizer;
|
||||
};
|
||||
m_og->append_line(line);
|
||||
line.append_widget(wiping_dialog_btn);
|
||||
|
||||
m_og->append_line(line);
|
||||
|
||||
// Frequently changed parameters for SLA_technology
|
||||
m_og_sla = std::make_shared<ConfigOptionsGroup>(parent, "");
|
||||
DynamicPrintConfig* config_sla = &wxGetApp().preset_bundle->sla_prints.get_edited_preset().config;
|
||||
m_og_sla->set_config(config_sla);
|
||||
m_og_sla->label_width = label_width*2;
|
||||
m_og_sla->label_width = label_width == 0 ? 1 : label_width;
|
||||
|
||||
m_og_sla->m_on_change = [config_sla, this](t_config_option_key opt_key, boost::any value) {
|
||||
Tab* tab = wxGetApp().get_tab(Preset::TYPE_SLA_PRINT);
|
||||
|
@ -428,12 +434,22 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
|
|||
tab->update_dirty();
|
||||
};
|
||||
|
||||
m_og_sla->append_single_option_line("supports_enable");
|
||||
m_og_sla->append_single_option_line("pad_enable");
|
||||
|
||||
line = Line{ "", "" };
|
||||
|
||||
option = m_og_sla->get_option("supports_enable");
|
||||
option.opt.sidetext = " ";
|
||||
line.append_option(option);
|
||||
|
||||
option = m_og_sla->get_option("pad_enable");
|
||||
option.opt.sidetext = " ";
|
||||
line.append_option(option);
|
||||
|
||||
m_og_sla->append_line(line);
|
||||
|
||||
m_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
m_sizer->Add(m_og->sizer, 0, wxEXPAND);
|
||||
m_sizer->Add(m_og_sla->sizer, 0, wxEXPAND | wxTOP, 5);
|
||||
m_sizer->Add(m_og_sla->sizer, 0, wxEXPAND);
|
||||
}
|
||||
|
||||
|
||||
|
@ -518,7 +534,7 @@ void Sidebar::priv::show_preset_comboboxes()
|
|||
Sidebar::Sidebar(Plater *parent)
|
||||
: wxPanel(parent), p(new priv(parent))
|
||||
{
|
||||
p->scrolled = new wxScrolledWindow(this, wxID_ANY, wxDefaultPosition, wxSize(400, -1));
|
||||
p->scrolled = new wxScrolledWindow(this, wxID_ANY, wxDefaultPosition, wxSize(40 * wxGetApp().em_unit(), -1));
|
||||
p->scrolled->SetScrollbars(0, 20, 1, 2);
|
||||
|
||||
// Sizer in the scrolled area
|
||||
|
@ -526,26 +542,26 @@ Sidebar::Sidebar(Plater *parent)
|
|||
p->scrolled->SetSizer(scrolled_sizer);
|
||||
|
||||
// Sizer with buttons for mode changing
|
||||
p->mode_sizer = new PrusaModeSizer(p->scrolled);
|
||||
p->mode_sizer = new PrusaModeSizer(p->scrolled, 2 * wxGetApp().em_unit());
|
||||
|
||||
// The preset chooser
|
||||
p->sizer_presets = new wxFlexGridSizer(5, 2, 1, 2);
|
||||
p->sizer_presets->AddGrowableCol(1, 1);
|
||||
p->sizer_presets = new wxFlexGridSizer(10, 1, 1, 2);
|
||||
p->sizer_presets->AddGrowableCol(0, 1);
|
||||
p->sizer_presets->SetFlexibleDirection(wxBOTH);
|
||||
p->sizer_filaments = new wxBoxSizer(wxVERTICAL);
|
||||
|
||||
auto init_combo = [this](PresetComboBox **combo, wxString label, Preset::Type preset_type, bool filament) {
|
||||
auto *text = new wxStaticText(p->scrolled, wxID_ANY, label);
|
||||
auto *text = new wxStaticText(p->scrolled, wxID_ANY, label+" :");
|
||||
text->SetFont(wxGetApp().small_font());
|
||||
*combo = new PresetComboBox(p->scrolled, preset_type);
|
||||
|
||||
auto *sizer_presets = this->p->sizer_presets;
|
||||
auto *sizer_filaments = this->p->sizer_filaments;
|
||||
sizer_presets->Add(text, 0, wxALIGN_RIGHT | wxALIGN_CENTER_VERTICAL | wxRIGHT, 4);
|
||||
sizer_presets->Add(text, 0, wxALIGN_LEFT | wxEXPAND | wxRIGHT, 4);
|
||||
if (! filament) {
|
||||
sizer_presets->Add(*combo, 1, wxALIGN_CENTER_VERTICAL | wxEXPAND | wxBOTTOM, 1);
|
||||
sizer_presets->Add(*combo, 0, wxEXPAND | wxBOTTOM, 1);
|
||||
} else {
|
||||
sizer_filaments->Add(*combo, 1, wxEXPAND | wxBOTTOM, 1);
|
||||
sizer_filaments->Add(*combo, 0, wxEXPAND | wxBOTTOM, 1);
|
||||
(*combo)->set_extruder_idx(0);
|
||||
sizer_presets->Add(sizer_filaments, 1, wxEXPAND);
|
||||
}
|
||||
|
@ -559,29 +575,32 @@ Sidebar::Sidebar(Plater *parent)
|
|||
init_combo(&p->combo_printer, _(L("Printer")), Preset::TYPE_PRINTER, false);
|
||||
|
||||
// calculate width of the preset labels
|
||||
p->sizer_presets->Layout();
|
||||
const wxArrayInt& ar = p->sizer_presets->GetColWidths();
|
||||
int label_width = ar.IsEmpty() ? 100 : ar.front()-4;
|
||||
// p->sizer_presets->Layout();
|
||||
// const wxArrayInt& ar = p->sizer_presets->GetColWidths();
|
||||
// const int label_width = ar.IsEmpty() ? 10*wxGetApp().em_unit() : ar.front()-4;
|
||||
|
||||
const int margin_5 = int(0.5*wxGetApp().em_unit());// 5;
|
||||
const int margin_10 = int(1.5*wxGetApp().em_unit());// 15;
|
||||
|
||||
p->sizer_params = new wxBoxSizer(wxVERTICAL);
|
||||
|
||||
// Frequently changed parameters
|
||||
p->frequently_changed_parameters = new FreqChangedParams(p->scrolled, label_width);
|
||||
p->sizer_params->Add(p->frequently_changed_parameters->get_sizer(), 0, wxEXPAND | wxBOTTOM | wxLEFT, 2);
|
||||
p->frequently_changed_parameters = new FreqChangedParams(p->scrolled, 0/*label_width*/);
|
||||
p->sizer_params->Add(p->frequently_changed_parameters->get_sizer(), 0, wxEXPAND | wxTOP | wxBOTTOM, margin_10);
|
||||
|
||||
// Object List
|
||||
p->object_list = new ObjectList(p->scrolled);
|
||||
p->sizer_params->Add(p->object_list->get_sizer(), 1, wxEXPAND | wxTOP, 20);
|
||||
p->sizer_params->Add(p->object_list->get_sizer(), 1, wxEXPAND);
|
||||
|
||||
// Object Manipulations
|
||||
p->object_manipulation = new ObjectManipulation(p->scrolled);
|
||||
p->object_manipulation->Hide();
|
||||
p->sizer_params->Add(p->object_manipulation->get_sizer(), 0, wxEXPAND | wxLEFT | wxTOP, 20);
|
||||
p->sizer_params->Add(p->object_manipulation->get_sizer(), 0, wxEXPAND | wxTOP, margin_5);
|
||||
|
||||
// Frequently Object Settings
|
||||
p->object_settings = new ObjectSettings(p->scrolled);
|
||||
p->object_settings->Hide();
|
||||
p->sizer_params->Add(p->object_settings->get_sizer(), 0, wxEXPAND | wxLEFT | wxTOP, 20);
|
||||
p->sizer_params->Add(p->object_settings->get_sizer(), 0, wxEXPAND | wxTOP, margin_5);
|
||||
|
||||
wxBitmap arrow_up(GUI::from_u8(Slic3r::var("brick_go.png")), wxBITMAP_TYPE_PNG);
|
||||
p->btn_send_gcode = new wxButton(this, wxID_ANY, _(L("Send to printer")));
|
||||
|
@ -594,11 +613,11 @@ Sidebar::Sidebar(Plater *parent)
|
|||
p->sliced_info = new SlicedInfo(p->scrolled);
|
||||
|
||||
// Sizer in the scrolled area
|
||||
scrolled_sizer->Add(p->mode_sizer, 0, wxALIGN_RIGHT/*CENTER_HORIZONTAL*/ | wxBOTTOM | wxRIGHT, 5);
|
||||
scrolled_sizer->Add(p->sizer_presets, 0, wxEXPAND | wxLEFT, 2);
|
||||
scrolled_sizer->Add(p->sizer_params, 1, wxEXPAND);
|
||||
scrolled_sizer->Add(p->object_info, 0, wxEXPAND | wxTOP | wxLEFT, 20);
|
||||
scrolled_sizer->Add(p->sliced_info, 0, wxEXPAND | wxTOP | wxLEFT, 20);
|
||||
scrolled_sizer->Add(p->mode_sizer, 0, wxALIGN_CENTER_HORIZONTAL/*RIGHT | wxBOTTOM | wxRIGHT, 5*/);
|
||||
scrolled_sizer->Add(p->sizer_presets, 0, wxEXPAND | wxLEFT, margin_5);
|
||||
scrolled_sizer->Add(p->sizer_params, 1, wxEXPAND | wxLEFT, margin_5);
|
||||
scrolled_sizer->Add(p->object_info, 0, wxEXPAND | wxTOP | wxLEFT, margin_5);
|
||||
scrolled_sizer->Add(p->sliced_info, 0, wxEXPAND | wxTOP | wxLEFT, margin_5);
|
||||
|
||||
// Buttons underneath the scrolled area
|
||||
p->btn_export_gcode = new wxButton(this, wxID_ANY, _(L("Export G-code")) + dots);
|
||||
|
@ -608,13 +627,13 @@ Sidebar::Sidebar(Plater *parent)
|
|||
enable_buttons(false);
|
||||
|
||||
auto *btns_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
btns_sizer->Add(p->btn_reslice, 0, wxEXPAND | wxTOP, 5);
|
||||
btns_sizer->Add(p->btn_send_gcode, 0, wxEXPAND | wxTOP, 5);
|
||||
btns_sizer->Add(p->btn_export_gcode, 0, wxEXPAND | wxTOP, 5);
|
||||
btns_sizer->Add(p->btn_reslice, 0, wxEXPAND | wxTOP, margin_5);
|
||||
btns_sizer->Add(p->btn_send_gcode, 0, wxEXPAND | wxTOP, margin_5);
|
||||
btns_sizer->Add(p->btn_export_gcode, 0, wxEXPAND | wxTOP, margin_5);
|
||||
|
||||
auto *sizer = new wxBoxSizer(wxVERTICAL);
|
||||
sizer->Add(p->scrolled, 1, wxEXPAND | wxTOP, 5);
|
||||
sizer->Add(btns_sizer, 0, wxEXPAND | wxLEFT, 20);
|
||||
sizer->Add(p->scrolled, 1, wxEXPAND);
|
||||
sizer->Add(btns_sizer, 0, wxEXPAND | wxLEFT, margin_5);
|
||||
SetSizer(sizer);
|
||||
|
||||
// Events
|
||||
|
|
|
@ -15,7 +15,7 @@ void PreferencesDialog::build()
|
|||
{
|
||||
auto app_config = get_app_config();
|
||||
m_optgroup = std::make_shared<ConfigOptionsGroup>(this, _(L("General")));
|
||||
m_optgroup->label_width = 400;
|
||||
m_optgroup->label_width = 40 * wxGetApp().em_unit(); //400;
|
||||
m_optgroup->m_on_change = [this](t_config_option_key opt_key, boost::any value){
|
||||
m_values[opt_key] = boost::any_cast<bool>(value) ? "1" : "0";
|
||||
};
|
||||
|
|
|
@ -20,7 +20,7 @@ void Chart::draw() {
|
|||
dc.DrawRectangle(m_rect);
|
||||
|
||||
if (visible_area.m_width < 0.499) {
|
||||
dc.DrawText(_(L("NO RAMMING AT ALL")),wxPoint(m_rect.GetLeft()+m_rect.GetWidth()/2-50,m_rect.GetBottom()-m_rect.GetHeight()/2));
|
||||
dc.DrawText(_(L("NO RAMMING AT ALL")),wxPoint(m_rect.GetLeft()+m_rect.GetWidth()/2-legend_side,m_rect.GetBottom()-m_rect.GetHeight()/2));
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -55,9 +55,9 @@ void Chart::draw() {
|
|||
for (float math_x=int(visible_area.m_x*10)/10 ; math_x < (visible_area.m_x+visible_area.m_width) ; math_x+=0.1f) {
|
||||
int x = math_to_screen(wxPoint2DDouble(math_x,visible_area.m_y)).x;
|
||||
int y = m_rect.GetBottom();
|
||||
if (x-last_mark < 50) continue;
|
||||
if (x-last_mark < legend_side) continue;
|
||||
dc.DrawLine(x,y+3,x,y-3);
|
||||
dc.DrawText(wxString().Format(wxT("%.1f"), math_x),wxPoint(x-10,y+7));
|
||||
dc.DrawText(wxString().Format(wxT("%.1f"), math_x),wxPoint(x-scale_unit,y+0.5*scale_unit));
|
||||
last_mark = x;
|
||||
}
|
||||
|
||||
|
@ -66,9 +66,9 @@ void Chart::draw() {
|
|||
for (int math_y=visible_area.m_y ; math_y < (visible_area.m_y+visible_area.m_height) ; math_y+=1) {
|
||||
int y = math_to_screen(wxPoint2DDouble(visible_area.m_x,math_y)).y;
|
||||
int x = m_rect.GetLeft();
|
||||
if (last_mark-y < 50) continue;
|
||||
if (last_mark-y < legend_side) continue;
|
||||
dc.DrawLine(x-3,y,x+3,y);
|
||||
dc.DrawText(wxString()<<math_y,wxPoint(x-25,y-2/*7*/));
|
||||
dc.DrawText(wxString()<<math_y,wxPoint(x-2*scale_unit,y-0.5*scale_unit));
|
||||
last_mark = y;
|
||||
}
|
||||
|
||||
|
@ -77,7 +77,7 @@ void Chart::draw() {
|
|||
int text_width = 0;
|
||||
int text_height = 0;
|
||||
dc.GetTextExtent(label,&text_width,&text_height);
|
||||
dc.DrawText(label,wxPoint(0.5*(m_rect.GetRight()+m_rect.GetLeft())-text_width/2.f, m_rect.GetBottom()+25));
|
||||
dc.DrawText(label,wxPoint(0.5*(m_rect.GetRight()+m_rect.GetLeft())-text_width/2.f, m_rect.GetBottom()+0.5*legend_side));
|
||||
label = _(L("Volumetric speed")) + " (" + _(L("mm")) + wxString("³/", wxConvUTF8) + _(L("s")) + ")";
|
||||
dc.GetTextExtent(label,&text_width,&text_height);
|
||||
dc.DrawRotatedText(label,wxPoint(0,0.5*(m_rect.GetBottom()+m_rect.GetTop())+text_width/2.f),90);
|
||||
|
|
|
@ -13,11 +13,12 @@ wxDECLARE_EVENT(EVT_WIPE_TOWER_CHART_CHANGED, wxCommandEvent);
|
|||
class Chart : public wxWindow {
|
||||
|
||||
public:
|
||||
Chart(wxWindow* parent, wxRect rect,const std::vector<std::pair<float,float>>& initial_buttons,int ramming_speed_size, float sampling) :
|
||||
wxWindow(parent,wxID_ANY,rect.GetTopLeft(),rect.GetSize())
|
||||
Chart(wxWindow* parent, wxRect rect,const std::vector<std::pair<float,float>>& initial_buttons,int ramming_speed_size, float sampling, int scale_unit=10) :
|
||||
wxWindow(parent,wxID_ANY,rect.GetTopLeft(),rect.GetSize()),
|
||||
scale_unit(scale_unit), legend_side(5*scale_unit)
|
||||
{
|
||||
SetBackgroundStyle(wxBG_STYLE_PAINT);
|
||||
m_rect = wxRect(wxPoint(50,0),rect.GetSize()-wxSize(50,50));
|
||||
m_rect = wxRect(wxPoint(legend_side,0),rect.GetSize()-wxSize(legend_side,legend_side));
|
||||
visible_area = wxRect2DDouble(0.0, 0.0, sampling*ramming_speed_size, 20.);
|
||||
m_buttons.clear();
|
||||
if (initial_buttons.size()>0)
|
||||
|
@ -49,6 +50,7 @@ public:
|
|||
DECLARE_EVENT_TABLE()
|
||||
|
||||
|
||||
|
||||
|
||||
private:
|
||||
static const bool fixed_x = true;
|
||||
|
@ -56,6 +58,9 @@ private:
|
|||
static const bool manual_points_manipulation = false;
|
||||
static const int side = 10; // side of draggable button
|
||||
|
||||
const int scale_unit;
|
||||
int legend_side;
|
||||
|
||||
class ButtonToDrag {
|
||||
public:
|
||||
bool operator<(const ButtonToDrag& a) const { return m_pos.m_x < a.m_pos.m_x; }
|
||||
|
|
|
@ -7,6 +7,8 @@
|
|||
|
||||
#include <wx/clipbrd.h>
|
||||
#include <wx/platinfo.h>
|
||||
#include "GUI_App.hpp"
|
||||
#include "wxExtensions.hpp"
|
||||
|
||||
namespace Slic3r {
|
||||
namespace GUI {
|
||||
|
@ -44,15 +46,16 @@ SysInfoDialog::SysInfoDialog()
|
|||
wxColour bgr_clr = wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW);
|
||||
SetBackgroundColour(bgr_clr);
|
||||
wxBoxSizer* hsizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
hsizer->SetMinSize(wxSize(600, -1));
|
||||
hsizer->SetMinSize(wxSize(50 * wxGetApp().em_unit(), -1));
|
||||
|
||||
auto main_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
main_sizer->Add(hsizer, 0, wxEXPAND | wxALL, 10);
|
||||
main_sizer->Add(hsizer, 1, wxEXPAND | wxALL, 10);
|
||||
|
||||
// logo
|
||||
wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG);
|
||||
auto *logo = new wxStaticBitmap(this, wxID_ANY, std::move(logo_bmp));
|
||||
hsizer->Add(logo, 0, wxEXPAND | wxTOP | wxBOTTOM, 15);
|
||||
// wxBitmap logo_bmp = wxBitmap(from_u8(Slic3r::var("Slic3r_192px.png")), wxBITMAP_TYPE_PNG);
|
||||
// auto *logo = new wxStaticBitmap(this, wxID_ANY, std::move(logo_bmp));
|
||||
auto *logo = new wxStaticBitmap(this, wxID_ANY, create_scaled_bitmap("Slic3r_192px.png"));
|
||||
hsizer->Add(logo, 0, wxALIGN_CENTER_VERTICAL);
|
||||
|
||||
wxBoxSizer* vsizer = new wxBoxSizer(wxVERTICAL);
|
||||
hsizer->Add(vsizer, 1, wxEXPAND|wxLEFT, 20);
|
||||
|
@ -65,7 +68,7 @@ SysInfoDialog::SysInfoDialog()
|
|||
title_font.SetFamily(wxFONTFAMILY_ROMAN);
|
||||
title_font.SetPointSize(22);
|
||||
title->SetFont(title_font);
|
||||
vsizer->Add(title, 0, wxALIGN_LEFT | wxTOP, 50);
|
||||
vsizer->Add(title, 0, wxEXPAND | wxALIGN_LEFT | wxTOP, wxGetApp().em_unit()/*50*/);
|
||||
}
|
||||
|
||||
// main_info_text
|
||||
|
@ -91,13 +94,13 @@ SysInfoDialog::SysInfoDialog()
|
|||
"</html>", bgr_clr_str, text_clr_str, text_clr_str,
|
||||
get_main_info(true));
|
||||
html->SetPage(text);
|
||||
vsizer->Add(html, 1, wxEXPAND);
|
||||
vsizer->Add(html, 1, wxEXPAND | wxBOTTOM, wxGetApp().em_unit());
|
||||
}
|
||||
|
||||
// opengl_info
|
||||
wxHtmlWindow* opengl_info_html = new wxHtmlWindow(this, wxID_ANY, wxDefaultPosition, wxDefaultSize, wxHW_SCROLLBAR_AUTO);
|
||||
{
|
||||
opengl_info_html->SetMinSize(wxSize(-1, 200));
|
||||
opengl_info_html->SetMinSize(wxSize(-1, 16 * wxGetApp().em_unit()));
|
||||
opengl_info_html->SetFonts(font.GetFaceName(), font.GetFaceName(), size);
|
||||
opengl_info_html->SetBorders(10);
|
||||
const auto text = wxString::Format(
|
||||
|
|
|
@ -56,6 +56,8 @@ Tab::Tab(wxNotebook* parent, const wxString& title, const char* name) :
|
|||
m_compatible_prints.dialog_label = _(L("Select the print profiles this profile is compatible with."));
|
||||
|
||||
wxGetApp().tabs_list.push_back(this);
|
||||
|
||||
m_em_unit = wxGetApp().em_unit();
|
||||
}
|
||||
|
||||
void Tab::set_type()
|
||||
|
@ -96,22 +98,26 @@ void Tab::create_preset_tab()
|
|||
#endif //__WXOSX__
|
||||
|
||||
// preset chooser
|
||||
m_presets_choice = new wxBitmapComboBox(panel, wxID_ANY, "", wxDefaultPosition, wxSize(270, -1), 0, 0,wxCB_READONLY);
|
||||
m_presets_choice = new wxBitmapComboBox(panel, wxID_ANY, "", wxDefaultPosition, wxSize(25 * m_em_unit, -1), 0, 0, wxCB_READONLY);
|
||||
|
||||
auto color = wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW);
|
||||
|
||||
//buttons
|
||||
wxBitmap bmpMenu;
|
||||
bmpMenu = wxBitmap(from_u8(Slic3r::var("disk.png")), wxBITMAP_TYPE_PNG);
|
||||
// bmpMenu = wxBitmap(from_u8(Slic3r::var("disk.png")), wxBITMAP_TYPE_PNG);
|
||||
bmpMenu = create_scaled_bitmap("disk.png");
|
||||
m_btn_save_preset = new wxBitmapButton(panel, wxID_ANY, bmpMenu, wxDefaultPosition, wxDefaultSize, wxBORDER_NONE);
|
||||
if (wxMSW) m_btn_save_preset->SetBackgroundColour(color);
|
||||
bmpMenu = wxBitmap(from_u8(Slic3r::var("delete.png")), wxBITMAP_TYPE_PNG);
|
||||
// bmpMenu = wxBitmap(from_u8(Slic3r::var("delete.png")), wxBITMAP_TYPE_PNG);
|
||||
bmpMenu = create_scaled_bitmap("delete.png");
|
||||
m_btn_delete_preset = new wxBitmapButton(panel, wxID_ANY, bmpMenu, wxDefaultPosition, wxDefaultSize, wxBORDER_NONE);
|
||||
if (wxMSW) m_btn_delete_preset->SetBackgroundColour(color);
|
||||
|
||||
m_show_incompatible_presets = false;
|
||||
m_bmp_show_incompatible_presets.LoadFile(from_u8(Slic3r::var("flag-red-icon.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_hide_incompatible_presets.LoadFile(from_u8(Slic3r::var("flag-green-icon.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_show_incompatible_presets.LoadFile(from_u8(Slic3r::var("flag-red-icon.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_hide_incompatible_presets.LoadFile(from_u8(Slic3r::var("flag-green-icon.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_show_incompatible_presets = create_scaled_bitmap("flag-red-icon.png");
|
||||
m_bmp_hide_incompatible_presets = create_scaled_bitmap("flag-green-icon.png");
|
||||
m_btn_hide_incompatible_presets = new wxBitmapButton(panel, wxID_ANY, m_bmp_hide_incompatible_presets, wxDefaultPosition, wxDefaultSize, wxBORDER_NONE);
|
||||
if (wxMSW) m_btn_hide_incompatible_presets->SetBackgroundColour(color);
|
||||
|
||||
|
@ -134,13 +140,18 @@ void Tab::create_preset_tab()
|
|||
// Determine the theme color of OS (dark or light)
|
||||
auto luma = wxGetApp().get_colour_approx_luma(wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW));
|
||||
// Bitmaps to be shown on the "Revert to system" aka "Lock to system" button next to each input field.
|
||||
m_bmp_value_lock .LoadFile(from_u8(var("sys_lock.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_value_unlock .LoadFile(from_u8(var(luma >= 128 ? "sys_unlock.png" : "sys_unlock_grey.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_value_lock .LoadFile(from_u8(var("sys_lock.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_value_unlock .LoadFile(from_u8(var(luma >= 128 ? "sys_unlock.png" : "sys_unlock_grey.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_value_lock = create_scaled_bitmap("sys_lock.png");
|
||||
m_bmp_value_unlock = create_scaled_bitmap(luma >= 128 ? "sys_unlock.png" : "sys_unlock_grey.png");
|
||||
m_bmp_non_system = &m_bmp_white_bullet;
|
||||
// Bitmaps to be shown on the "Undo user changes" button next to each input field.
|
||||
m_bmp_value_revert .LoadFile(from_u8(var(luma >= 128 ? "action_undo.png" : "action_undo_grey.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_white_bullet .LoadFile(from_u8(var("bullet_white.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_question .LoadFile(from_u8(var("question_mark_01.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_value_revert .LoadFile(from_u8(var(luma >= 128 ? "action_undo.png" : "action_undo_grey.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_white_bullet .LoadFile(from_u8(var("bullet_white.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_question .LoadFile(from_u8(var("question_mark_01.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_value_revert = create_scaled_bitmap(luma >= 128 ? "action_undo.png" : "action_undo_grey.png");
|
||||
m_bmp_white_bullet = create_scaled_bitmap("bullet_white.png");
|
||||
m_bmp_question = create_scaled_bitmap("question_mark_01.png");
|
||||
|
||||
fill_icon_descriptions();
|
||||
set_tooltips_text();
|
||||
|
@ -171,19 +182,20 @@ void Tab::create_preset_tab()
|
|||
// Sizer with buttons for mode changing
|
||||
m_mode_sizer = new PrusaModeSizer(panel);
|
||||
|
||||
const float scale_factor = wxGetApp().em_unit()*0.1;// GetContentScaleFactor();
|
||||
m_hsizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(m_hsizer, 0, wxEXPAND | wxBOTTOM, 3);
|
||||
m_hsizer->Add(m_presets_choice, 0, wxLEFT | wxRIGHT | wxTOP | wxALIGN_CENTER_VERTICAL, 3);
|
||||
m_hsizer->AddSpacer(4);
|
||||
m_hsizer->AddSpacer(int(4*scale_factor));
|
||||
m_hsizer->Add(m_btn_save_preset, 0, wxALIGN_CENTER_VERTICAL);
|
||||
m_hsizer->AddSpacer(4);
|
||||
m_hsizer->AddSpacer(int(4 * scale_factor));
|
||||
m_hsizer->Add(m_btn_delete_preset, 0, wxALIGN_CENTER_VERTICAL);
|
||||
m_hsizer->AddSpacer(16);
|
||||
m_hsizer->AddSpacer(int(16 * scale_factor));
|
||||
m_hsizer->Add(m_btn_hide_incompatible_presets, 0, wxALIGN_CENTER_VERTICAL);
|
||||
m_hsizer->AddSpacer(64);
|
||||
m_hsizer->AddSpacer(int(64 * scale_factor));
|
||||
m_hsizer->Add(m_undo_to_sys_btn, 0, wxALIGN_CENTER_VERTICAL);
|
||||
m_hsizer->Add(m_undo_btn, 0, wxALIGN_CENTER_VERTICAL);
|
||||
m_hsizer->AddSpacer(32);
|
||||
m_hsizer->AddSpacer(int(32 * scale_factor));
|
||||
m_hsizer->Add(m_question_btn, 0, wxALIGN_CENTER_VERTICAL);
|
||||
// m_hsizer->AddStretchSpacer(32);
|
||||
// StretchSpacer has a strange behavior under OSX, so
|
||||
|
@ -201,10 +213,10 @@ void Tab::create_preset_tab()
|
|||
m_hsizer->Add(m_left_sizer, 0, wxEXPAND | wxLEFT | wxTOP | wxBOTTOM, 3);
|
||||
|
||||
// tree
|
||||
m_treectrl = new wxTreeCtrl(panel, wxID_ANY, wxDefaultPosition, wxSize(185, -1),
|
||||
m_treectrl = new wxTreeCtrl(panel, wxID_ANY, wxDefaultPosition, wxSize(20 * m_em_unit, -1),
|
||||
wxTR_NO_BUTTONS | wxTR_HIDE_ROOT | wxTR_SINGLE | wxTR_NO_LINES | wxBORDER_SUNKEN | wxWANTS_CHARS);
|
||||
m_left_sizer->Add(m_treectrl, 1, wxEXPAND);
|
||||
m_icons = new wxImageList(16, 16, true, 1);
|
||||
m_icons = new wxImageList(int(16 * scale_factor), int(16 * scale_factor), true, 1);
|
||||
// Index of the last icon inserted into $self->{icons}.
|
||||
m_icon_count = -1;
|
||||
m_treectrl->AssignImageList(m_icons);
|
||||
|
@ -263,8 +275,9 @@ Slic3r::GUI::PageShp Tab::add_options_page(const wxString& title, const std::str
|
|||
icon_idx = (m_icon_index.find(icon) == m_icon_index.end()) ? -1 : m_icon_index.at(icon);
|
||||
if (icon_idx == -1) {
|
||||
// Add a new icon to the icon list.
|
||||
wxIcon img_icon(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG);
|
||||
m_icons->Add(img_icon);
|
||||
// wxIcon img_icon(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG);
|
||||
// m_icons->Add(img_icon);
|
||||
m_icons->Add(create_scaled_bitmap(icon));
|
||||
icon_idx = ++m_icon_count;
|
||||
m_icon_index[icon] = icon_idx;
|
||||
}
|
||||
|
@ -497,7 +510,7 @@ void TabSLAMaterial::init_options_list()
|
|||
|
||||
void Tab::get_sys_and_mod_flags(const std::string& opt_key, bool& sys_page, bool& modified_page)
|
||||
{
|
||||
auto opt = m_options_list.find(opt_key);
|
||||
auto opt = m_options_list.find(opt_key);
|
||||
if (sys_page) sys_page = (opt->second & osSystemValue) != 0;
|
||||
modified_page |= (opt->second & osInitValue) == 0;
|
||||
}
|
||||
|
@ -1111,14 +1124,14 @@ void TabPrint::build()
|
|||
optgroup = page->new_optgroup(_(L("Post-processing scripts")), 0);
|
||||
option = optgroup->get_option("post_process");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 50;
|
||||
option.opt.height = 5 * m_em_unit;//50;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Notes")), "note.png");
|
||||
optgroup = page->new_optgroup(_(L("Notes")), 0);
|
||||
option = optgroup->get_option("notes");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 250;
|
||||
option.opt.height = 25 * m_em_unit;//250;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Dependencies")), "wrench.png");
|
||||
|
@ -1474,18 +1487,20 @@ void TabFilament::build()
|
|||
};
|
||||
optgroup->append_line(line);
|
||||
|
||||
const int gcode_field_height = 15 * m_em_unit; // 150
|
||||
const int notes_field_height = 25 * m_em_unit; // 250
|
||||
|
||||
page = add_options_page(_(L("Custom G-code")), "cog.png");
|
||||
optgroup = page->new_optgroup(_(L("Start G-code")), 0);
|
||||
Option option = optgroup->get_option("start_filament_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;// 150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("End G-code")), 0);
|
||||
option = optgroup->get_option("end_filament_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;// 150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Notes")), "note.png");
|
||||
|
@ -1493,7 +1508,7 @@ void TabFilament::build()
|
|||
optgroup->label_width = 0;
|
||||
option = optgroup->get_option("filament_notes");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 250;
|
||||
option.opt.height = notes_field_height;// 250;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Dependencies")), "wrench.png");
|
||||
|
@ -1594,7 +1609,8 @@ void TabPrinter::build_printhost(ConfigOptionsGroup *optgroup)
|
|||
// TODO: SLA Bonjour
|
||||
|
||||
auto btn = m_printhost_browse_btn = new wxButton(parent, wxID_ANY, _(L(" Browse "))+dots, wxDefaultPosition, wxDefaultSize, wxBU_LEFT);
|
||||
btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("zoom.png")), wxBITMAP_TYPE_PNG));
|
||||
// btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("zoom.png")), wxBITMAP_TYPE_PNG));
|
||||
btn->SetBitmap(create_scaled_bitmap("zoom.png"));
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(btn);
|
||||
|
||||
|
@ -1612,7 +1628,8 @@ void TabPrinter::build_printhost(ConfigOptionsGroup *optgroup)
|
|||
auto print_host_test = [this](wxWindow* parent) {
|
||||
auto btn = m_print_host_test_btn = new wxButton(parent, wxID_ANY, _(L("Test")),
|
||||
wxDefaultPosition, wxDefaultSize, wxBU_LEFT | wxBU_EXACTFIT);
|
||||
btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("wrench.png")), wxBITMAP_TYPE_PNG));
|
||||
// btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("wrench.png")), wxBITMAP_TYPE_PNG));
|
||||
btn->SetBitmap(create_scaled_bitmap("wrench.png"));
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(btn);
|
||||
|
||||
|
@ -1648,7 +1665,8 @@ void TabPrinter::build_printhost(ConfigOptionsGroup *optgroup)
|
|||
|
||||
auto printhost_cafile_browse = [this, optgroup] (wxWindow* parent) {
|
||||
auto btn = new wxButton(parent, wxID_ANY, _(L(" Browse "))+dots, wxDefaultPosition, wxDefaultSize, wxBU_LEFT);
|
||||
btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("zoom.png")), wxBITMAP_TYPE_PNG));
|
||||
// btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("zoom.png")), wxBITMAP_TYPE_PNG));
|
||||
btn->SetBitmap(create_scaled_bitmap("zoom.png"));
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(btn);
|
||||
|
||||
|
@ -1725,7 +1743,8 @@ void TabPrinter::build_fff()
|
|||
line.widget = [this](wxWindow* parent) {
|
||||
auto btn = new wxButton(parent, wxID_ANY, _(L(" Set "))+dots, wxDefaultPosition, wxDefaultSize, wxBU_LEFT | wxBU_EXACTFIT);
|
||||
btn->SetFont(wxGetApp().small_font());
|
||||
btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
// btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
btn->SetBitmap(create_scaled_bitmap("printer_empty.png"));
|
||||
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(btn);
|
||||
|
@ -1852,48 +1871,50 @@ void TabPrinter::build_fff()
|
|||
optgroup->append_single_option_line("use_volumetric_e");
|
||||
optgroup->append_single_option_line("variable_layer_height");
|
||||
|
||||
const int gcode_field_height = 15 * m_em_unit; // 150
|
||||
const int notes_field_height = 25 * m_em_unit; // 250
|
||||
page = add_options_page(_(L("Custom G-code")), "cog.png");
|
||||
optgroup = page->new_optgroup(_(L("Start G-code")), 0);
|
||||
option = optgroup->get_option("start_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("End G-code")), 0);
|
||||
option = optgroup->get_option("end_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("Before layer change G-code")), 0);
|
||||
option = optgroup->get_option("before_layer_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("After layer change G-code")), 0);
|
||||
option = optgroup->get_option("layer_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("Tool change G-code")), 0);
|
||||
option = optgroup->get_option("toolchange_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
optgroup = page->new_optgroup(_(L("Between objects G-code (for sequential printing)")), 0);
|
||||
option = optgroup->get_option("between_objects_gcode");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 150;
|
||||
option.opt.height = gcode_field_height;//150;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Notes")), "note.png");
|
||||
optgroup = page->new_optgroup(_(L("Notes")), 0);
|
||||
option = optgroup->get_option("printer_notes");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 250;
|
||||
option.opt.height = notes_field_height;//250;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Dependencies")), "wrench.png");
|
||||
|
@ -1924,7 +1945,8 @@ void TabPrinter::build_sla()
|
|||
line.widget = [this](wxWindow* parent) {
|
||||
auto btn = new wxButton(parent, wxID_ANY, _(L(" Set ")) + dots, wxDefaultPosition, wxDefaultSize, wxBU_LEFT | wxBU_EXACTFIT);
|
||||
// btn->SetFont(Slic3r::GUI::small_font);
|
||||
btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
// btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
btn->SetBitmap(create_scaled_bitmap("printer_empty.png"));
|
||||
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add(btn);
|
||||
|
@ -1970,11 +1992,13 @@ void TabPrinter::build_sla()
|
|||
optgroup = page->new_optgroup(_(L("Print Host upload")));
|
||||
build_printhost(optgroup.get());
|
||||
|
||||
const int notes_field_height = 25 * m_em_unit; // 250
|
||||
|
||||
page = add_options_page(_(L("Notes")), "note.png");
|
||||
optgroup = page->new_optgroup(_(L("Notes")), 0);
|
||||
option = optgroup->get_option("printer_notes");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 250;
|
||||
option.opt.height = notes_field_height;//250;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Dependencies")), "wrench.png");
|
||||
|
@ -2023,7 +2047,7 @@ PageShp TabPrinter::build_kinematics_page()
|
|||
// Legend for OptionsGroups
|
||||
auto optgroup = page->new_optgroup("");
|
||||
optgroup->set_show_modified_btns_val(false);
|
||||
optgroup->label_width = 230;
|
||||
optgroup->label_width = 23 * m_em_unit;// 230;
|
||||
auto line = Line{ "", "" };
|
||||
|
||||
ConfigOptionDef def;
|
||||
|
@ -2800,7 +2824,8 @@ wxSizer* Tab::compatible_widget_create(wxWindow* parent, PresetDependencies &dep
|
|||
deps.checkbox = new wxCheckBox(parent, wxID_ANY, _(L("All")));
|
||||
deps.btn = new wxButton(parent, wxID_ANY, _(L(" Set "))+dots, wxDefaultPosition, wxDefaultSize, wxBU_LEFT | wxBU_EXACTFIT);
|
||||
|
||||
deps.btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
// deps.btn->SetBitmap(wxBitmap(from_u8(Slic3r::var("printer_empty.png")), wxBITMAP_TYPE_PNG));
|
||||
deps.btn->SetBitmap(create_scaled_bitmap("printer_empty.png"));
|
||||
|
||||
auto sizer = new wxBoxSizer(wxHORIZONTAL);
|
||||
sizer->Add((deps.checkbox), 0, wxALIGN_CENTER_VERTICAL);
|
||||
|
@ -2991,7 +3016,8 @@ ConfigOptionsGroupShp Page::new_optgroup(const wxString& title, int noncommon_la
|
|||
bmp_name = mode == comExpert ? "mode_expert_.png" :
|
||||
mode == comAdvanced ? "mode_middle_.png" : "mode_simple_.png";
|
||||
}
|
||||
auto bmp = new wxStaticBitmap(parent, wxID_ANY, bmp_name.empty() ? wxNullBitmap : wxBitmap(from_u8(var(bmp_name)), wxBITMAP_TYPE_PNG));
|
||||
// auto bmp = new wxStaticBitmap(parent, wxID_ANY, bmp_name.empty() ? wxNullBitmap : wxBitmap(from_u8(var(bmp_name)), wxBITMAP_TYPE_PNG));
|
||||
auto bmp = new wxStaticBitmap(parent, wxID_ANY, bmp_name.empty() ? wxNullBitmap : create_scaled_bitmap(bmp_name));
|
||||
return bmp;
|
||||
};
|
||||
|
||||
|
@ -3109,7 +3135,7 @@ void TabSLAMaterial::build()
|
|||
optgroup->append_single_option_line("initial_exposure_time");
|
||||
|
||||
optgroup = page->new_optgroup(_(L("Corrections")));
|
||||
optgroup->label_width = 190;
|
||||
optgroup->label_width = 19 * m_em_unit;//190;
|
||||
std::vector<std::string> corrections = { "material_correction_printing", "material_correction_curing" };
|
||||
std::vector<std::string> axes{ "X", "Y", "Z" };
|
||||
for (auto& opt_key : corrections) {
|
||||
|
@ -3130,7 +3156,7 @@ void TabSLAMaterial::build()
|
|||
optgroup->label_width = 0;
|
||||
Option option = optgroup->get_option("material_notes");
|
||||
option.opt.full_width = true;
|
||||
option.opt.height = 250;
|
||||
option.opt.height = 25 * m_em_unit;//250;
|
||||
optgroup->append_single_option_line(option);
|
||||
|
||||
page = add_options_page(_(L("Dependencies")), "wrench.png");
|
||||
|
|
|
@ -203,6 +203,7 @@ protected:
|
|||
|
||||
void set_type();
|
||||
|
||||
int m_em_unit;
|
||||
std::set<std::string> m_dirty_options = {};
|
||||
|
||||
public:
|
||||
|
|
|
@ -3,9 +3,13 @@
|
|||
#include "WipeTowerDialog.hpp"
|
||||
#include "GUI.hpp"
|
||||
#include "I18N.hpp"
|
||||
#include "GUI_App.hpp"
|
||||
|
||||
#include <wx/sizer.h>
|
||||
|
||||
int scale(const int val) { return val * Slic3r::GUI::wxGetApp().em_unit(); }
|
||||
int ITEM_WIDTH() { return scale(6); }
|
||||
|
||||
RammingDialog::RammingDialog(wxWindow* parent,const std::string& parameters)
|
||||
: wxDialog(parent, wxID_ANY, _(L("Ramming customization")), wxDefaultPosition, wxDefaultSize, wxDEFAULT_DIALOG_STYLE/* | wxRESIZE_BORDER*/)
|
||||
{
|
||||
|
@ -65,14 +69,14 @@ RammingPanel::RammingPanel(wxWindow* parent, const std::string& parameters)
|
|||
while (stream >> x >> y)
|
||||
buttons.push_back(std::make_pair(x, y));
|
||||
|
||||
m_chart = new Chart(this, wxRect(10, 10, 480, 360), buttons, ramming_speed_size, 0.25f);
|
||||
m_chart = new Chart(this, wxRect(scale(1),scale(1),scale(48),scale(36)), buttons, ramming_speed_size, 0.25f, scale(1));
|
||||
m_chart->SetBackgroundColour(parent->GetBackgroundColour()); // see comment in RammingDialog constructor
|
||||
sizer_chart->Add(m_chart, 0, wxALL, 5);
|
||||
|
||||
m_widget_time = new wxSpinCtrlDouble(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(75, -1),wxSP_ARROW_KEYS,0.,5.0,3.,0.5);
|
||||
m_widget_volume = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(75, -1),wxSP_ARROW_KEYS,0,10000,0);
|
||||
m_widget_ramming_line_width_multiplicator = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(75, -1),wxSP_ARROW_KEYS,10,200,100);
|
||||
m_widget_ramming_step_multiplicator = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(75, -1),wxSP_ARROW_KEYS,10,200,100);
|
||||
m_widget_time = new wxSpinCtrlDouble(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS,0.,5.0,3.,0.5);
|
||||
m_widget_volume = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS,0,10000,0);
|
||||
m_widget_ramming_line_width_multiplicator = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS,10,200,100);
|
||||
m_widget_ramming_step_multiplicator = new wxSpinCtrl(this,wxID_ANY,wxEmptyString,wxDefaultPosition,wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS,10,200,100);
|
||||
|
||||
auto gsizer_param = new wxFlexGridSizer(2, 5, 15);
|
||||
gsizer_param->Add(new wxStaticText(this, wxID_ANY, wxString(_(L("Total ramming time")) + " (" + _(L("s")) + "):")), 0, wxALIGN_CENTER_VERTICAL);
|
||||
|
@ -86,7 +90,7 @@ RammingPanel::RammingPanel(wxWindow* parent, const std::string& parameters)
|
|||
gsizer_param->Add(new wxStaticText(this, wxID_ANY, wxString(_(L("Ramming line spacing")) + " (%):")), 0, wxALIGN_CENTER_VERTICAL);
|
||||
gsizer_param->Add(m_widget_ramming_step_multiplicator);
|
||||
|
||||
sizer_param->Add(gsizer_param, 0, wxTOP, 100);
|
||||
sizer_param->Add(gsizer_param, 0, wxTOP, scale(10));
|
||||
|
||||
m_widget_time->SetValue(m_chart->get_time());
|
||||
m_widget_time->SetDigits(2);
|
||||
|
@ -132,7 +136,6 @@ std::string RammingPanel::get_parameters()
|
|||
}
|
||||
|
||||
|
||||
#define ITEM_WIDTH 60
|
||||
// Parent dialog for purging volume adjustments - it fathers WipingPanel widget (that contains all controls) and a button to toggle simple/advanced mode:
|
||||
WipingDialog::WipingDialog(wxWindow* parent,const std::vector<float>& matrix, const std::vector<float>& extruders)
|
||||
: wxDialog(parent, wxID_ANY, _(L("Wipe tower - Purging volume adjustment")), wxDefaultPosition, wxDefaultSize, wxDEFAULT_DIALOG_STYLE/* | wxRESIZE_BORDER*/)
|
||||
|
@ -143,7 +146,7 @@ WipingDialog::WipingDialog(wxWindow* parent,const std::vector<float>& matrix, co
|
|||
auto main_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
|
||||
// set min sizer width according to extruders count
|
||||
const auto sizer_width = (int)((sqrt(matrix.size()) + 2.8)*ITEM_WIDTH);
|
||||
const auto sizer_width = (int)((sqrt(matrix.size()) + 2.8)*ITEM_WIDTH());
|
||||
main_sizer->SetMinSize(wxSize(sizer_width, -1));
|
||||
|
||||
main_sizer->Add(m_panel_wiping, 0, wxEXPAND | wxALL, 5);
|
||||
|
@ -166,7 +169,10 @@ WipingDialog::WipingDialog(wxWindow* parent,const std::vector<float>& matrix, co
|
|||
// This function allows to "play" with sizers parameters (like align or border)
|
||||
void WipingPanel::format_sizer(wxSizer* sizer, wxPanel* page, wxGridSizer* grid_sizer, const wxString& info, const wxString& table_title, int table_lshift/*=0*/)
|
||||
{
|
||||
sizer->Add(new wxStaticText(page, wxID_ANY, info,wxDefaultPosition,wxSize(0,50)), 0, wxEXPAND | wxLEFT, 15);
|
||||
wxSize text_size = GetTextExtent(info);
|
||||
auto info_str = new wxStaticText(page, wxID_ANY, info ,wxDefaultPosition, wxDefaultSize, wxALIGN_CENTER);
|
||||
info_str->Wrap(int(0.6*text_size.x));
|
||||
sizer->Add( info_str, 0, wxALIGN_CENTER_HORIZONTAL | wxEXPAND);
|
||||
auto table_sizer = new wxBoxSizer(wxVERTICAL);
|
||||
sizer->Add(table_sizer, 0, wxALIGN_CENTER | wxCENTER, table_lshift);
|
||||
table_sizer->Add(new wxStaticText(page, wxID_ANY, table_title), 0, wxALIGN_CENTER | wxTOP, 50);
|
||||
|
@ -198,7 +204,7 @@ WipingPanel::WipingPanel(wxWindow* parent, const std::vector<float>& matrix, con
|
|||
edit_boxes.push_back(std::vector<wxTextCtrl*>(0));
|
||||
|
||||
for (unsigned int j = 0; j < m_number_of_extruders; ++j) {
|
||||
edit_boxes.back().push_back(new wxTextCtrl(m_page_advanced, wxID_ANY, wxEmptyString, wxDefaultPosition, wxSize(ITEM_WIDTH, -1)));
|
||||
edit_boxes.back().push_back(new wxTextCtrl(m_page_advanced, wxID_ANY, wxEmptyString, wxDefaultPosition, wxSize(ITEM_WIDTH(), -1)));
|
||||
if (i == j)
|
||||
edit_boxes[i][j]->Disable();
|
||||
else
|
||||
|
@ -229,8 +235,8 @@ WipingPanel::WipingPanel(wxWindow* parent, const std::vector<float>& matrix, con
|
|||
gridsizer_simple->Add(new wxStaticText(m_page_simple,wxID_ANY,wxString(_(L("loaded")))), 0, wxALIGN_CENTER | wxALIGN_CENTER_VERTICAL);
|
||||
|
||||
for (unsigned int i=0;i<m_number_of_extruders;++i) {
|
||||
m_old.push_back(new wxSpinCtrl(m_page_simple,wxID_ANY,wxEmptyString,wxDefaultPosition, wxSize(80, -1),wxSP_ARROW_KEYS|wxALIGN_RIGHT,0,300,extruders[2*i]));
|
||||
m_new.push_back(new wxSpinCtrl(m_page_simple,wxID_ANY,wxEmptyString,wxDefaultPosition, wxSize(80, -1),wxSP_ARROW_KEYS|wxALIGN_RIGHT,0,300,extruders[2*i+1]));
|
||||
m_old.push_back(new wxSpinCtrl(m_page_simple,wxID_ANY,wxEmptyString,wxDefaultPosition, wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS|wxALIGN_RIGHT,0,300,extruders[2*i]));
|
||||
m_new.push_back(new wxSpinCtrl(m_page_simple,wxID_ANY,wxEmptyString,wxDefaultPosition, wxSize(ITEM_WIDTH(), -1),wxSP_ARROW_KEYS|wxALIGN_RIGHT,0,300,extruders[2*i+1]));
|
||||
gridsizer_simple->Add(new wxStaticText(m_page_simple, wxID_ANY, wxString(_(L("Tool #"))) << i + 1 << ": "), 0, wxALIGN_LEFT | wxALIGN_CENTER_VERTICAL);
|
||||
gridsizer_simple->Add(m_old.back(),0);
|
||||
gridsizer_simple->Add(m_new.back(),0);
|
||||
|
|
|
@ -13,6 +13,7 @@
|
|||
#include "GUI_App.hpp"
|
||||
#include "GUI_ObjectList.hpp"
|
||||
#include "libslic3r/GCode/PreviewData.hpp"
|
||||
#include "I18N.hpp"
|
||||
|
||||
using Slic3r::GUI::from_u8;
|
||||
|
||||
|
@ -41,7 +42,8 @@ wxMenuItem* append_menu_item(wxMenu* menu, int id, const wxString& string, const
|
|||
wxMenuItem* append_menu_item(wxMenu* menu, int id, const wxString& string, const wxString& description,
|
||||
std::function<void(wxCommandEvent& event)> cb, const std::string& icon, wxEvtHandler* event_handler)
|
||||
{
|
||||
const wxBitmap& bmp = !icon.empty() ? wxBitmap(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG) : wxNullBitmap;
|
||||
// const wxBitmap& bmp = !icon.empty() ? wxBitmap(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG) : wxNullBitmap;
|
||||
const wxBitmap& bmp = !icon.empty() ? create_scaled_bitmap(icon) : wxNullBitmap;
|
||||
return append_menu_item(menu, id, string, description, cb, bmp, event_handler);
|
||||
}
|
||||
|
||||
|
@ -52,7 +54,8 @@ wxMenuItem* append_submenu(wxMenu* menu, wxMenu* sub_menu, int id, const wxStrin
|
|||
|
||||
wxMenuItem* item = new wxMenuItem(menu, id, string, description);
|
||||
if (!icon.empty())
|
||||
item->SetBitmap(wxBitmap(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG));
|
||||
// item->SetBitmap(wxBitmap(from_u8(Slic3r::var(icon)), wxBITMAP_TYPE_PNG));
|
||||
item->SetBitmap(create_scaled_bitmap(icon));
|
||||
|
||||
item->SetSubMenu(sub_menu);
|
||||
menu->Append(item);
|
||||
|
@ -402,11 +405,28 @@ void PrusaCollapsiblePaneMSW::Collapse(bool collapse)
|
|||
// PrusaObjectDataViewModelNode
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
wxBitmap create_scaled_bitmap(const std::string& bmp_name)
|
||||
{
|
||||
const double scale_f = Slic3r::GUI::wxGetApp().em_unit()* 0.1;//GetContentScaleFactor();
|
||||
if (scale_f == 1.0)
|
||||
return wxBitmap(Slic3r::GUI::from_u8(Slic3r::var(bmp_name)), wxBITMAP_TYPE_PNG);
|
||||
// else if (scale_f == 2.0) // use biger icon
|
||||
// return wxBitmap(Slic3r::GUI::from_u8(Slic3r::var(bmp_name_X2)), wxBITMAP_TYPE_PNG);
|
||||
|
||||
wxImage img = wxImage(Slic3r::GUI::from_u8(Slic3r::var(bmp_name)), wxBITMAP_TYPE_PNG);
|
||||
const int sz_w = int(img.GetWidth()*scale_f);
|
||||
const int sz_h = int(img.GetHeight()*scale_f);
|
||||
img.Rescale(sz_w, sz_h, wxIMAGE_QUALITY_BILINEAR);
|
||||
return wxBitmap(img);
|
||||
}
|
||||
|
||||
void PrusaObjectDataViewModelNode::set_object_action_icon() {
|
||||
m_action_icon = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("add_object.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_action_icon = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("add_object.png")), wxBITMAP_TYPE_PNG);
|
||||
m_action_icon = create_scaled_bitmap("add_object.png");
|
||||
}
|
||||
void PrusaObjectDataViewModelNode::set_part_action_icon() {
|
||||
m_action_icon = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var(m_type == itVolume ? "cog.png" : "brick_go.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_action_icon = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var(m_type == itVolume ? "cog.png" : "brick_go.png")), wxBITMAP_TYPE_PNG);
|
||||
m_action_icon = create_scaled_bitmap(m_type == itVolume ? "cog.png" : "brick_go.png");
|
||||
}
|
||||
|
||||
Slic3r::GUI::BitmapCache *m_bitmap_cache = nullptr;
|
||||
|
@ -1420,22 +1440,32 @@ PrusaDoubleSlider::PrusaDoubleSlider(wxWindow *parent,
|
|||
SetDoubleBuffered(true);
|
||||
#endif //__WXOSX__
|
||||
|
||||
m_bmp_thumb_higher = wxBitmap(style == wxSL_HORIZONTAL ? Slic3r::GUI::from_u8(Slic3r::var("right_half_circle.png")) :
|
||||
Slic3r::GUI::from_u8(Slic3r::var("up_half_circle.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_thumb_lower = wxBitmap(style == wxSL_HORIZONTAL ? Slic3r::GUI::from_u8(Slic3r::var("left_half_circle.png")) :
|
||||
Slic3r::GUI::from_u8(Slic3r::var("down_half_circle.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_thumb_higher = wxBitmap(style == wxSL_HORIZONTAL ? Slic3r::GUI::from_u8(Slic3r::var("right_half_circle.png")) :
|
||||
// Slic3r::GUI::from_u8(Slic3r::var("up_half_circle.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_thumb_lower = wxBitmap(style == wxSL_HORIZONTAL ? Slic3r::GUI::from_u8(Slic3r::var("left_half_circle.png")) :
|
||||
// Slic3r::GUI::from_u8(Slic3r::var("down_half_circle.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_thumb_higher = wxBitmap(create_scaled_bitmap(style == wxSL_HORIZONTAL ? "right_half_circle.png" : "up_half_circle.png"));
|
||||
m_bmp_thumb_lower = wxBitmap(create_scaled_bitmap(style == wxSL_HORIZONTAL ? "left_half_circle.png" : "down_half_circle.png"));
|
||||
m_thumb_size = m_bmp_thumb_lower.GetSize();
|
||||
|
||||
m_bmp_add_tick_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_add_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_add_tick_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_add_off.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_del_tick_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_delete_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_del_tick_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_delete_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_add_tick_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_add_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_add_tick_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_add_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_del_tick_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_delete_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_del_tick_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("colorchange_delete_off.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_add_tick_on = create_scaled_bitmap("colorchange_add_on.png");
|
||||
m_bmp_add_tick_off = create_scaled_bitmap("colorchange_add_off.png");
|
||||
m_bmp_del_tick_on = create_scaled_bitmap("colorchange_delete_on.png");
|
||||
m_bmp_del_tick_off = create_scaled_bitmap("colorchange_delete_off.png");
|
||||
m_tick_icon_dim = m_bmp_add_tick_on.GetSize().x;
|
||||
|
||||
m_bmp_one_layer_lock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_one_layer_lock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_one_layer_unlock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_one_layer_unlock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_one_layer_lock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_one_layer_lock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_one_layer_unlock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_one_layer_unlock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_one_layer_lock_on = create_scaled_bitmap("one_layer_lock_on.png");
|
||||
m_bmp_one_layer_lock_off = create_scaled_bitmap("one_layer_lock_off.png");
|
||||
m_bmp_one_layer_unlock_on = create_scaled_bitmap("one_layer_unlock_on.png");
|
||||
m_bmp_one_layer_unlock_off = create_scaled_bitmap("one_layer_unlock_off.png");
|
||||
m_lock_icon_dim = m_bmp_one_layer_lock_on.GetSize().x;
|
||||
|
||||
m_selection = ssUndef;
|
||||
|
@ -1454,7 +1484,7 @@ PrusaDoubleSlider::PrusaDoubleSlider(wxWindow *parent,
|
|||
Bind(wxEVT_RIGHT_UP, &PrusaDoubleSlider::OnRightUp, this);
|
||||
|
||||
// control's view variables
|
||||
SLIDER_MARGIN = 4 + (style == wxSL_HORIZONTAL ? m_bmp_thumb_higher.GetWidth() : m_bmp_thumb_higher.GetHeight());
|
||||
SLIDER_MARGIN = 4 + Slic3r::GUI::wxGetApp().em_unit();//(style == wxSL_HORIZONTAL ? m_bmp_thumb_higher.GetWidth() : m_bmp_thumb_higher.GetHeight());
|
||||
|
||||
DARK_ORANGE_PEN = wxPen(wxColour(253, 84, 2));
|
||||
ORANGE_PEN = wxPen(wxColour(253, 126, 66));
|
||||
|
@ -1480,7 +1510,7 @@ wxSize PrusaDoubleSlider::DoGetBestSize() const
|
|||
const wxSize size = wxControl::DoGetBestSize();
|
||||
if (size.x > 1 && size.y > 1)
|
||||
return size;
|
||||
const int new_size = is_horizontal() ? 80 : 120;
|
||||
const int new_size = is_horizontal() ? 6 * Slic3r::GUI::wxGetApp().em_unit() : 8 * Slic3r::GUI::wxGetApp().em_unit();
|
||||
return wxSize(new_size, new_size);
|
||||
}
|
||||
|
||||
|
@ -2253,10 +2283,16 @@ PrusaLockButton::PrusaLockButton( wxWindow *parent,
|
|||
const wxSize& size /*= wxDefaultSize*/):
|
||||
wxButton(parent, id, wxEmptyString, pos, size, wxBU_EXACTFIT | wxNO_BORDER)
|
||||
{
|
||||
m_bmp_lock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_lock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_unlock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_unlock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_lock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_lock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_lock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_unlock_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_on.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_unlock_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("one_layer_unlock_off.png")), wxBITMAP_TYPE_PNG);
|
||||
|
||||
m_bmp_lock_on = create_scaled_bitmap("one_layer_lock_on.png");
|
||||
m_bmp_lock_off = create_scaled_bitmap("one_layer_lock_off.png");
|
||||
m_bmp_unlock_on = create_scaled_bitmap("one_layer_unlock_on.png");
|
||||
m_bmp_unlock_off = create_scaled_bitmap("one_layer_unlock_off.png");
|
||||
|
||||
|
||||
#ifdef __WXMSW__
|
||||
SetBackgroundColour(wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW));
|
||||
|
@ -2305,15 +2341,16 @@ PrusaModeButton::PrusaModeButton( wxWindow *parent,
|
|||
wxWindowID id,
|
||||
const wxString& mode/* = wxEmptyString*/,
|
||||
const wxBitmap& bmp_on/* = wxNullBitmap*/,
|
||||
const wxPoint& pos/* = wxDefaultPosition*/,
|
||||
const wxSize& size/* = wxDefaultSize*/) :
|
||||
wxButton(parent, id, mode, pos, size, wxBU_EXACTFIT | wxNO_BORDER),
|
||||
const wxSize& size/* = wxDefaultSize*/,
|
||||
const wxPoint& pos/* = wxDefaultPosition*/) :
|
||||
wxButton(parent, id, mode, pos, size, /*wxBU_EXACTFIT | */wxNO_BORDER),
|
||||
m_bmp_on(bmp_on)
|
||||
{
|
||||
#ifdef __WXMSW__
|
||||
SetBackgroundColour(wxSystemSettings::GetColour(wxSYS_COLOUR_WINDOW));
|
||||
#endif // __WXMSW__
|
||||
m_bmp_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("mode_off_sq.png")), wxBITMAP_TYPE_PNG);
|
||||
// m_bmp_off = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("mode_off_sq.png")), wxBITMAP_TYPE_PNG);
|
||||
m_bmp_off = create_scaled_bitmap("mode_off_sq.png");
|
||||
|
||||
SetBitmap(m_bmp_on);
|
||||
|
||||
|
@ -2339,8 +2376,8 @@ void PrusaModeButton::SetState(const bool state)
|
|||
|
||||
void PrusaModeButton::focus_button(const bool focus)
|
||||
{
|
||||
const wxBitmap& bmp = focus ? m_bmp_on : m_bmp_off;
|
||||
SetBitmap(bmp);
|
||||
// const wxBitmap& bmp = focus ? m_bmp_on : m_bmp_off;
|
||||
// SetBitmap(bmp);
|
||||
const wxFont& new_font = focus ? Slic3r::GUI::wxGetApp().bold_font() : Slic3r::GUI::wxGetApp().small_font();
|
||||
SetFont(new_font);
|
||||
|
||||
|
@ -2353,20 +2390,25 @@ void PrusaModeButton::focus_button(const bool focus)
|
|||
// PrusaModeSizer
|
||||
// ----------------------------------------------------------------------------
|
||||
|
||||
PrusaModeSizer::PrusaModeSizer(wxWindow *parent) :
|
||||
wxFlexGridSizer(3, 0, 5)
|
||||
PrusaModeSizer::PrusaModeSizer(wxWindow *parent, int hgap/* = 10*/) :
|
||||
wxFlexGridSizer(3, 0, hgap)
|
||||
{
|
||||
SetFlexibleDirection(wxHORIZONTAL);
|
||||
|
||||
const wxBitmap bmp_simple_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("mode_simple_sq.png")), wxBITMAP_TYPE_PNG);
|
||||
const wxBitmap bmp_advanced_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("mode_middle_sq.png")), wxBITMAP_TYPE_PNG);
|
||||
const wxBitmap bmp_expert_on = wxBitmap(Slic3r::GUI::from_u8(Slic3r::var("mode_expert_sq.png")), wxBITMAP_TYPE_PNG);
|
||||
|
||||
mode_btns.reserve(3);
|
||||
std::vector<std::pair<wxString, wxBitmap>> buttons = {
|
||||
{_(L("Simple")), create_scaled_bitmap("mode_simple_sq.png")},
|
||||
{_(L("Advanced")), create_scaled_bitmap("mode_middle_sq.png")},
|
||||
{_(L("Expert")), create_scaled_bitmap("mode_expert_sq.png")}
|
||||
};
|
||||
|
||||
mode_btns.push_back(new PrusaModeButton(parent, wxID_ANY, "Simple", bmp_simple_on));
|
||||
mode_btns.push_back(new PrusaModeButton(parent, wxID_ANY, "Advanced", bmp_advanced_on));
|
||||
mode_btns.push_back(new PrusaModeButton(parent, wxID_ANY, "Expert", bmp_expert_on));
|
||||
mode_btns.reserve(3);
|
||||
for (const auto& button : buttons) {
|
||||
int x, y;
|
||||
parent->GetTextExtent(button.first, &x, &y, nullptr, nullptr, &Slic3r::GUI::wxGetApp().bold_font());
|
||||
const wxSize size = wxSize(x + button.second.GetWidth() + Slic3r::GUI::wxGetApp().em_unit(),
|
||||
y + Slic3r::GUI::wxGetApp().em_unit());
|
||||
mode_btns.push_back(new PrusaModeButton(parent, wxID_ANY, button.first, button.second, size));
|
||||
}
|
||||
|
||||
for (auto btn : mode_btns)
|
||||
{
|
||||
|
|
|
@ -23,6 +23,8 @@ wxMenuItem* append_menu_item(wxMenu* menu, int id, const wxString& string, const
|
|||
|
||||
wxMenuItem* append_submenu(wxMenu* menu, wxMenu* sub_menu, int id, const wxString& string, const wxString& description, const std::string& icon = "");
|
||||
|
||||
wxBitmap create_scaled_bitmap(const std::string& bmp_name);
|
||||
|
||||
class wxCheckListBoxComboPopup : public wxCheckListBox, public wxComboPopup
|
||||
{
|
||||
static const unsigned int DefaultWidth;
|
||||
|
@ -882,8 +884,8 @@ public:
|
|||
wxWindowID id,
|
||||
const wxString& mode = wxEmptyString,
|
||||
const wxBitmap& bmp_on = wxNullBitmap,
|
||||
const wxPoint& pos = wxDefaultPosition,
|
||||
const wxSize& size = wxDefaultSize);
|
||||
const wxSize& size = wxDefaultSize,
|
||||
const wxPoint& pos = wxDefaultPosition);
|
||||
~PrusaModeButton() {}
|
||||
|
||||
void OnButton(wxCommandEvent& event);
|
||||
|
@ -911,7 +913,7 @@ private:
|
|||
class PrusaModeSizer : public wxFlexGridSizer
|
||||
{
|
||||
public:
|
||||
PrusaModeSizer( wxWindow *parent);
|
||||
PrusaModeSizer( wxWindow *parent, int hgap = 10);
|
||||
~PrusaModeSizer() {}
|
||||
|
||||
void SetMode(const /*ConfigOptionMode*/int mode);
|
||||
|
|
Loading…
Reference in a new issue