Merge remote-tracking branch 'remotes/origin/vb_wold_object_manipulation'

This commit is contained in:
bubnikv 2019-05-07 13:50:40 +02:00
commit a351e99bac
34 changed files with 1269 additions and 861 deletions

View File

@ -180,8 +180,67 @@ extern void stl_rotate_z(stl_file *stl, float angle);
extern void stl_mirror_xy(stl_file *stl);
extern void stl_mirror_yz(stl_file *stl);
extern void stl_mirror_xz(stl_file *stl);
extern void stl_transform(stl_file *stl, float *trafo3x4);
extern void stl_transform(stl_file *stl, const Eigen::Transform<double, 3, Eigen::Affine, Eigen::DontAlign>& t);
extern void stl_get_size(stl_file *stl);
template<typename T>
extern void stl_transform(stl_file *stl, T *trafo3x4)
{
if (stl->error)
return;
for (uint32_t i_face = 0; i_face < stl->stats.number_of_facets; ++ i_face) {
stl_facet &face = stl->facet_start[i_face];
for (int i_vertex = 0; i_vertex < 3; ++ i_vertex) {
stl_vertex &v_dst = face.vertex[i_vertex];
stl_vertex v_src = v_dst;
v_dst(0) = T(trafo3x4[0] * v_src(0) + trafo3x4[1] * v_src(1) + trafo3x4[2] * v_src(2) + trafo3x4[3]);
v_dst(1) = T(trafo3x4[4] * v_src(0) + trafo3x4[5] * v_src(1) + trafo3x4[6] * v_src(2) + trafo3x4[7]);
v_dst(2) = T(trafo3x4[8] * v_src(0) + trafo3x4[9] * v_src(1) + trafo3x4[10] * v_src(2) + trafo3x4[11]);
}
stl_vertex &v_dst = face.normal;
stl_vertex v_src = v_dst;
v_dst(0) = T(trafo3x4[0] * v_src(0) + trafo3x4[1] * v_src(1) + trafo3x4[2] * v_src(2));
v_dst(1) = T(trafo3x4[4] * v_src(0) + trafo3x4[5] * v_src(1) + trafo3x4[6] * v_src(2));
v_dst(2) = T(trafo3x4[8] * v_src(0) + trafo3x4[9] * v_src(1) + trafo3x4[10] * v_src(2));
}
stl_get_size(stl);
}
template<typename T>
inline void stl_transform(stl_file *stl, const Eigen::Transform<T, 3, Eigen::Affine, Eigen::DontAlign>& t)
{
if (stl->error)
return;
const Eigen::Matrix<double, 3, 3, Eigen::DontAlign> r = t.matrix().template block<3, 3>(0, 0);
for (size_t i = 0; i < stl->stats.number_of_facets; ++i) {
stl_facet &f = stl->facet_start[i];
for (size_t j = 0; j < 3; ++j)
f.vertex[j] = (t * f.vertex[j].template cast<T>()).template cast<float>().eval();
f.normal = (r * f.normal.template cast<T>()).template cast<float>().eval();
}
stl_get_size(stl);
}
template<typename T>
inline void stl_transform(stl_file *stl, const Eigen::Matrix<T, 3, 3, Eigen::DontAlign>& m)
{
if (stl->error)
return;
for (size_t i = 0; i < stl->stats.number_of_facets; ++i) {
stl_facet &f = stl->facet_start[i];
for (size_t j = 0; j < 3; ++j)
f.vertex[j] = (m * f.vertex[j].template cast<T>()).template cast<float>().eval();
f.normal = (m * f.normal.template cast<T>()).template cast<float>().eval();
}
stl_get_size(stl);
}
extern void stl_open_merge(stl_file *stl, char *file);
extern void stl_invalidate_shared_vertices(stl_file *stl);
extern void stl_generate_shared_vertices(stl_file *stl);
@ -214,7 +273,6 @@ extern void stl_read(stl_file *stl, int first_facet, bool first);
extern void stl_facet_stats(stl_file *stl, stl_facet facet, bool &first);
extern void stl_reallocate(stl_file *stl);
extern void stl_add_facet(stl_file *stl, stl_facet *new_facet);
extern void stl_get_size(stl_file *stl);
extern void stl_clear_error(stl_file *stl);
extern int stl_get_error(stl_file *stl);

View File

@ -137,65 +137,6 @@ static void calculate_normals(stl_file *stl)
}
}
void stl_transform(stl_file *stl, float *trafo3x4) {
int i_face, i_vertex;
if (stl->error)
return;
for (i_face = 0; i_face < stl->stats.number_of_facets; ++ i_face) {
stl_vertex *vertices = stl->facet_start[i_face].vertex;
for (i_vertex = 0; i_vertex < 3; ++ i_vertex) {
stl_vertex &v_dst = vertices[i_vertex];
stl_vertex v_src = v_dst;
v_dst(0) = trafo3x4[0] * v_src(0) + trafo3x4[1] * v_src(1) + trafo3x4[2] * v_src(2) + trafo3x4[3];
v_dst(1) = trafo3x4[4] * v_src(0) + trafo3x4[5] * v_src(1) + trafo3x4[6] * v_src(2) + trafo3x4[7];
v_dst(2) = trafo3x4[8] * v_src(0) + trafo3x4[9] * v_src(1) + trafo3x4[10] * v_src(2) + trafo3x4[11];
}
}
stl_get_size(stl);
calculate_normals(stl);
}
void stl_transform(stl_file *stl, const Eigen::Transform<double, 3, Eigen::Affine, Eigen::DontAlign>& t)
{
if (stl->error)
return;
unsigned int vertices_count = 3 * (unsigned int)stl->stats.number_of_facets;
if (vertices_count == 0)
return;
Eigen::MatrixXf src_vertices(3, vertices_count);
stl_facet* facet_ptr = stl->facet_start;
unsigned int v_id = 0;
while (facet_ptr < stl->facet_start + stl->stats.number_of_facets)
{
for (int i = 0; i < 3; ++i)
{
::memcpy((void*)src_vertices.col(v_id).data(), (const void*)&facet_ptr->vertex[i], 3 * sizeof(float));
++v_id;
}
facet_ptr += 1;
}
Eigen::MatrixXf dst_vertices(3, vertices_count);
dst_vertices = t.cast<float>() * src_vertices.colwise().homogeneous();
facet_ptr = stl->facet_start;
v_id = 0;
while (facet_ptr < stl->facet_start + stl->stats.number_of_facets)
{
for (int i = 0; i < 3; ++i)
{
::memcpy((void*)&facet_ptr->vertex[i], (const void*)dst_vertices.col(v_id).data(), 3 * sizeof(float));
++v_id;
}
facet_ptr += 1;
}
stl_get_size(stl);
calculate_normals(stl);
}
void
stl_rotate_x(stl_file *stl, float angle) {
int i;

View File

@ -280,7 +280,7 @@ std::ostream& ConfigDef::print_cli_help(std::ostream& out, bool show_defaults, s
// right: option description
std::string descr = def.tooltip;
if (show_defaults && def.default_value != nullptr && def.type != coBool
if (show_defaults && def.default_value && def.type != coBool
&& (def.type != coString || !def.default_value->serialize().empty())) {
descr += " (";
if (!def.sidetext.empty()) {
@ -627,7 +627,7 @@ ConfigOption* DynamicConfig::optptr(const t_config_option_key &opt_key, bool cre
// Let the parent decide what to do if the opt_key is not defined by this->def().
return nullptr;
ConfigOption *opt = nullptr;
if (optdef->default_value != nullptr) {
if (optdef->default_value) {
opt = (optdef->default_value->type() == coEnum) ?
// Special case: For a DynamicConfig, convert a templated enum to a generic enum.
new ConfigOptionEnumGeneric(optdef->enum_keys_map, optdef->default_value->getInt()) :
@ -783,8 +783,8 @@ void StaticConfig::set_defaults()
for (const std::string &key : this->keys()) {
const ConfigOptionDef *def = defs->get(key);
ConfigOption *opt = this->option(key);
if (def != nullptr && opt != nullptr && def->default_value != nullptr)
opt->set(def->default_value);
if (def != nullptr && opt != nullptr && def->default_value)
opt->set(def->default_value.get());
}
}
}

View File

@ -12,6 +12,7 @@
#include <string>
#include <vector>
#include "libslic3r.h"
#include "clonable_ptr.hpp"
#include "Point.hpp"
#include <boost/format.hpp>
@ -1010,7 +1011,10 @@ public:
// What type? bool, int, string etc.
ConfigOptionType type = coNone;
// Default value of this option. The default value object is owned by ConfigDef, it is released in its destructor.
const ConfigOption *default_value = nullptr;
Slic3r::clonable_ptr<const ConfigOption> default_value;
void set_default_value(const ConfigOption* ptr) { this->default_value = Slic3r::clonable_ptr<const ConfigOption>(ptr); }
template<typename T>
const T* get_default_value() const { return static_cast<const T*>(this->default_value.get()); }
// Usually empty.
// Special values - "i_enum_open", "f_enum_open" to provide combo box for int or float selection,
@ -1099,12 +1103,6 @@ typedef std::map<t_config_option_key, ConfigOptionDef> t_optiondef_map;
class ConfigDef
{
public:
~ConfigDef() {
for (std::pair<const t_config_option_key, ConfigOptionDef> &def : this->options)
delete def.second.default_value;
this->options.clear();
}
t_optiondef_map options;
bool has(const t_config_option_key &opt_key) const { return this->options.count(opt_key) > 0; }

View File

@ -269,6 +269,21 @@ extern Eigen::Quaterniond rotation_xyz_diff(const Vec3d &rot_xyz_from, const Vec
// This should only be called if it is known, that the two rotations only differ in rotation around the Z axis.
extern double rotation_diff_z(const Vec3d &rot_xyz_from, const Vec3d &rot_xyz_to);
// Is the angle close to a multiple of 90 degrees?
inline bool is_rotation_ninety_degrees(double a)
{
a = fmod(std::abs(a), 0.5 * M_PI);
if (a > 0.25 * PI)
a = 0.5 * PI - a;
return a < 0.001;
}
// Is the angle close to a multiple of 90 degrees?
inline bool is_rotation_ninety_degrees(const Vec3d &rotation)
{
return is_rotation_ninety_degrees(rotation.x()) && is_rotation_ninety_degrees(rotation.y()) && is_rotation_ninety_degrees(rotation.z());
}
} }
#endif

View File

@ -24,6 +24,19 @@ unsigned int Model::s_auto_extruder_id = 1;
size_t ModelBase::s_last_id = 0;
// Unique object / instance ID for the wipe tower.
ModelID wipe_tower_object_id()
{
static ModelBase mine;
return mine.id();
}
ModelID wipe_tower_instance_id()
{
static ModelBase mine;
return mine.id();
}
Model& Model::assign_copy(const Model &rhs)
{
this->copy_id(rhs);
@ -1320,6 +1333,58 @@ void ModelObject::repair()
v->mesh.repair();
}
// Support for non-uniform scaling of instances. If an instance is rotated by angles, which are not multiples of ninety degrees,
// then the scaling in world coordinate system is not representable by the Geometry::Transformation structure.
// This situation is solved by baking in the instance transformation into the mesh vertices.
// Rotation and mirroring is being baked in. In case the instance scaling was non-uniform, it is baked in as well.
void ModelObject::bake_xy_rotation_into_meshes(size_t instance_idx)
{
assert(instance_idx < this->instances.size());
const Geometry::Transformation reference_trafo = this->instances[instance_idx]->get_transformation();
if (Geometry::is_rotation_ninety_degrees(reference_trafo.get_rotation()))
// nothing to do, scaling in the world coordinate space is possible in the representation of Geometry::Transformation.
return;
bool left_handed = reference_trafo.is_left_handed();
bool has_mirrorring = ! reference_trafo.get_mirror().isApprox(Vec3d(1., 1., 1.));
bool uniform_scaling = std::abs(reference_trafo.get_scaling_factor().x() - reference_trafo.get_scaling_factor().y()) < EPSILON &&
std::abs(reference_trafo.get_scaling_factor().x() - reference_trafo.get_scaling_factor().z()) < EPSILON;
double new_scaling_factor = uniform_scaling ? reference_trafo.get_scaling_factor().x() : 1.;
// Adjust the instances.
for (size_t i = 0; i < this->instances.size(); ++ i) {
ModelInstance &model_instance = *this->instances[i];
model_instance.set_rotation(Vec3d(0., 0., Geometry::rotation_diff_z(reference_trafo.get_rotation(), model_instance.get_rotation())));
model_instance.set_scaling_factor(Vec3d(new_scaling_factor, new_scaling_factor, new_scaling_factor));
model_instance.set_mirror(Vec3d(1., 1., 1.));
}
// Adjust the meshes.
// Transformation to be applied to the meshes.
Eigen::Matrix3d mesh_trafo_3x3 = reference_trafo.get_matrix(true, false, uniform_scaling, ! has_mirrorring).matrix().block<3, 3>(0, 0);
Transform3d volume_offset_correction = this->instances[instance_idx]->get_transformation().get_matrix().inverse() * reference_trafo.get_matrix();
for (ModelVolume *model_volume : this->volumes) {
const Geometry::Transformation volume_trafo = model_volume->get_transformation();
bool volume_left_handed = volume_trafo.is_left_handed();
bool volume_has_mirrorring = ! volume_trafo.get_mirror().isApprox(Vec3d(1., 1., 1.));
bool volume_uniform_scaling = std::abs(volume_trafo.get_scaling_factor().x() - volume_trafo.get_scaling_factor().y()) < EPSILON &&
std::abs(volume_trafo.get_scaling_factor().x() - volume_trafo.get_scaling_factor().z()) < EPSILON;
double volume_new_scaling_factor = volume_uniform_scaling ? volume_trafo.get_scaling_factor().x() : 1.;
// Transform the mesh.
Matrix3d volume_trafo_3x3 = volume_trafo.get_matrix(true, false, volume_uniform_scaling, !volume_has_mirrorring).matrix().block<3, 3>(0, 0);
model_volume->transform_mesh(mesh_trafo_3x3 * volume_trafo_3x3, left_handed != volume_left_handed);
// Reset the rotation, scaling and mirroring.
model_volume->set_rotation(Vec3d(0., 0., 0.));
model_volume->set_scaling_factor(Vec3d(volume_new_scaling_factor, volume_new_scaling_factor, volume_new_scaling_factor));
model_volume->set_mirror(Vec3d(1., 1., 1.));
// Move the reference point of the volume to compensate for the change of the instance trafo.
model_volume->set_offset(volume_offset_correction * volume_trafo.get_offset());
}
this->invalidate_bounding_box();
}
double ModelObject::get_min_z() const
{
if (instances.empty())
@ -1708,6 +1773,22 @@ void ModelVolume::scale_geometry(const Vec3d& versor)
m_convex_hull.scale(versor);
}
void ModelVolume::transform_mesh(const Transform3d &mesh_trafo, bool fix_left_handed)
{
this->mesh.transform(mesh_trafo, fix_left_handed);
this->m_convex_hull.transform(mesh_trafo, fix_left_handed);
// Let the rest of the application know that the geometry changed, so the meshes have to be reloaded.
this->set_new_unique_id();
}
void ModelVolume::transform_mesh(const Matrix3d &matrix, bool fix_left_handed)
{
this->mesh.transform(matrix, fix_left_handed);
this->m_convex_hull.transform(matrix, fix_left_handed);
// Let the rest of the application know that the geometry changed, so the meshes have to be reloaded.
this->set_new_unique_id();
}
void ModelInstance::transform_mesh(TriangleMesh* mesh, bool dont_translate) const
{
mesh->transform(get_matrix(dont_translate));

View File

@ -54,6 +54,10 @@ struct ModelID
size_t id;
};
// Unique object / instance ID for the wipe tower.
extern ModelID wipe_tower_object_id();
extern ModelID wipe_tower_instance_id();
// Base for Model, ModelObject, ModelVolume, ModelInstance or ModelMaterial to provide a unique ID
// to synchronize the front end (UI) with the back end (BackgroundSlicingProcess / Print / PrintObject).
// Achtung! The s_last_id counter is not thread safe, so it is expected, that the ModelBase derived instances
@ -85,6 +89,9 @@ private:
static inline ModelID generate_new_id() { return ModelID(++ s_last_id); }
static size_t s_last_id;
friend ModelID wipe_tower_object_id();
friend ModelID wipe_tower_instance_id();
};
#define MODELBASE_DERIVED_COPY_MOVE_CLONE(TYPE) \
@ -265,6 +272,11 @@ public:
ModelObjectPtrs cut(size_t instance, coordf_t z, bool keep_upper = true, bool keep_lower = true, bool rotate_lower = false); // Note: z is in world coordinates
void split(ModelObjectPtrs* new_objects);
void repair();
// Support for non-uniform scaling of instances. If an instance is rotated by angles, which are not multiples of ninety degrees,
// then the scaling in world coordinate system is not representable by the Geometry::Transformation structure.
// This situation is solved by baking in the instance transformation into the mesh vertices.
// Rotation and mirroring is being baked in. In case the instance scaling was non-uniform, it is baked in as well.
void bake_xy_rotation_into_meshes(size_t instance_idx);
double get_min_z() const;
double get_instance_min_z(size_t instance_idx) const;
@ -421,6 +433,8 @@ protected:
explicit ModelVolume(const ModelVolume &rhs) = default;
void set_model_object(ModelObject *model_object) { object = model_object; }
void transform_mesh(const Transform3d& t, bool fix_left_handed);
void transform_mesh(const Matrix3d& m, bool fix_left_handed);
private:
// Parent object owning this ModelVolume.

View File

@ -40,6 +40,11 @@ typedef std::vector<Vec3crd> Points3;
typedef std::vector<Vec2d> Pointfs;
typedef std::vector<Vec3d> Pointf3s;
typedef Eigen::Matrix<float, 2, 2, Eigen::DontAlign> Matrix2f;
typedef Eigen::Matrix<double, 2, 2, Eigen::DontAlign> Matrix2d;
typedef Eigen::Matrix<float, 3, 3, Eigen::DontAlign> Matrix3f;
typedef Eigen::Matrix<double, 3, 3, Eigen::DontAlign> Matrix3d;
typedef Eigen::Transform<float, 2, Eigen::Affine, Eigen::DontAlign> Transform2f;
typedef Eigen::Transform<double, 2, Eigen::Affine, Eigen::DontAlign> Transform2d;
typedef Eigen::Transform<float, 3, Eigen::Affine, Eigen::DontAlign> Transform3f;

File diff suppressed because it is too large Load Diff

View File

@ -307,8 +307,8 @@ protected:
m_keys.emplace_back(kvp.first);
const ConfigOptionDef *def = defs->get(kvp.first);
assert(def != nullptr);
if (def->default_value != nullptr)
opt->set(def->default_value);
if (def->default_value)
opt->set(def->default_value.get());
}
}

View File

@ -330,6 +330,17 @@ void TriangleMesh::transform(const Transform3d& t, bool fix_left_handed)
}
}
void TriangleMesh::transform(const Matrix3d& m, bool fix_left_handed)
{
stl_transform(&stl, m);
stl_invalidate_shared_vertices(&stl);
if (fix_left_handed && m.determinant() < 0.) {
// Left handed transformation is being applied. It is a good idea to flip the faces and their normals.
this->repair();
stl_reverse_all_facets(&stl);
}
}
void TriangleMesh::align_to_origin()
{
this->translate(

View File

@ -52,6 +52,7 @@ public:
void mirror_y() { this->mirror(Y); }
void mirror_z() { this->mirror(Z); }
void transform(const Transform3d& t, bool fix_left_handed = false);
void transform(const Matrix3d& t, bool fix_left_handed = false);
void align_to_origin();
void rotate(double angle, Point* center);
TriangleMeshPtrs split() const;

View File

@ -0,0 +1,168 @@
// clonable_ptr: a smart pointer with a usage similar to unique_ptr, with the exception, that
// the copy constructor / copy assignment operator work by calling the ->clone() method.
// derived from https://github.com/SRombauts/shared_ptr/blob/master/include/unique_ptr.hpp
/**
* @file clonable_ptr.hpp
* @brief clonable_ptr is a fake implementation to use in place of a C++11 std::clonable_ptr when compiling on an older compiler.
*
* @see http://www.cplusplus.com/reference/memory/clonable_ptr/
*
* Copyright (c) 2014-2019 Sebastien Rombauts (sebastien.rombauts@gmail.com)
*
* Distributed under the MIT License (MIT) (See accompanying file LICENSE.txt
* or copy at http://opensource.org/licenses/MIT)
*/
#include "assert.h"
namespace Slic3r {
// Detect whether the compiler supports C++11 noexcept exception specifications.
#if defined(_MSC_VER) && _MSC_VER < 1900 && ! defined(noexcept)
#define noexcept throw()
#endif
template<class T>
class clonable_ptr
{
public:
/// The type of the managed object, aliased as member type
typedef T element_type;
/// @brief Default constructor
clonable_ptr() noexcept :
px(nullptr)
{
}
/// @brief Constructor with the provided pointer to manage
explicit clonable_ptr(T* p) noexcept :
px(p)
{
}
/// @brief Copy constructor, clones by calling the rhs.clone() method
clonable_ptr(const clonable_ptr& rhs) :
px(rhs ? rhs.px->clone() : nullptr)
{
}
/// @brief Move constructor, never throws
clonable_ptr(clonable_ptr&& rhs) noexcept :
px(rhs.px)
{
rhs.px = nullptr;
}
/// @brief Assignment operator
clonable_ptr& operator=(const clonable_ptr& rhs)
{
delete px;
px = rhs ? rhs.px->clone() : nullptr;
return *this;
}
/// @brief Move operator, never throws
clonable_ptr& operator=(clonable_ptr&& rhs)
{
delete px;
px = rhs.px;
rhs.px = nullptr;
return *this;
}
/// @brief the destructor releases its ownership and destroy the object
inline ~clonable_ptr() noexcept
{
destroy();
}
/// @brief this reset releases its ownership and destroy the object
inline void reset() noexcept
{
destroy();
}
/// @brief this reset release its ownership and re-acquire another one
void reset(T* p) noexcept
{
assert((nullptr == p) || (px != p)); // auto-reset not allowed
destroy();
px = p;
}
/// @brief Swap method for the copy-and-swap idiom (copy constructor and swap method)
void swap(clonable_ptr& rhs) noexcept
{
T *tmp = px;
px = rhs.px;
rhs.px = tmp;
}
/// @brief release the ownership of the px pointer without destroying the object!
inline void release() noexcept
{
px = nullptr;
}
// reference counter operations :
inline operator bool() const noexcept
{
return (nullptr != px); // TODO nullptrptr
}
// underlying pointer operations :
inline T& operator*() const noexcept
{
assert(nullptr != px);
return *px;
}
inline T* operator->() const noexcept
{
assert(nullptr != px);
return px;
}
inline T* get() const noexcept
{
// no assert, can return nullptr
return px;
}
private:
/// @brief release the ownership of the px pointer and destroy the object
inline void destroy() noexcept
{
delete px;
px = nullptr;
}
/// @brief hack: const-cast release the ownership of the px pointer without destroying the object!
inline void release() const noexcept
{
px = nullptr;
}
private:
T* px; //!< Native pointer
};
// comparison operators
template<class T, class U> inline bool operator==(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() == r.get());
}
template<class T, class U> inline bool operator!=(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() != r.get());
}
template<class T, class U> inline bool operator<=(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() <= r.get());
}
template<class T, class U> inline bool operator<(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() < r.get());
}
template<class T, class U> inline bool operator>=(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() >= r.get());
}
template<class T, class U> inline bool operator>(const clonable_ptr<T>& l, const clonable_ptr<U>& r) noexcept
{
return (l.get() > r.get());
}
} // namespace Slic3r

View File

@ -365,19 +365,18 @@ const BoundingBoxf3& GLVolume::transformed_bounding_box() const
const BoundingBoxf3& GLVolume::transformed_convex_hull_bounding_box() const
{
if (m_transformed_convex_hull_bounding_box_dirty)
{
if ((m_convex_hull != nullptr) && (m_convex_hull->stl.stats.number_of_facets > 0))
m_transformed_convex_hull_bounding_box = m_convex_hull->transformed_bounding_box(world_matrix());
else
m_transformed_convex_hull_bounding_box = bounding_box.transformed(world_matrix());
m_transformed_convex_hull_bounding_box_dirty = false;
}
if (m_transformed_convex_hull_bounding_box_dirty)
m_transformed_convex_hull_bounding_box = this->transformed_convex_hull_bounding_box(world_matrix());
return m_transformed_convex_hull_bounding_box;
}
BoundingBoxf3 GLVolume::transformed_convex_hull_bounding_box(const Transform3d &trafo) const
{
return (m_convex_hull != nullptr && m_convex_hull->stl.stats.number_of_facets > 0) ?
m_convex_hull->transformed_bounding_box(trafo) :
bounding_box.transformed(trafo);
}
void GLVolume::set_range(double min_z, double max_z)
{
this->qverts_range.first = 0;
@ -719,6 +718,8 @@ int GLVolumeCollection::load_wipe_tower_preview(
v.bounding_box = v.indexed_vertex_array.bounding_box();
v.indexed_vertex_array.finalize_geometry(use_VBOs);
v.composite_id = GLVolume::CompositeID(obj_idx, 0, 0);
v.geometry_id.first = 0;
v.geometry_id.second = wipe_tower_instance_id().id;
v.is_wipe_tower = true;
v.shader_outside_printer_detection_enabled = ! size_unknown;
return int(this->volumes.size() - 1);

View File

@ -283,6 +283,8 @@ public:
int volume_id;
// Instance ID, which is equal to the index of the respective ModelInstance in ModelObject.instances array.
int instance_id;
bool operator==(const CompositeID &rhs) const { return object_id == rhs.object_id && volume_id == rhs.volume_id && instance_id == rhs.instance_id; }
bool operator!=(const CompositeID &rhs) const { return ! (*this == rhs); }
};
CompositeID composite_id;
// Fingerprint of the source geometry. For ModelVolumes, it is the ModelVolume::ID and ModelInstanceID,
@ -403,6 +405,9 @@ public:
bool is_left_handed() const;
const BoundingBoxf3& transformed_bounding_box() const;
// non-caching variant
BoundingBoxf3 transformed_convex_hull_bounding_box(const Transform3d &trafo) const;
// caching variant
const BoundingBoxf3& transformed_convex_hull_bounding_box() const;
bool empty() const { return this->indexed_vertex_array.empty(); }

View File

@ -68,14 +68,14 @@ void BedShapePanel::build_panel(ConfigOptionPoints* default_pt)
auto optgroup = init_shape_options_page(_(L("Rectangular")));
ConfigOptionDef def;
def.type = coPoints;
def.default_value = new ConfigOptionPoints{ Vec2d(200, 200) };
def.set_default_value(new ConfigOptionPoints{ Vec2d(200, 200) });
def.label = L("Size");
def.tooltip = L("Size in X and Y of the rectangular plate.");
Option option(def, "rect_size");
optgroup->append_single_option_line(option);
def.type = coPoints;
def.default_value = new ConfigOptionPoints{ Vec2d(0, 0) };
def.set_default_value(new ConfigOptionPoints{ Vec2d(0, 0) });
def.label = L("Origin");
def.tooltip = L("Distance of the 0,0 G-code coordinate from the front left corner of the rectangle.");
option = Option(def, "rect_origin");
@ -83,7 +83,7 @@ void BedShapePanel::build_panel(ConfigOptionPoints* default_pt)
optgroup = init_shape_options_page(_(L("Circular")));
def.type = coFloat;
def.default_value = new ConfigOptionFloat(200);
def.set_default_value(new ConfigOptionFloat(200));
def.sidetext = L("mm");
def.label = L("Diameter");
def.tooltip = L("Diameter of the print bed. It is assumed that origin (0,0) is located in the center.");

View File

@ -499,7 +499,7 @@ PageFirmware::PageFirmware(ConfigWizard *parent)
gcode_picker = new wxChoice(this, wxID_ANY, wxDefaultPosition, wxDefaultSize, choices);
const auto &enum_values = gcode_opt.enum_values;
auto needle = enum_values.cend();
if (gcode_opt.default_value != nullptr) {
if (gcode_opt.default_value) {
needle = std::find(enum_values.cbegin(), enum_values.cend(), gcode_opt.default_value->serialize());
}
if (needle != enum_values.cend()) {
@ -544,14 +544,12 @@ PageDiameters::PageDiameters(ConfigWizard *parent)
{
spin_nozzle->SetDigits(2);
spin_nozzle->SetIncrement(0.1);
const auto &def_nozzle = *print_config_def.get("nozzle_diameter");
auto *default_nozzle = dynamic_cast<const ConfigOptionFloats*>(def_nozzle.default_value);
auto *default_nozzle = print_config_def.get("nozzle_diameter")->get_default_value<ConfigOptionFloats>();
spin_nozzle->SetValue(default_nozzle != nullptr && default_nozzle->size() > 0 ? default_nozzle->get_at(0) : 0.5);
spin_filam->SetDigits(2);
spin_filam->SetIncrement(0.25);
const auto &def_filam = *print_config_def.get("filament_diameter");
auto *default_filam = dynamic_cast<const ConfigOptionFloats*>(def_filam.default_value);
auto *default_filam = print_config_def.get("filament_diameter")->get_default_value<ConfigOptionFloats>();
spin_filam->SetValue(default_filam != nullptr && default_filam->size() > 0 ? default_filam->get_at(0) : 3.0);
append_text(_(L("Enter the diameter of your printer's hot end nozzle.")));
@ -596,13 +594,13 @@ PageTemperatures::PageTemperatures(ConfigWizard *parent)
spin_extr->SetIncrement(5.0);
const auto &def_extr = *print_config_def.get("temperature");
spin_extr->SetRange(def_extr.min, def_extr.max);
auto *default_extr = dynamic_cast<const ConfigOptionInts*>(def_extr.default_value);
auto *default_extr = def_extr.get_default_value<ConfigOptionInts>();
spin_extr->SetValue(default_extr != nullptr && default_extr->size() > 0 ? default_extr->get_at(0) : 200);
spin_bed->SetIncrement(5.0);
const auto &def_bed = *print_config_def.get("bed_temperature");
spin_bed->SetRange(def_bed.min, def_bed.max);
auto *default_bed = dynamic_cast<const ConfigOptionInts*>(def_bed.default_value);
auto *default_bed = def_bed.get_default_value<ConfigOptionInts>();
spin_bed->SetValue(default_bed != nullptr && default_bed->size() > 0 ? default_bed->get_at(0) : 0);
append_text(_(L("Enter the temperature needed for extruding your filament.")));

View File

@ -15,19 +15,7 @@ namespace Slic3r { namespace GUI {
wxString double_to_string(double const value, const int max_precision /*= 4*/)
{
if (value - int(value) == 0)
return wxString::Format(_T("%i"), int(value));
int precision = max_precision;
for (size_t p = 1; p < max_precision; p++)
{
double cur_val = pow(10, p)*value;
if (cur_val - int(cur_val) == 0) {
precision = p;
break;
}
}
return wxNumberFormatter::ToString(value, precision, wxNumberFormatter::Style_None);
return wxNumberFormatter::ToString(value, max_precision, wxNumberFormatter::Style_NoTrailingZeroes);
}
void Field::PostInitialize()
@ -215,7 +203,7 @@ void TextCtrl::BUILD() {
case coFloatOrPercent:
{
text_value = double_to_string(m_opt.default_value->getFloat());
if (static_cast<const ConfigOptionFloatOrPercent*>(m_opt.default_value)->percent)
if (m_opt.get_default_value<ConfigOptionFloatOrPercent>()->percent)
text_value += "%";
break;
}
@ -230,19 +218,19 @@ void TextCtrl::BUILD() {
case coFloat:
{
double val = m_opt.type == coFloats ?
static_cast<const ConfigOptionFloats*>(m_opt.default_value)->get_at(m_opt_idx) :
m_opt.get_default_value<ConfigOptionFloats>()->get_at(m_opt_idx) :
m_opt.type == coFloat ?
m_opt.default_value->getFloat() :
static_cast<const ConfigOptionPercents*>(m_opt.default_value)->get_at(m_opt_idx);
m_opt.get_default_value<ConfigOptionPercents>()->get_at(m_opt_idx);
text_value = double_to_string(val);
break;
}
case coString:
text_value = static_cast<const ConfigOptionString*>(m_opt.default_value)->value;
text_value = m_opt.get_default_value<ConfigOptionString>()->value;
break;
case coStrings:
{
const ConfigOptionStrings *vec = static_cast<const ConfigOptionStrings*>(m_opt.default_value);
const ConfigOptionStrings *vec = m_opt.get_default_value<ConfigOptionStrings>();
if (vec == nullptr || vec->empty()) break; //for the case of empty default value
text_value = vec->get_at(m_opt_idx);
break;
@ -385,8 +373,8 @@ void CheckBox::BUILD() {
bool check_value = m_opt.type == coBool ?
m_opt.default_value->getBool() : m_opt.type == coBools ?
static_cast<const ConfigOptionBools*>(m_opt.default_value)->get_at(m_opt_idx) :
false;
m_opt.get_default_value<ConfigOptionBools>()->get_at(m_opt_idx) :
false;
// Set Label as a string of at least one space simbol to correct system scaling of a CheckBox
auto temp = new wxCheckBox(m_parent, wxID_ANY, wxString(" "), wxDefaultPosition, size);
@ -439,7 +427,7 @@ void SpinCtrl::BUILD() {
break;
case coInts:
{
const ConfigOptionInts *vec = static_cast<const ConfigOptionInts*>(m_opt.default_value);
const ConfigOptionInts *vec = m_opt.get_default_value<ConfigOptionInts>();
if (vec == nullptr || vec->empty()) break;
for (size_t id = 0; id < vec->size(); ++id)
{
@ -641,7 +629,7 @@ void Choice::set_selection()
break;
}
case coEnum:{
int id_value = static_cast<const ConfigOptionEnum<SeamPosition>*>(m_opt.default_value)->value; //!!
int id_value = m_opt.get_default_value<ConfigOptionEnum<SeamPosition>>()->value; //!!
field->SetSelection(id_value);
break;
}
@ -661,7 +649,7 @@ void Choice::set_selection()
break;
}
case coStrings:{
text_value = static_cast<const ConfigOptionStrings*>(m_opt.default_value)->get_at(m_opt_idx);
text_value = m_opt.get_default_value<ConfigOptionStrings>()->get_at(m_opt_idx);
size_t idx = 0;
for (auto el : m_opt.enum_values)
@ -898,7 +886,7 @@ void ColourPicker::BUILD()
if (m_opt.width >= 0) size.SetWidth(m_opt.width*m_em_unit);
// Validate the color
wxString clr_str(static_cast<const ConfigOptionStrings*>(m_opt.default_value)->get_at(m_opt_idx));
wxString clr_str(m_opt.get_default_value<ConfigOptionStrings>()->get_at(m_opt_idx));
wxColour clr(clr_str);
if (! clr.IsOk()) {
clr = wxTransparentColour;
@ -932,7 +920,7 @@ void PointCtrl::BUILD()
const wxSize field_size(4 * m_em_unit, -1);
auto default_pt = static_cast<const ConfigOptionPoints*>(m_opt.default_value)->values.at(0);
auto default_pt = m_opt.get_default_value<ConfigOptionPoints>()->values.at(0);
double val = default_pt(0);
wxString X = val - int(val) == 0 ? wxString::Format(_T("%i"), int(val)) : wxNumberFormatter::ToString(val, 2, wxNumberFormatter::Style_None);
val = default_pt(1);
@ -1031,7 +1019,7 @@ void StaticText::BUILD()
if (m_opt.height >= 0) size.SetHeight(m_opt.height*m_em_unit);
if (m_opt.width >= 0) size.SetWidth(m_opt.width*m_em_unit);
const wxString legend(static_cast<const ConfigOptionString*>(m_opt.default_value)->value);
const wxString legend(m_opt.get_default_value<ConfigOptionString>()->value);
auto temp = new wxStaticText(m_parent, wxID_ANY, legend, wxDefaultPosition, size, wxST_ELLIPSIZE_MIDDLE);
temp->SetFont(Slic3r::GUI::wxGetApp().normal_font());
temp->SetBackgroundStyle(wxBG_STYLE_PAINT);
@ -1066,7 +1054,7 @@ void SliderCtrl::BUILD()
auto temp = new wxBoxSizer(wxHORIZONTAL);
auto def_val = static_cast<const ConfigOptionInt*>(m_opt.default_value)->value;
auto def_val = m_opt.get_default_value<ConfigOptionInt>()->value;
auto min = m_opt.min == INT_MIN ? 0 : m_opt.min;
auto max = m_opt.max == INT_MAX ? 100 : m_opt.max;

View File

@ -1783,7 +1783,7 @@ void GLCanvas3D::mirror_selection(Axis axis)
{
m_selection.mirror(axis);
do_mirror();
wxGetApp().obj_manipul()->update_settings_value(m_selection);
wxGetApp().obj_manipul()->set_dirty();
}
// Reload the 3D scene of
@ -1828,6 +1828,7 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
// State of the sla_steps for all SLAPrintObjects.
std::vector<SLASupportState> sla_support_state;
std::vector<size_t> instance_ids_selected;
std::vector<size_t> map_glvolume_old_to_new(m_volumes.volumes.size(), size_t(-1));
std::vector<GLVolume*> glvolumes_new;
glvolumes_new.reserve(m_volumes.volumes.size());
@ -1892,6 +1893,10 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
if (it != model_volume_state.end() && it->geometry_id == key.geometry_id)
mvs = &(*it);
}
// Emplace instance ID of the volume. Both the aux volumes and model volumes share the same instance ID.
// The wipe tower has its own wipe_tower_instance_id().
if (m_selection.contains_volume(volume_id))
instance_ids_selected.emplace_back(volume->geometry_id.second);
if (mvs == nullptr || force_full_scene_refresh) {
// This GLVolume will be released.
if (volume->is_wipe_tower) {
@ -1923,13 +1928,18 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
}
}
}
sort_remove_duplicates(instance_ids_selected);
}
if (m_reload_delayed)
return;
bool update_object_list = false;
if (m_regenerate_volumes)
{
if (m_volumes.volumes != glvolumes_new)
update_object_list = true;
m_volumes.volumes = std::move(glvolumes_new);
for (unsigned int obj_idx = 0; obj_idx < (unsigned int)m_model->objects.size(); ++ obj_idx) {
const ModelObject &model_object = *m_model->objects[obj_idx];
@ -1944,12 +1954,16 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
// New volume.
m_volumes.load_object_volume(&model_object, obj_idx, volume_idx, instance_idx, m_color_by, m_use_VBOs && m_initialized);
m_volumes.volumes.back()->geometry_id = key.geometry_id;
update_object_list = true;
} else {
// Recycling an old GLVolume.
GLVolume &existing_volume = *m_volumes.volumes[it->volume_idx];
assert(existing_volume.geometry_id == key.geometry_id);
// Update the Object/Volume/Instance indices into the current Model.
existing_volume.composite_id = it->composite_id;
if (existing_volume.composite_id != it->composite_id) {
existing_volume.composite_id = it->composite_id;
update_object_list = true;
}
}
}
}
@ -2051,13 +2065,17 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
update_volumes_colors_by_extruder();
// Update selection indices based on the old/new GLVolumeCollection.
m_selection.volumes_changed(map_glvolume_old_to_new);
if (m_selection.get_mode() == Selection::Instance)
m_selection.instances_changed(instance_ids_selected);
else
m_selection.volumes_changed(map_glvolume_old_to_new);
}
m_gizmos.update_data(*this);
// Update the toolbar
post_event(SimpleEvent(EVT_GLCANVAS_OBJECT_SELECT));
if (update_object_list)
post_event(SimpleEvent(EVT_GLCANVAS_OBJECT_SELECT));
// checks for geometry outside the print volume to render it accordingly
if (!m_volumes.empty())
@ -2108,7 +2126,7 @@ void GLCanvas3D::reload_scene(bool refresh_immediately, bool force_full_scene_re
// to force a reset of its cache
auto manip = wxGetApp().obj_manipul();
if (manip != nullptr)
manip->update_settings_value(m_selection);
manip->set_dirty();
}
// and force this canvas to be redrawn.
@ -2796,7 +2814,7 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
m_regenerate_volumes = false;
m_selection.translate(cur_pos - m_mouse.drag.start_position_3D);
wxGetApp().obj_manipul()->update_settings_value(m_selection);
wxGetApp().obj_manipul()->set_dirty();
m_dirty = true;
}
}
@ -2856,7 +2874,7 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
{
m_regenerate_volumes = false;
do_move();
wxGetApp().obj_manipul()->update_settings_value(m_selection);
wxGetApp().obj_manipul()->set_dirty();
// Let the platter know that the dragging finished, so a delayed refresh
// of the scene with the background processing data should be performed.
post_event(SimpleEvent(EVT_GLCANVAS_MOUSE_DRAGGING_FINISHED));
@ -2875,7 +2893,7 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
{
m_selection.clear();
m_selection.set_mode(Selection::Instance);
wxGetApp().obj_manipul()->update_settings_value(m_selection);
wxGetApp().obj_manipul()->set_dirty();
m_gizmos.reset_all_states();
m_gizmos.update_data(*this);
post_event(SimpleEvent(EVT_GLCANVAS_OBJECT_SELECT));
@ -2902,7 +2920,7 @@ void GLCanvas3D::on_mouse(wxMouseEvent& evt)
m_gizmos.refresh_on_off_state(m_selection);
post_event(SimpleEvent(EVT_GLCANVAS_OBJECT_SELECT));
m_gizmos.update_data(*this);
wxGetApp().obj_manipul()->update_settings_value(m_selection);
wxGetApp().obj_manipul()->set_dirty();
// forces a frame render to update the view before the context menu is shown
render();

View File

@ -120,7 +120,7 @@ ObjectList::ObjectList(wxWindow* parent) :
#endif //__WXMSW__
});
Bind(wxEVT_CHAR, [this](wxKeyEvent& event) { key_event(event); }); // doesn't work on OSX
// Bind(wxEVT_CHAR, [this](wxKeyEvent& event) { key_event(event); }); // doesn't work on OSX
#ifdef __WXMSW__
GetMainWindow()->Bind(wxEVT_MOTION, [this](wxMouseEvent& event) {
@ -142,9 +142,27 @@ ObjectList::ObjectList(wxWindow* parent) :
Bind(wxCUSTOMEVT_LAST_VOLUME_IS_DELETED, [this](wxCommandEvent& e) { last_volume_is_deleted(e.GetInt()); });
#ifdef __WXOSX__
Bind(wxEVT_KEY_DOWN, &ObjectList::OnChar, this);
// Bind(wxEVT_KEY_DOWN, &ObjectList::OnChar, this);
#endif //__WXOSX__
{
// Accelerators
wxAcceleratorEntry entries[6];
entries[0].Set(wxACCEL_CTRL, (int) 'C', wxID_COPY);
entries[1].Set(wxACCEL_CTRL, (int) 'X', wxID_CUT);
entries[2].Set(wxACCEL_CTRL, (int) 'V', wxID_PASTE);
entries[3].Set(wxACCEL_CTRL, (int) 'A', wxID_SELECTALL);
entries[4].Set(wxACCEL_NORMAL, WXK_DELETE, wxID_DELETE);
entries[5].Set(wxACCEL_NORMAL, WXK_BACK, wxID_DELETE);
wxAcceleratorTable accel(6, entries);
SetAcceleratorTable(accel);
this->Bind(wxEVT_MENU, [this](wxCommandEvent &evt) { wxPostEvent((wxEvtHandler*)wxGetApp().plater()->canvas3D()->get_wxglcanvas(), SimpleEvent(EVT_GLTOOLBAR_COPY)); }, wxID_COPY);
this->Bind(wxEVT_MENU, [this](wxCommandEvent &evt) { wxPostEvent((wxEvtHandler*)wxGetApp().plater()->canvas3D()->get_wxglcanvas(), SimpleEvent(EVT_GLTOOLBAR_PASTE)); }, wxID_PASTE);
this->Bind(wxEVT_MENU, [this](wxCommandEvent &evt) { this->select_item_all_children(); }, wxID_SELECTALL);
this->Bind(wxEVT_MENU, [this](wxCommandEvent &evt) { this->remove(); }, wxID_DELETE);
}
Bind(wxEVT_SIZE, ([this](wxSizeEvent &e) { this->EnsureVisible(this->GetCurrentItem()); e.Skip(); }));
}
@ -1466,19 +1484,12 @@ Geometry::Transformation volume_to_bed_transformation(const Geometry::Transforma
{
Geometry::Transformation out;
// Is the angle close to a multiple of 90 degrees?
auto ninety_degrees = [](double a) {
a = fmod(std::abs(a), 0.5 * PI);
if (a > 0.25 * PI)
a = 0.5 * PI - a;
return a < 0.001;
};
if (instance_transformation.is_scaling_uniform()) {
// No need to run the non-linear least squares fitting for uniform scaling.
// Just set the inverse.
out.set_from_transform(instance_transformation.get_matrix(true).inverse());
}
else if (ninety_degrees(instance_transformation.get_rotation().x()) && ninety_degrees(instance_transformation.get_rotation().y()) && ninety_degrees(instance_transformation.get_rotation().z()))
else if (Geometry::is_rotation_ninety_degrees(instance_transformation.get_rotation()))
{
// Anisotropic scaling, rotation by multiples of ninety degrees.
Eigen::Matrix3d instance_rotation_trafo =

View File

@ -17,6 +17,50 @@ namespace Slic3r
namespace GUI
{
static wxBitmapComboBox* create_word_local_combo(wxWindow *parent)
{
wxSize size(15 * wxGetApp().em_unit(), -1);
wxBitmapComboBox *temp = nullptr;
#ifdef __WXOSX__
/* wxBitmapComboBox with wxCB_READONLY style return NULL for GetTextCtrl(),
* so ToolTip doesn't shown.
* Next workaround helps to solve this problem
*/
temp = new wxBitmapComboBox();
temp->SetTextCtrlStyle(wxTE_READONLY);
temp->Create(parent, wxID_ANY, wxString(""), wxDefaultPosition, size, 0, nullptr);
#else
temp = new wxBitmapComboBox(parent, wxID_ANY, wxString(""), wxDefaultPosition, size, 0, nullptr, wxCB_READONLY);
#endif //__WXOSX__
temp->SetFont(Slic3r::GUI::wxGetApp().normal_font());
temp->SetBackgroundStyle(wxBG_STYLE_PAINT);
temp->Append(_(L("World")));
temp->Append(_(L("Local")));
temp->SetSelection(0);
temp->SetValue(temp->GetString(0));
#ifndef __WXGTK__
/* Workaround for a correct rendering of the control without Bitmap (under MSW and OSX):
*
* 1. We should create small Bitmap to fill Bitmaps RefData,
* ! in this case wxBitmap.IsOK() return true.
* 2. But then set width to 0 value for no using of bitmap left and right spacing
* 3. Set this empty bitmap to the at list one item and BitmapCombobox will be recreated correct
*
* Note: Set bitmap height to the Font size because of OSX rendering.
*/
wxBitmap empty_bmp(1, temp->GetFont().GetPixelSize().y + 2);
empty_bmp.SetWidth(0);
temp->SetItemBitmap(0, empty_bmp);
#endif
temp->SetToolTip(_(L("Select coordinate space, in which the transformation will be performed.")));
return temp;
}
ObjectManipulation::ObjectManipulation(wxWindow* parent) :
OG_Settings(parent, true)
#ifndef __APPLE__
@ -76,11 +120,12 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
def.label = "";
def.gui_type = "legend";
def.tooltip = L("Object name");
def.width = 21;
#ifdef __APPLE__
def.width = 19;
#else
def.width = 21;
#endif
def.default_value = new ConfigOptionString{ " " };
def.set_default_value(new ConfigOptionString{ " " });
line.append_option(Option(def, "object_name"));
m_og->append_line(line);
@ -92,22 +137,26 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
def.type = coString;
def.width = field_width/*50*/;
std::vector<std::string> axes{ "x", "y", "z" };
for (const auto axis : axes) {
const auto label = boost::algorithm::to_upper_copy(axis);
def.default_value = new ConfigOptionString{ " " + label };
for (const std::string axis : { "x", "y", "z" }) {
const std::string label = boost::algorithm::to_upper_copy(axis);
def.set_default_value(new ConfigOptionString{ " " + label });
Option option = Option(def, axis + "_axis_legend");
line.append_option(option);
}
line.near_label_widget = [this](wxWindow* parent) {
wxBitmapComboBox *combo = create_word_local_combo(parent);
combo->Bind(wxEVT_COMBOBOX, ([this](wxCommandEvent &evt) { this->set_world_coordinates(evt.GetSelection() != 1); }), combo->GetId());
m_word_local_combo = combo;
return combo;
};
m_og->append_line(line);
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.set_default_value(new ConfigOptionFloat(0.0));
def.width = field_width/*50*/;
// Add "uniform scaling" button in front of "Scale" option
@ -133,11 +182,10 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
const std::string lower_name = boost::algorithm::to_lower_copy(option_name);
std::vector<std::string> axes{ "x", "y", "z" };
for (auto axis : axes) {
if (axis == "z")
for (const char *axis : { "_x", "_y", "_z" }) {
if (axis[1] == 'z')
def.sidetext = sidetext;
Option option = Option(def, lower_name + "_" + axis);
Option option = Option(def, lower_name + axis);
option.opt.full_width = true;
line.append_option(option);
}
@ -163,15 +211,19 @@ ObjectManipulation::ObjectManipulation(wxWindow* parent) :
void ObjectManipulation::Show(const bool show)
{
if (show == IsShown())
return;
if (show != IsShown()) {
m_og->Show(show);
m_og->Show(show);
if (show && wxGetApp().get_mode() != comSimple) {
m_og->get_grid_sizer()->Show(size_t(0), false);
m_og->get_grid_sizer()->Show(size_t(1), false);
}
}
if (show && wxGetApp().get_mode() != comSimple) {
m_og->get_grid_sizer()->Show(size_t(0), false);
m_og->get_grid_sizer()->Show(size_t(1), false);
}
if (show) {
bool show_world_local_combo = wxGetApp().plater()->canvas3D()->get_selection().is_single_full_instance();
m_word_local_combo->Show(show_world_local_combo);
}
}
bool ObjectManipulation::IsShown()
@ -181,9 +233,10 @@ bool ObjectManipulation::IsShown()
void ObjectManipulation::UpdateAndShow(const bool show)
{
if (show) {
update_settings_value(wxGetApp().plater()->canvas3D()->get_selection());
}
if (show) {
this->set_dirty();
this->update_if_dirty();
}
OG_Settings::UpdateAndShow(show);
}
@ -200,35 +253,34 @@ void ObjectManipulation::update_settings_value(const Selection& selection)
// all volumes in the selection belongs to the same instance, any of them contains the needed instance data, so we take the first one
const GLVolume* volume = selection.get_volume(*selection.get_volume_idxs().begin());
m_new_position = volume->get_instance_offset();
m_new_rotation = volume->get_instance_rotation();
m_new_scale = volume->get_instance_scaling_factor();
int obj_idx = volume->object_idx();
int instance_idx = volume->instance_idx();
if ((0 <= obj_idx) && (obj_idx < (int)wxGetApp().model_objects()->size()))
{
bool changed_box = false;
if (!m_cache.instance.matches_object(obj_idx))
{
m_cache.instance.set(obj_idx, instance_idx, (*wxGetApp().model_objects())[obj_idx]->raw_mesh_bounding_box().size());
changed_box = true;
}
if (changed_box || !m_cache.instance.matches_instance(instance_idx) || !m_cache.scale.isApprox(100.0 * m_new_scale))
m_new_size = (volume->get_instance_transformation().get_matrix(true, true) * m_cache.instance.box_size).cwiseAbs();
}
else
// this should never happen
m_new_size = Vec3d::Zero();
// Verify whether the instance rotation is multiples of 90 degrees, so that the scaling in world coordinates is possible.
if (m_world_coordinates && ! m_uniform_scale &&
! Geometry::is_rotation_ninety_degrees(volume->get_instance_rotation())) {
// Manipulating an instance in the world coordinate system, rotation is not multiples of ninety degrees, therefore enforce uniform scaling.
m_uniform_scale = true;
m_lock_bnt->SetLock(true);
}
if (m_world_coordinates) {
m_new_rotate_label_string = L("Rotate");
m_new_rotation = Vec3d::Zero();
m_new_size = selection.get_bounding_box().size();
m_new_scale = m_new_size.cwiseProduct(selection.get_unscaled_instance_bounding_box().size().cwiseInverse()) * 100.;
} else {
m_new_rotation = volume->get_instance_rotation() * (180. / M_PI);
m_new_size = volume->get_instance_transformation().get_scaling_factor().cwiseProduct((*wxGetApp().model_objects())[volume->object_idx()]->raw_mesh_bounding_box().size());
m_new_scale = volume->get_instance_scaling_factor() * 100.;
}
m_new_enabled = true;
}
else if (selection.is_single_full_object() && obj_list->is_selected(itObject))
{
m_cache.instance.reset();
const BoundingBoxf3& box = selection.get_bounding_box();
m_new_position = box.center();
m_new_rotation = Vec3d::Zero();
m_new_scale = Vec3d(1.0, 1.0, 1.0);
m_new_scale = Vec3d(100., 100., 100.);
m_new_size = box.size();
m_new_rotate_label_string = L("Rotate");
m_new_scale_label_string = L("Scale");
@ -236,14 +288,12 @@ void ObjectManipulation::update_settings_value(const Selection& selection)
}
else if (selection.is_single_modifier() || selection.is_single_volume())
{
m_cache.instance.reset();
// the selection contains a single volume
const GLVolume* volume = selection.get_volume(*selection.get_volume_idxs().begin());
m_new_position = volume->get_volume_offset();
m_new_rotation = volume->get_volume_rotation();
m_new_scale = volume->get_volume_scaling_factor();
m_new_size = (volume->get_volume_transformation().get_matrix(true, true) * volume->bounding_box.size()).cwiseAbs();
m_new_rotation = volume->get_volume_rotation() * (180. / M_PI);
m_new_scale = volume->get_volume_scaling_factor() * 100.;
m_new_size = volume->get_volume_transformation().get_scaling_factor().cwiseProduct(volume->bounding_box.size());
m_new_enabled = true;
}
else if (obj_list->multiple_selection() || obj_list->is_selected(itInstanceRoot))
@ -255,87 +305,51 @@ void ObjectManipulation::update_settings_value(const Selection& selection)
m_new_size = selection.get_bounding_box().size();
m_new_enabled = true;
}
else
reset_settings_value();
m_dirty = true;
else {
// No selection, reset the cache.
// assert(selection.is_empty());
reset_settings_value();
}
}
void ObjectManipulation::update_if_dirty()
{
if (!m_dirty)
if (! m_dirty)
return;
if (m_cache.move_label_string != _(m_new_move_label_string)+ ":")
{
m_cache.move_label_string = _(m_new_move_label_string)+ ":";
m_move_Label->SetLabel(m_cache.move_label_string);
const Selection &selection = wxGetApp().plater()->canvas3D()->get_selection();
this->update_settings_value(selection);
auto update_label = [](wxString &label_cache, const std::string &new_label, wxStaticText *widget) {
wxString new_label_localized = _(new_label) + ":";
if (label_cache != new_label_localized) {
label_cache = new_label_localized;
widget->SetLabel(new_label_localized);
}
};
update_label(m_cache.move_label_string, m_new_move_label_string, m_move_Label);
update_label(m_cache.rotate_label_string, m_new_rotate_label_string, m_rotate_Label);
update_label(m_cache.scale_label_string, m_new_scale_label_string, m_scale_Label);
char axis[2] = "x";
for (int i = 0; i < 3; ++ i, ++ axis[0]) {
auto update = [this, i, &axis](Vec3d &cached, Vec3d &cached_rounded, const char *key, const Vec3d &new_value) {
wxString new_text = double_to_string(new_value(i), 2);
double new_rounded;
new_text.ToDouble(&new_rounded);
if (std::abs(cached_rounded(i) - new_rounded) > EPSILON) {
cached_rounded(i) = new_rounded;
m_og->set_value(std::string(key) + axis, new_text);
}
cached(i) = new_value(i);
};
update(m_cache.position, m_cache.position_rounded, "position_", m_new_position);
update(m_cache.scale, m_cache.scale_rounded, "scale_", m_new_scale);
update(m_cache.size, m_cache.size_rounded, "size_", m_new_size);
update(m_cache.rotation, m_cache.rotation_rounded, "rotation_", m_new_rotation);
}
if (m_cache.rotate_label_string != _(m_new_rotate_label_string)+ ":")
{
m_cache.rotate_label_string = _(m_new_rotate_label_string)+ ":";
m_rotate_Label->SetLabel(m_cache.rotate_label_string);
}
if (m_cache.scale_label_string != _(m_new_scale_label_string)+ ":")
{
m_cache.scale_label_string = _(m_new_scale_label_string)+ ":";
m_scale_Label->SetLabel(m_cache.scale_label_string);
}
if (m_cache.position(0) != m_new_position(0))
m_og->set_value("position_x", double_to_string(m_new_position(0), 2));
if (m_cache.position(1) != m_new_position(1))
m_og->set_value("position_y", double_to_string(m_new_position(1), 2));
if (m_cache.position(2) != m_new_position(2))
m_og->set_value("position_z", double_to_string(m_new_position(2), 2));
m_cache.position = m_new_position;
auto scale = m_new_scale * 100.0;
if (m_cache.scale(0) != scale(0))
m_og->set_value("scale_x", double_to_string(scale(0), 2));
if (m_cache.scale(1) != scale(1))
m_og->set_value("scale_y", double_to_string(scale(1), 2));
if (m_cache.scale(2) != scale(2))
m_og->set_value("scale_z", double_to_string(scale(2), 2));
m_cache.scale = scale;
if (m_cache.size(0) != m_new_size(0))
m_og->set_value("size_x", double_to_string(m_new_size(0), 2));
if (m_cache.size(1) != m_new_size(1))
m_og->set_value("size_y", double_to_string(m_new_size(1), 2));
if (m_cache.size(2) != m_new_size(2))
m_og->set_value("size_z", double_to_string(m_new_size(2), 2));
m_cache.size = m_new_size;
Vec3d deg_rotation;
for (size_t i = 0; i < 3; ++i)
{
deg_rotation(i) = Geometry::rad2deg(m_new_rotation(i));
}
if ((m_cache.rotation(0) != m_new_rotation(0)) || (m_new_rotation(0) == 0.0))
m_og->set_value("rotation_x", double_to_string(deg_rotation(0), 2));
if ((m_cache.rotation(1) != m_new_rotation(1)) || (m_new_rotation(1) == 0.0))
m_og->set_value("rotation_y", double_to_string(deg_rotation(1), 2));
if ((m_cache.rotation(2) != m_new_rotation(2)) || (m_new_rotation(2) == 0.0))
m_og->set_value("rotation_z", double_to_string(deg_rotation(2), 2));
m_cache.rotation = deg_rotation;
if (wxGetApp().plater()->canvas3D()->get_selection().requires_uniform_scale()) {
if (selection.requires_uniform_scale()) {
m_lock_bnt->SetLock(true);
m_lock_bnt->Disable();
}
@ -344,6 +358,12 @@ void ObjectManipulation::update_if_dirty()
m_lock_bnt->Enable();
}
{
int new_selection = m_world_coordinates ? 0 : 1;
if (m_word_local_combo->GetSelection() != new_selection)
m_word_local_combo->SetSelection(new_selection);
}
if (m_new_enabled)
m_og->enable();
else
@ -382,12 +402,19 @@ void ObjectManipulation::reset_settings_value()
m_new_scale = Vec3d::Ones();
m_new_size = Vec3d::Zero();
m_new_enabled = false;
m_cache.instance.reset();
m_dirty = true;
// no need to set the dirty flag here as this method is called from update_settings_value(),
// which is called from update_if_dirty(), which resets the dirty flag anyways.
// m_dirty = true;
}
void ObjectManipulation::change_position_value(const Vec3d& position)
void ObjectManipulation::change_position_value(int axis, double value)
{
if (std::abs(m_cache.position_rounded(axis) - value) < EPSILON)
return;
Vec3d position = m_cache.position;
position(axis) = value;
auto canvas = wxGetApp().plater()->canvas3D();
Selection& selection = canvas->get_selection();
selection.start_dragging();
@ -395,113 +422,102 @@ void ObjectManipulation::change_position_value(const Vec3d& position)
canvas->do_move();
m_cache.position = position;
m_cache.position_rounded(axis) = DBL_MAX;
this->UpdateAndShow(true);
}
void ObjectManipulation::change_rotation_value(const Vec3d& rotation)
void ObjectManipulation::change_rotation_value(int axis, double value)
{
if (std::abs(m_cache.rotation_rounded(axis) - value) < EPSILON)
return;
Vec3d rotation = m_cache.rotation;
rotation(axis) = value;
GLCanvas3D* canvas = wxGetApp().plater()->canvas3D();
const Selection& selection = canvas->get_selection();
Selection& selection = canvas->get_selection();
TransformationType transformation_type(TransformationType::World_Relative_Joint);
if (selection.is_single_full_instance() || selection.requires_local_axes())
transformation_type.set_independent();
if (selection.is_single_full_instance()) {
if (selection.is_single_full_instance() && ! m_world_coordinates) {
//FIXME Selection::rotate() does not process absoulte rotations correctly: It does not recognize the axis index, which was changed.
// transformation_type.set_absolute();
transformation_type.set_local();
}
Vec3d rad_rotation;
for (size_t i = 0; i < 3; ++i)
rad_rotation(i) = Geometry::deg2rad((transformation_type.absolute()) ? rotation(i) : rotation(i) - m_cache.rotation(i));
canvas->get_selection().start_dragging();
canvas->get_selection().rotate(rad_rotation, transformation_type);
selection.start_dragging();
selection.rotate(
(M_PI / 180.0) * (transformation_type.absolute() ? rotation : rotation - m_cache.rotation),
transformation_type);
canvas->do_rotate();
m_cache.rotation = rotation;
m_cache.rotation_rounded(axis) = DBL_MAX;
this->UpdateAndShow(true);
}
void ObjectManipulation::change_scale_value(const Vec3d& scale)
void ObjectManipulation::change_scale_value(int axis, double value)
{
Vec3d scaling_factor = scale;
const Selection& selection = wxGetApp().plater()->canvas3D()->get_selection();
if (m_uniform_scale || selection.requires_uniform_scale())
{
Vec3d abs_scale_diff = (scale - m_cache.scale).cwiseAbs();
double max_diff = abs_scale_diff(X);
Axis max_diff_axis = X;
if (max_diff < abs_scale_diff(Y))
{
max_diff = abs_scale_diff(Y);
max_diff_axis = Y;
}
if (max_diff < abs_scale_diff(Z))
{
max_diff = abs_scale_diff(Z);
max_diff_axis = Z;
}
scaling_factor = scale(max_diff_axis) * Vec3d::Ones();
}
if (std::abs(m_cache.scale_rounded(axis) - value) < EPSILON)
return;
scaling_factor *= 0.01;
Vec3d scale = m_cache.scale;
scale(axis) = value;
auto canvas = wxGetApp().plater()->canvas3D();
canvas->get_selection().start_dragging();
canvas->get_selection().scale(scaling_factor, false);
canvas->do_scale();
if (!m_cache.scale.isApprox(scale))
m_cache.instance.instance_idx = -1;
this->do_scale(axis, scale);
m_cache.scale = scale;
m_cache.scale_rounded(axis) = DBL_MAX;
this->UpdateAndShow(true);
}
void ObjectManipulation::change_size_value(const Vec3d& size)
void ObjectManipulation::change_size_value(int axis, double value)
{
if (std::abs(m_cache.size_rounded(axis) - value) < EPSILON)
return;
Vec3d size = m_cache.size;
size(axis) = value;
const Selection& selection = wxGetApp().plater()->canvas3D()->get_selection();
Vec3d ref_size = m_cache.size;
if (selection.is_single_volume() || selection.is_single_modifier())
{
const GLVolume* volume = selection.get_volume(*selection.get_volume_idxs().begin());
ref_size = volume->bounding_box.size();
}
else if (selection.is_single_full_instance())
ref_size = m_cache.instance.box_size;
if (selection.is_single_volume() || selection.is_single_modifier())
ref_size = selection.get_volume(*selection.get_volume_idxs().begin())->bounding_box.size();
else if (selection.is_single_full_instance())
ref_size = m_world_coordinates ?
selection.get_unscaled_instance_bounding_box().size() :
(*wxGetApp().model_objects())[selection.get_volume(*selection.get_volume_idxs().begin())->object_idx()]->raw_mesh_bounding_box().size();
Vec3d scale = 100.0 * Vec3d(size(0) / ref_size(0), size(1) / ref_size(1), size(2) / ref_size(2));
Vec3d scaling_factor = scale;
if (m_uniform_scale || selection.requires_uniform_scale())
{
Vec3d abs_scale_diff = (scale - m_cache.scale).cwiseAbs();
double max_diff = abs_scale_diff(X);
Axis max_diff_axis = X;
if (max_diff < abs_scale_diff(Y))
{
max_diff = abs_scale_diff(Y);
max_diff_axis = Y;
}
if (max_diff < abs_scale_diff(Z))
{
max_diff = abs_scale_diff(Z);
max_diff_axis = Z;
}
scaling_factor = scale(max_diff_axis) * Vec3d::Ones();
}
scaling_factor *= 0.01;
auto canvas = wxGetApp().plater()->canvas3D();
canvas->get_selection().start_dragging();
canvas->get_selection().scale(scaling_factor, false);
canvas->do_scale();
this->do_scale(axis, 100. * Vec3d(size(0) / ref_size(0), size(1) / ref_size(1), size(2) / ref_size(2)));
m_cache.size = size;
m_cache.size_rounded(axis) = DBL_MAX;
this->UpdateAndShow(true);
}
void ObjectManipulation::on_change(const t_config_option_key& opt_key, const boost::any& value)
void ObjectManipulation::do_scale(int axis, const Vec3d &scale) const
{
Selection& selection = wxGetApp().plater()->canvas3D()->get_selection();
Vec3d scaling_factor = scale;
TransformationType transformation_type(TransformationType::World_Relative_Joint);
if (selection.is_single_full_instance()) {
transformation_type.set_absolute();
if (! m_world_coordinates)
transformation_type.set_local();
}
if (m_uniform_scale || selection.requires_uniform_scale())
scaling_factor = scale(axis) * Vec3d::Ones();
selection.start_dragging();
selection.scale(scaling_factor * 0.01, transformation_type);
wxGetApp().plater()->canvas3D()->do_scale();
}
void ObjectManipulation::on_change(t_config_option_key opt_key, const boost::any& value)
{
// needed to hide the visual hints in 3D scene
wxGetApp().plater()->canvas3D()->handle_sidebar_focus_event(opt_key, false);
@ -512,24 +528,17 @@ void ObjectManipulation::on_change(const t_config_option_key& opt_key, const boo
if (!m_cache.is_valid())
return;
std::vector<std::string> axes{ "_x", "_y", "_z" };
int axis = opt_key.back() - 'x';
double new_value = boost::any_cast<double>(m_og->get_value(opt_key));
std::string param;
std::copy(opt_key.begin(), opt_key.end() - 2, std::back_inserter(param));
size_t i = 0;
Vec3d new_value;
for (auto axis : axes)
new_value(i++) = boost::any_cast<double>(m_og->get_value(param + axis));
if (param == "position")
change_position_value(new_value);
else if (param == "rotation")
change_rotation_value(new_value);
else if (param == "scale")
change_scale_value(new_value);
else if (param == "size")
change_size_value(new_value);
if (boost::starts_with(opt_key, "position_"))
change_position_value(axis, new_value);
else if (boost::starts_with(opt_key, "rotation_"))
change_rotation_value(axis, new_value);
else if (boost::starts_with(opt_key, "scale_"))
change_scale_value(axis, new_value);
else if (boost::starts_with(opt_key, "size_"))
change_size_value(axis, new_value);
}
void ObjectManipulation::on_fill_empty_value(const std::string& opt_key)
@ -543,21 +552,62 @@ void ObjectManipulation::on_fill_empty_value(const std::string& opt_key)
if (!m_cache.is_valid())
return;
std::string param;
std::copy(opt_key.begin(), opt_key.end() - 2, std::back_inserter(param));
const Vec3d *vec = nullptr;
Vec3d *rounded = nullptr;
if (boost::starts_with(opt_key, "position_")) {
vec = &m_cache.position;
rounded = &m_cache.position_rounded;
} else if (boost::starts_with(opt_key, "rotation_")) {
vec = &m_cache.rotation;
rounded = &m_cache.rotation_rounded;
} else if (boost::starts_with(opt_key, "scale_")) {
vec = &m_cache.scale;
rounded = &m_cache.scale_rounded;
} else if (boost::starts_with(opt_key, "size_")) {
vec = &m_cache.size;
rounded = &m_cache.size_rounded;
} else
assert(false);
double value = 0.0;
auto opt_key_to_axis = [&opt_key]() { return opt_key.back() == 'x' ? 0 : opt_key.back() == 'y' ? 1 : 2; };
if (param == "position")
value = m_cache.position(opt_key_to_axis());
else if (param == "rotation")
value = m_cache.rotation(opt_key_to_axis());
else if (param == "scale")
value = m_cache.scale(opt_key_to_axis());
else if (param == "size")
value = m_cache.size(opt_key_to_axis());
if (vec != nullptr) {
int axis = opt_key.back() - 'x';
wxString new_text = double_to_string((*vec)(axis));
m_og->set_value(opt_key, new_text);
new_text.ToDouble(&(*rounded)(axis));
}
}
m_og->set_value(opt_key, double_to_string(value));
void ObjectManipulation::set_uniform_scaling(const bool new_value)
{
const Selection &selection = wxGetApp().plater()->canvas3D()->get_selection();
if (selection.is_single_full_instance() && m_world_coordinates && !new_value) {
// Verify whether the instance rotation is multiples of 90 degrees, so that the scaling in world coordinates is possible.
// all volumes in the selection belongs to the same instance, any of them contains the needed instance data, so we take the first one
const GLVolume* volume = selection.get_volume(*selection.get_volume_idxs().begin());
// Is the angle close to a multiple of 90 degrees?
if (! Geometry::is_rotation_ninety_degrees(volume->get_instance_rotation())) {
// Cannot apply scaling in the world coordinate system.
wxMessageDialog dlg(GUI::wxGetApp().mainframe,
_(L("The currently manipulated object is tilted (rotation angles are not multiples of 90°).\n"
"Non-uniform scaling of tilted objects is only possible in the World coordinate system,\n"
"once the rotation is embedded into the object coordinates.\n"
"Do you want to proceed?")),
SLIC3R_APP_NAME,
wxYES_NO | wxNO_DEFAULT | wxICON_QUESTION);
if (dlg.ShowModal() != wxID_YES) {
// Enforce uniform scaling.
m_lock_bnt->SetLock(true);
return;
}
// Bake the rotation into the meshes of the object.
(*wxGetApp().model_objects())[volume->composite_id.object_id]->bake_xy_rotation_into_meshes(volume->composite_id.instance_id);
// Update the 3D scene, selections etc.
wxGetApp().plater()->update();
// Recalculate cached values at this panel, refresh the screen.
this->UpdateAndShow(true);
}
}
m_uniform_scale = new_value;
}
void ObjectManipulation::msw_rescale()
@ -569,4 +619,4 @@ void ObjectManipulation::msw_rescale()
}
} //namespace GUI
} //namespace Slic3r
} //namespace Slic3r

View File

@ -6,6 +6,7 @@
#include "GUI_ObjectSettings.hpp"
#include "GLCanvas3D.hpp"
class wxBitmapComboBox;
class wxStaticText;
class LockButton;
class wxStaticBitmap;
@ -20,41 +21,28 @@ class ObjectManipulation : public OG_Settings
struct Cache
{
Vec3d position;
Vec3d position_rounded;
Vec3d rotation;
Vec3d rotation_rounded;
Vec3d scale;
Vec3d scale_rounded;
Vec3d size;
Vec3d size_rounded;
std::string move_label_string;
std::string rotate_label_string;
std::string scale_label_string;
struct Instance
{
int object_idx;
int instance_idx;
Vec3d box_size;
Instance() { reset(); }
void reset() { this->object_idx = -1; this->instance_idx = -1; this->box_size = Vec3d::Zero(); }
void set(int object_idx, int instance_idx, const Vec3d& box_size) { this->object_idx = object_idx; this->instance_idx = instance_idx; this->box_size = box_size; }
bool matches(int object_idx, int instance_idx) const { return (this->object_idx == object_idx) && (this->instance_idx == instance_idx); }
bool matches_object(int object_idx) const { return (this->object_idx == object_idx); }
bool matches_instance(int instance_idx) const { return (this->instance_idx == instance_idx); }
};
Instance instance;
wxString move_label_string;
wxString rotate_label_string;
wxString scale_label_string;
Cache() { reset(); }
void reset()
{
position = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
rotation = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
scale = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
size = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
move_label_string = "";
rotate_label_string = "";
scale_label_string = "";
instance.reset();
position = position_rounded = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
rotation = rotation_rounded = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
scale = scale_rounded = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
size = size_rounded = Vec3d(DBL_MAX, DBL_MAX, DBL_MAX);
move_label_string = wxString();
rotate_label_string = wxString();
scale_label_string = wxString();
}
bool is_valid() const { return position != Vec3d(DBL_MAX, DBL_MAX, DBL_MAX); }
};
@ -77,7 +65,10 @@ class ObjectManipulation : public OG_Settings
Vec3d m_new_size;
bool m_new_enabled;
bool m_uniform_scale {true};
// Does the object manipulation panel work in World or Local coordinates?
bool m_world_coordinates = true;
LockButton* m_lock_bnt{ nullptr };
wxBitmapComboBox* m_word_local_combo = nullptr;
ScalableBitmap m_manifold_warning_bmp;
wxStaticBitmap* m_fix_throught_netfab_bitmap;
@ -95,13 +86,15 @@ public:
bool IsShown() override;
void UpdateAndShow(const bool show) override;
void update_settings_value(const Selection& selection);
void set_dirty() { m_dirty = true; }
// Called from the App to update the UI if dirty.
void update_if_dirty();
void set_uniform_scaling(const bool uniform_scale) { m_uniform_scale = uniform_scale;}
void set_uniform_scaling(const bool uniform_scale);
bool get_uniform_scaling() const { return m_uniform_scale; }
// Does the object manipulation panel work in World or Local coordinates?
void set_world_coordinates(const bool world_coordinates) { m_world_coordinates = world_coordinates; this->UpdateAndShow(true); }
bool get_world_coordinates() const { return m_world_coordinates; }
void reset_cache() { m_cache.reset(); }
#ifndef __APPLE__
@ -116,6 +109,7 @@ public:
private:
void reset_settings_value();
void update_settings_value(const Selection& selection);
// update size values after scale unit changing or "gizmos"
void update_size_value(const Vec3d& size);
@ -123,12 +117,13 @@ private:
void update_rotation_value(const Vec3d& rotation);
// change values
void change_position_value(const Vec3d& position);
void change_rotation_value(const Vec3d& rotation);
void change_scale_value(const Vec3d& scale);
void change_size_value(const Vec3d& size);
void change_position_value(int axis, double value);
void change_rotation_value(int axis, double value);
void change_scale_value(int axis, double value);
void change_size_value(int axis, double value);
void do_scale(int axis, const Vec3d &scale) const;
void on_change(const t_config_option_key& opt_key, const boost::any& value);
void on_change(t_config_option_key opt_key, const boost::any& value);
void on_fill_empty_value(const std::string& opt_key);
};

View File

@ -590,7 +590,7 @@ bool GLGizmosManager::on_mouse(wxMouseEvent& evt, GLCanvas3D& canvas)
// Rotate the object so the normal points downward:
selection.flattening_rotate(get_flattening_normal());
canvas.do_flatten();
wxGetApp().obj_manipul()->update_settings_value(selection);
wxGetApp().obj_manipul()->set_dirty();
}
canvas.set_as_dirty();
@ -623,14 +623,17 @@ bool GLGizmosManager::on_mouse(wxMouseEvent& evt, GLCanvas3D& canvas)
{
// Apply new temporary offset
selection.translate(get_displacement());
wxGetApp().obj_manipul()->update_settings_value(selection);
wxGetApp().obj_manipul()->set_dirty();
break;
}
case Scale:
{
// Apply new temporary scale factors
selection.scale(get_scale(), evt.AltDown());
wxGetApp().obj_manipul()->update_settings_value(selection);
TransformationType transformation_type(TransformationType::Local_Absolute_Joint);
if (evt.AltDown())
transformation_type.set_independent();
selection.scale(get_scale(), transformation_type);
wxGetApp().obj_manipul()->set_dirty();
break;
}
case Rotate:
@ -640,7 +643,7 @@ bool GLGizmosManager::on_mouse(wxMouseEvent& evt, GLCanvas3D& canvas)
if (evt.AltDown())
transformation_type.set_independent();
selection.rotate(get_rotation(), transformation_type);
wxGetApp().obj_manipul()->update_settings_value(selection);
wxGetApp().obj_manipul()->set_dirty();
break;
}
default:
@ -677,7 +680,7 @@ bool GLGizmosManager::on_mouse(wxMouseEvent& evt, GLCanvas3D& canvas)
stop_dragging();
update_data(canvas);
wxGetApp().obj_manipul()->update_settings_value(selection);
wxGetApp().obj_manipul()->set_dirty();
// Let the platter know that the dragging finished, so a delayed refresh
// of the scene with the background processing data should be performed.
canvas.post_event(SimpleEvent(EVT_GLCANVAS_MOUSE_DRAGGING_FINISHED));

View File

@ -109,8 +109,8 @@ void KBShortcutsDialog::fill_shortcuts()
main_shortcuts.push_back(Shortcut(ctrl+"S" ,L("Save project (3MF)")));
main_shortcuts.push_back(Shortcut(ctrl+alt+"L" ,L("Load Config from .ini/amf/3mf/gcode and merge")));
main_shortcuts.push_back(Shortcut(ctrl+"R" ,L("(Re)slice")));
main_shortcuts.push_back(Shortcut(ctrl+"U" ,L("Quick slice")));
main_shortcuts.push_back(Shortcut(ctrl+"Shift+U" ,L("Repeat last quick slice")));
// main_shortcuts.push_back(Shortcut(ctrl+"U" ,L("Quick slice")));
// main_shortcuts.push_back(Shortcut(ctrl+"Shift+U" ,L("Repeat last quick slice")));
main_shortcuts.push_back(Shortcut(ctrl+"1" ,L("Select Plater Tab")));
main_shortcuts.push_back(Shortcut(ctrl+alt+"U" ,L("Quick slice and Save as")));
main_shortcuts.push_back(Shortcut(ctrl+"2" ,L("Select Print Settings Tab")));

View File

@ -49,7 +49,7 @@ LambdaObjectDialog::LambdaObjectDialog(wxWindow* parent,
};
def.type = coFloat;
def.default_value = new ConfigOptionFloat{ 1.0 };
def.set_default_value(new ConfigOptionFloat{ 1.0 });
def.label = L("Length");
Option option(def, "l");
optgroup->append_single_option_line(option);
@ -75,7 +75,7 @@ LambdaObjectDialog::LambdaObjectDialog(wxWindow* parent,
};
def.type = coInt;
def.default_value = new ConfigOptionInt{ 1 };
def.set_default_value(new ConfigOptionInt{ 1 });
def.label = L("Radius");
auto option = Option(def, "cyl_r");
optgroup->append_single_option_line(option);
@ -94,7 +94,7 @@ LambdaObjectDialog::LambdaObjectDialog(wxWindow* parent,
};
def.type = coFloat;
def.default_value = new ConfigOptionFloat{ 1.0 };
def.set_default_value(new ConfigOptionFloat{ 1.0 });
def.label = L("Rho");
auto option = Option(def, "sph_rho");
optgroup->append_single_option_line(option);
@ -112,7 +112,7 @@ LambdaObjectDialog::LambdaObjectDialog(wxWindow* parent,
};
def.type = coFloat;
def.default_value = new ConfigOptionFloat{ 1.0 };
def.set_default_value(new ConfigOptionFloat{ 1.0 });
def.label = L("Height");
auto option = Option(def, "slab_h");
optgroup->append_single_option_line(option);

View File

@ -175,18 +175,21 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
// Build a label if we have it
wxStaticText* label=nullptr;
if (label_width != 0) {
long label_style = staticbox ? 0 : wxALIGN_RIGHT;
if (! line.near_label_widget || ! line.label.IsEmpty()) {
// Only create the label if it is going to be displayed.
long label_style = staticbox ? 0 : wxALIGN_RIGHT;
#ifdef __WXGTK__
// workaround for correct text align of the StaticBox on Linux
// flags wxALIGN_RIGHT and wxALIGN_CENTRE don't work when Ellipsize flags are _not_ given.
// Text is properly aligned only when Ellipsize is checked.
label_style |= staticbox ? 0 : wxST_ELLIPSIZE_END;
// workaround for correct text align of the StaticBox on Linux
// flags wxALIGN_RIGHT and wxALIGN_CENTRE don't work when Ellipsize flags are _not_ given.
// Text is properly aligned only when Ellipsize is checked.
label_style |= staticbox ? 0 : wxST_ELLIPSIZE_END;
#endif /* __WXGTK__ */
label = new wxStaticText(this->ctrl_parent(), wxID_ANY, line.label + (line.label.IsEmpty() ? "" : ": "),
wxDefaultPosition, wxSize(label_width*wxGetApp().em_unit(), -1), label_style);
label->SetBackgroundStyle(wxBG_STYLE_PAINT);
label->SetFont(wxGetApp().normal_font());
label->Wrap(label_width*wxGetApp().em_unit()); // avoid a Linux/GTK bug
label = new wxStaticText(this->ctrl_parent(), wxID_ANY, line.label + (line.label.IsEmpty() ? "" : ": "),
wxDefaultPosition, wxSize(label_width*wxGetApp().em_unit(), -1), label_style);
label->SetBackgroundStyle(wxBG_STYLE_PAINT);
label->SetFont(wxGetApp().normal_font());
label->Wrap(label_width*wxGetApp().em_unit()); // avoid a Linux/GTK bug
}
if (!line.near_label_widget)
grid_sizer->Add(label, 0, (staticbox ? 0 : wxALIGN_RIGHT | wxRIGHT) | wxALIGN_CENTER_VERTICAL, line.label.IsEmpty() ? 0 : 5);
else {
@ -203,7 +206,7 @@ void OptionsGroup::append_line(const Line& line, wxStaticText** full_Label/* = n
sizer->Add(label, 0, (staticbox ? 0 : wxALIGN_RIGHT | wxRIGHT) | wxALIGN_CENTER_VERTICAL, 5);
}
}
if (line.label_tooltip.compare("") != 0)
if (label != nullptr && line.label_tooltip != "")
label->SetToolTip(line.label_tooltip);
}
@ -426,22 +429,21 @@ void ConfigOptionsGroup::back_to_config_value(const DynamicPrintConfig& config,
void ConfigOptionsGroup::on_kill_focus(const std::string& opt_key)
{
if (m_fill_empty_value) {
if (m_fill_empty_value)
m_fill_empty_value(opt_key);
return;
}
reload_config();
else
reload_config();
}
void ConfigOptionsGroup::reload_config() {
for (t_opt_map::iterator it = m_opt_map.begin(); it != m_opt_map.end(); ++it) {
auto opt_id = it->first;
std::string opt_key = m_opt_map.at(opt_id).first;
int opt_index = m_opt_map.at(opt_id).second;
auto option = m_options.at(opt_id).opt;
set_value(opt_id, config_value(opt_key, opt_index, option.gui_flags.compare("serialized") == 0 ));
void ConfigOptionsGroup::reload_config()
{
for (auto &kvp : m_opt_map) {
const std::string &opt_id = kvp.first;
const std::string &opt_key = kvp.second.first;
int opt_index = kvp.second.second;
const ConfigOptionDef &option = m_options.at(opt_id).opt;
this->set_value(opt_key, config_value(opt_key, opt_index, option.gui_flags == "serialized"));
}
}
void ConfigOptionsGroup::Hide()

View File

@ -260,7 +260,7 @@ public:
void back_to_initial_value(const std::string& opt_key) override;
void back_to_sys_value(const std::string& opt_key) override;
void back_to_config_value(const DynamicPrintConfig& config, const std::string& opt_key);
void on_kill_focus(const std::string& opt_key) override;// { reload_config(); }
void on_kill_focus(const std::string& opt_key) override;
void reload_config();
// return value shows visibility : false => all options are hidden
void Hide();

View File

@ -394,16 +394,27 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
}
new_conf.set_key_value("brim_width", new ConfigOptionFloat(new_val));
}
else { //(opt_key == "support")
else {
assert(opt_key == "support");
const wxString& selection = boost::any_cast<wxString>(value);
PrinterTechnology printer_technology = wxGetApp().preset_bundle->printers.get_edited_preset().printer_technology();
auto support_material = selection == _("None") ? false : true;
new_conf.set_key_value("support_material", new ConfigOptionBool(support_material));
if (selection == _("Everywhere"))
if (selection == _("Everywhere")) {
new_conf.set_key_value("support_material_buildplate_only", new ConfigOptionBool(false));
else if (selection == _("Support on build plate only"))
if (printer_technology == ptFFF)
new_conf.set_key_value("support_material_auto", new ConfigOptionBool(true));
} else if (selection == _("Support on build plate only")) {
new_conf.set_key_value("support_material_buildplate_only", new ConfigOptionBool(true));
if (printer_technology == ptFFF)
new_conf.set_key_value("support_material_auto", new ConfigOptionBool(true));
} else if (selection == _("For support enforcers only")) {
assert(printer_technology == ptFFF);
new_conf.set_key_value("support_material_buildplate_only", new ConfigOptionBool(false));
new_conf.set_key_value("support_material_auto", new ConfigOptionBool(false));
}
}
tab_print->load_config(new_conf);
}
@ -421,12 +432,9 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
support_def.tooltip = L("Select what kind of support do you need");
support_def.enum_labels.push_back(L("None"));
support_def.enum_labels.push_back(L("Support on build plate only"));
support_def.enum_labels.push_back(L("For support enforcers only"));
support_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";
support_def.default_value = new ConfigOptionStrings{ selection };
support_def.set_default_value(new ConfigOptionStrings{ "None" });
Option option = Option(support_def, "support");
option.opt.full_width = true;
line.append_option(option);
@ -447,7 +455,7 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
def.type = coBool;
def.tooltip = L("This flag enables the brim that will be printed around each object on the first layer.");
def.gui_type = "";
def.default_value = new ConfigOptionBool{ m_brim_width > 0.0 ? true : false };
def.set_default_value(new ConfigOptionBool{ m_brim_width > 0.0 ? true : false });
option = Option(def, "brim");
option.opt.sidetext = " ";
line.append_option(option);
@ -493,8 +501,9 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
tab->set_value(opt_key, value);
tab->update();
}
else //(opt_key == "support")
else
{
assert(opt_key == "support");
DynamicPrintConfig new_conf = *config_sla;
const wxString& selection = boost::any_cast<wxString>(value);
@ -514,17 +523,15 @@ FreqChangedParams::FreqChangedParams(wxWindow* parent, const int label_width) :
line = Line{ "", "" };
selection = !config_sla->opt_bool("supports_enable") ?
"None" : config_sla->opt_bool("support_buildplate_only") ?
"Support on build plate only" :
"Everywhere";
support_def.default_value = new ConfigOptionStrings{ selection };
option = Option(support_def, "support");
ConfigOptionDef support_def_sla = support_def;
support_def_sla.set_default_value(new ConfigOptionStrings{ "None" });
assert(support_def_sla.enum_labels[2] == L("For support enforcers only"));
support_def_sla.enum_labels.erase(support_def_sla.enum_labels.begin() + 2);
option = Option(support_def_sla, "support");
option.opt.full_width = true;
line.append_option(option);
m_og_sla->append_line(line);
line = Line{ "", "" };
option = m_og_sla->get_option("pad_enable");
@ -1099,9 +1106,9 @@ void Sidebar::enable_buttons(bool enable)
p->btn_send_gcode->Enable(enable);
}
void Sidebar::show_reslice(bool show) const { p->btn_reslice->Show(show); }
void Sidebar::show_export(bool show) const { p->btn_export_gcode->Show(show); }
void Sidebar::show_send(bool show) const { p->btn_send_gcode->Show(show); }
bool Sidebar::show_reslice(bool show) const { return p->btn_reslice->Show(show); }
bool Sidebar::show_export(bool show) const { return p->btn_export_gcode->Show(show); }
bool Sidebar::show_send(bool show) const { return p->btn_send_gcode->Show(show); }
bool Sidebar::is_multifilament()
{
@ -3194,17 +3201,18 @@ void Plater::priv::show_action_buttons(const bool is_ready_to_slice) const
// when a background processing is ON, export_btn and/or send_btn are showing
if (wxGetApp().app_config->get("background_processing") == "1")
{
sidebar->show_reslice(false);
sidebar->show_export(true);
sidebar->show_send(send_gcode_shown);
}
if (sidebar->show_reslice(false) |
sidebar->show_export(true) |
sidebar->show_send(send_gcode_shown))
sidebar->Layout();
}
else
{
sidebar->show_reslice(is_ready_to_slice);
sidebar->show_export(!is_ready_to_slice);
sidebar->show_send(send_gcode_shown && !is_ready_to_slice);
}
sidebar->Layout();
if (sidebar->show_reslice(is_ready_to_slice) |
sidebar->show_export(!is_ready_to_slice) |
sidebar->show_send(send_gcode_shown && !is_ready_to_slice))
sidebar->Layout();
}
}
void Sidebar::set_btn_label(const ActionButtonType btn_type, const wxString& label) const

View File

@ -103,9 +103,9 @@ public:
void show_sliced_info_sizer(const bool show);
void enable_buttons(bool enable);
void set_btn_label(const ActionButtonType btn_type, const wxString& label) const;
void show_reslice(bool show) const;
void show_export(bool show) const;
void show_send(bool show) const;
bool show_reslice(bool show) const;
bool show_export(bool show) const;
bool show_send(bool show) const;
bool is_multifilament();
void update_mode();

View File

@ -37,7 +37,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("If this is enabled, Slic3r will prompt the last output directory "
"instead of the one containing the input files.");
def.default_value = new ConfigOptionBool{ app_config->has("remember_output_path") ? app_config->get("remember_output_path") == "1" : true };
def.set_default_value(new ConfigOptionBool{ app_config->has("remember_output_path") ? app_config->get("remember_output_path") == "1" : true });
Option option(def, "remember_output_path");
m_optgroup->append_single_option_line(option);
@ -45,7 +45,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("If this is enabled, Slic3r will auto-center objects "
"around the print bed center.");
def.default_value = new ConfigOptionBool{ app_config->get("autocenter") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("autocenter") == "1" });
option = Option (def,"autocenter");
m_optgroup->append_single_option_line(option);
@ -53,7 +53,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("If this is enabled, Slic3r will pre-process objects as soon "
"as they\'re loaded in order to save time when exporting G-code.");
def.default_value = new ConfigOptionBool{ app_config->get("background_processing") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("background_processing") == "1" });
option = Option (def,"background_processing");
m_optgroup->append_single_option_line(option);
@ -61,7 +61,7 @@ void PreferencesDialog::build()
def.label = L("Check for application updates");
def.type = coBool;
def.tooltip = L("If enabled, Slic3r checks for new versions of " SLIC3R_APP_NAME " online. When a new version becomes available a notification is displayed at the next application startup (never during program usage). This is only a notification mechanisms, no automatic installation is done.");
def.default_value = new ConfigOptionBool(app_config->get("version_check") == "1");
def.set_default_value(new ConfigOptionBool(app_config->get("version_check") == "1"));
option = Option (def, "version_check");
m_optgroup->append_single_option_line(option);
@ -69,7 +69,7 @@ void PreferencesDialog::build()
def.label = L("Update built-in Presets automatically");
def.type = coBool;
def.tooltip = L("If enabled, Slic3r downloads updates of built-in system presets in the background. These updates are downloaded into a separate temporary location. When a new preset version becomes available it is offered at application startup.");
def.default_value = new ConfigOptionBool(app_config->get("preset_update") == "1");
def.set_default_value(new ConfigOptionBool(app_config->get("preset_update") == "1"));
option = Option (def, "preset_update");
m_optgroup->append_single_option_line(option);
@ -77,7 +77,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("Suppress \" - default - \" presets in the Print / Filament / Printer "
"selections once there are any other valid presets available.");
def.default_value = new ConfigOptionBool{ app_config->get("no_defaults") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("no_defaults") == "1" });
option = Option (def,"no_defaults");
m_optgroup->append_single_option_line(option);
@ -85,7 +85,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("When checked, the print and filament presets are shown in the preset editor "
"even if they are marked as incompatible with the active printer");
def.default_value = new ConfigOptionBool{ app_config->get("show_incompatible_presets") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("show_incompatible_presets") == "1" });
option = Option (def,"show_incompatible_presets");
m_optgroup->append_single_option_line(option);
@ -95,7 +95,7 @@ void PreferencesDialog::build()
def.tooltip = L("If you have rendering issues caused by a buggy OpenGL 2.0 driver, "
"you may try to check this checkbox. This will disable the layer height "
"editing and anti aliasing, so it is likely better to upgrade your graphics driver.");
def.default_value = new ConfigOptionBool{ app_config->get("use_legacy_opengl") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("use_legacy_opengl") == "1" });
option = Option (def,"use_legacy_opengl");
m_optgroup->append_single_option_line(option);
@ -104,7 +104,7 @@ void PreferencesDialog::build()
def.type = coBool;
def.tooltip = L("If enabled, the 3D scene will be rendered in Retina resolution. "
"If you are experiencing 3D performance problems, disabling this option may help.");
def.default_value = new ConfigOptionBool{ app_config->get("use_retina_opengl") == "1" };
def.set_default_value(new ConfigOptionBool{ app_config->get("use_retina_opengl") == "1" });
option = Option (def, "use_retina_opengl");
m_optgroup->append_single_option_line(option);
#endif

View File

@ -54,10 +54,10 @@ Selection::Selection()
, m_mode(Instance)
, m_type(Empty)
, m_valid(false)
, m_bounding_box_dirty(true)
, m_curved_arrow(16)
, m_scale_factor(1.0f)
{
this->set_bounding_boxes_dirty();
#if ENABLE_RENDER_SELECTION_CENTER
m_quadric = ::gluNewQuadric();
if (m_quadric != nullptr)
@ -148,7 +148,7 @@ void Selection::add(unsigned int volume_idx, bool as_single_selection, bool chec
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::remove(unsigned int volume_idx)
@ -173,7 +173,7 @@ void Selection::remove(unsigned int volume_idx)
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::add_object(unsigned int object_idx, bool as_single_selection)
@ -190,7 +190,7 @@ void Selection::add_object(unsigned int object_idx, bool as_single_selection)
do_add_object(object_idx);
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::remove_object(unsigned int object_idx)
@ -201,7 +201,7 @@ void Selection::remove_object(unsigned int object_idx)
do_remove_object(object_idx);
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::add_instance(unsigned int object_idx, unsigned int instance_idx, bool as_single_selection)
@ -218,7 +218,7 @@ void Selection::add_instance(unsigned int object_idx, unsigned int instance_idx,
do_add_instance(object_idx, instance_idx);
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::remove_instance(unsigned int object_idx, unsigned int instance_idx)
@ -229,7 +229,7 @@ void Selection::remove_instance(unsigned int object_idx, unsigned int instance_i
do_remove_instance(object_idx, instance_idx);
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::add_volume(unsigned int object_idx, unsigned int volume_idx, int instance_idx, bool as_single_selection)
@ -254,7 +254,7 @@ void Selection::add_volume(unsigned int object_idx, unsigned int volume_idx, int
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::remove_volume(unsigned int object_idx, unsigned int volume_idx)
@ -270,7 +270,7 @@ void Selection::remove_volume(unsigned int object_idx, unsigned int volume_idx)
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::add_all()
@ -288,7 +288,7 @@ void Selection::add_all()
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::clear()
@ -304,51 +304,44 @@ void Selection::clear()
m_list.clear();
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
// resets the cache in the sidebar
wxGetApp().obj_manipul()->reset_cache();
}
// Update the selection based on the new instance IDs.
void Selection::instances_changed(const std::vector<size_t> &instance_ids_selected)
{
assert(m_valid);
assert(m_mode == Instance);
m_list.clear();
for (unsigned int volume_idx = 0; volume_idx < (unsigned int)m_volumes->size(); ++ volume_idx) {
const GLVolume *volume = (*m_volumes)[volume_idx];
auto it = std::lower_bound(instance_ids_selected.begin(), instance_ids_selected.end(), volume->geometry_id.second);
if (it != instance_ids_selected.end() && *it == volume->geometry_id.second)
this->do_add_volume(volume_idx);
}
update_type();
this->set_bounding_boxes_dirty();
}
// Update the selection based on the map from old indices to new indices after m_volumes changed.
// If the current selection is by instance, this call may select newly added volumes, if they belong to already selected instances.
void Selection::volumes_changed(const std::vector<size_t> &map_volume_old_to_new)
{
assert(m_valid);
// 1) Update the selection set.
assert(m_mode == Volume);
IndicesList list_new;
std::vector<std::pair<unsigned int, unsigned int>> model_instances;
for (unsigned int idx : m_list) {
for (unsigned int idx : m_list)
if (map_volume_old_to_new[idx] != size_t(-1)) {
unsigned int new_idx = (unsigned int)map_volume_old_to_new[idx];
assert((*m_volumes)[new_idx]->selected);
list_new.insert(new_idx);
if (m_mode == Instance) {
// Save the object_idx / instance_idx pair of selected old volumes,
// so we may add the newly added volumes of the same object_idx / instance_idx pair
// to the selection.
const GLVolume *volume = (*m_volumes)[new_idx];
model_instances.emplace_back(volume->object_idx(), volume->instance_idx());
}
}
}
m_list = std::move(list_new);
if (!model_instances.empty()) {
// Instance selection mode. Add the newly added volumes of the same object_idx / instance_idx pair
// to the selection.
assert(m_mode == Instance);
sort_remove_duplicates(model_instances);
for (unsigned int i = 0; i < (unsigned int)m_volumes->size(); ++i) {
const GLVolume* volume = (*m_volumes)[i];
for (const std::pair<int, int> &model_instance : model_instances)
if (volume->object_idx() == model_instance.first && volume->instance_idx() == model_instance.second)
do_add_volume(i);
}
}
update_type();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
bool Selection::is_single_full_instance() const
@ -433,6 +426,14 @@ const BoundingBoxf3& Selection::get_bounding_box() const
return m_bounding_box;
}
const BoundingBoxf3& Selection::get_unscaled_instance_bounding_box() const
{
if (m_unscaled_instance_bounding_box_dirty)
calc_unscaled_instance_bounding_box();
return m_unscaled_instance_bounding_box;
}
void Selection::start_dragging()
{
if (!m_valid)
@ -480,7 +481,7 @@ void Selection::translate(const Vec3d& displacement, bool local)
synchronize_unselected_volumes();
#endif // !DISABLE_INSTANCES_SYNCH
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
// Rotate an object around one of the axes. Only one rotation component is expected to be changing.
@ -587,7 +588,7 @@ void Selection::rotate(const Vec3d& rotation, TransformationType transformation_
synchronize_unselected_volumes();
#endif // !DISABLE_INSTANCES_SYNCH
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::flattening_rotate(const Vec3d& normal)
@ -628,20 +629,29 @@ void Selection::flattening_rotate(const Vec3d& normal)
synchronize_unselected_instances(SYNC_ROTATION_FULL);
#endif // !DISABLE_INSTANCES_SYNCH
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::scale(const Vec3d& scale, bool local)
void Selection::scale(const Vec3d& scale, TransformationType transformation_type)
{
if (!m_valid)
return;
for (unsigned int i : m_list)
{
if (is_single_full_instance())
(*m_volumes)[i]->set_instance_scaling_factor(scale);
GLVolume &volume = *(*m_volumes)[i];
if (is_single_full_instance()) {
assert(transformation_type.absolute());
if (transformation_type.world() && (std::abs(scale.x() - scale.y()) > EPSILON || std::abs(scale.x() - scale.z()) > EPSILON)) {
// Non-uniform scaling. Transform the scaling factors into the local coordinate system.
// This is only possible, if the instance rotation is mulitples of ninety degrees.
assert(Geometry::is_rotation_ninety_degrees(volume.get_instance_rotation()));
volume.set_instance_scaling_factor((volume.get_instance_transformation().get_matrix(true, false, true, true).matrix().block<3, 3>(0, 0).transpose() * scale).cwiseAbs());
} else
volume.set_instance_scaling_factor(scale);
}
else if (is_single_volume() || is_single_modifier())
(*m_volumes)[i]->set_volume_scaling_factor(scale);
volume.set_volume_scaling_factor(scale);
else
{
Transform3d m = Geometry::assemble_transform(Vec3d::Zero(), Vec3d::Zero(), scale);
@ -650,22 +660,22 @@ void Selection::scale(const Vec3d& scale, bool local)
Eigen::Matrix<double, 3, 3, Eigen::DontAlign> new_matrix = (m * m_cache.volumes_data[i].get_instance_scale_matrix()).matrix().block(0, 0, 3, 3);
// extracts scaling factors from the composed transformation
Vec3d new_scale(new_matrix.col(0).norm(), new_matrix.col(1).norm(), new_matrix.col(2).norm());
if (!local)
(*m_volumes)[i]->set_instance_offset(m_cache.dragging_center + m * (m_cache.volumes_data[i].get_instance_position() - m_cache.dragging_center));
if (transformation_type.joint())
volume.set_instance_offset(m_cache.dragging_center + m * (m_cache.volumes_data[i].get_instance_position() - m_cache.dragging_center));
(*m_volumes)[i]->set_instance_scaling_factor(new_scale);
volume.set_instance_scaling_factor(new_scale);
}
else if (m_mode == Volume)
{
Eigen::Matrix<double, 3, 3, Eigen::DontAlign> new_matrix = (m * m_cache.volumes_data[i].get_volume_scale_matrix()).matrix().block(0, 0, 3, 3);
// extracts scaling factors from the composed transformation
Vec3d new_scale(new_matrix.col(0).norm(), new_matrix.col(1).norm(), new_matrix.col(2).norm());
if (!local)
if (transformation_type.joint())
{
Vec3d offset = m * (m_cache.volumes_data[i].get_volume_position() + m_cache.volumes_data[i].get_instance_position() - m_cache.dragging_center);
(*m_volumes)[i]->set_volume_offset(m_cache.dragging_center - m_cache.volumes_data[i].get_instance_position() + offset);
volume.set_volume_offset(m_cache.dragging_center - m_cache.volumes_data[i].get_instance_position() + offset);
}
(*m_volumes)[i]->set_volume_scaling_factor(new_scale);
volume.set_volume_scaling_factor(new_scale);
}
}
}
@ -679,7 +689,7 @@ void Selection::scale(const Vec3d& scale, bool local)
ensure_on_bed();
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::mirror(Axis axis)
@ -704,7 +714,7 @@ void Selection::mirror(Axis axis)
synchronize_unselected_volumes();
#endif // !DISABLE_INSTANCES_SYNCH
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::translate(unsigned int object_idx, const Vec3d& displacement)
@ -749,7 +759,7 @@ void Selection::translate(unsigned int object_idx, const Vec3d& displacement)
}
}
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::translate(unsigned int object_idx, unsigned int instance_idx, const Vec3d& displacement)
@ -794,7 +804,7 @@ void Selection::translate(unsigned int object_idx, unsigned int instance_idx, co
}
}
m_bounding_box_dirty = true;
this->set_bounding_boxes_dirty();
}
void Selection::erase()
@ -959,7 +969,7 @@ void Selection::render_sidebar_hints(const std::string& sidebar_field) const
const Vec3d& center = get_bounding_box().center();
if (is_single_full_instance())
if (is_single_full_instance() && ! wxGetApp().obj_manipul()->get_world_coordinates())
{
glsafe(::glTranslated(center(0), center(1), center(2)));
if (!boost::starts_with(sidebar_field, "position"))
@ -1400,7 +1410,23 @@ void Selection::calc_bounding_box() const
m_bounding_box.merge((*m_volumes)[i]->transformed_convex_hull_bounding_box());
}
}
m_bounding_box_dirty = false;
m_bounding_box_dirty = false;
}
void Selection::calc_unscaled_instance_bounding_box() const
{
m_unscaled_instance_bounding_box = BoundingBoxf3();
if (m_valid)
{
for (unsigned int i : m_list)
{
const GLVolume &volume = *(*m_volumes)[i];
Transform3d trafo = volume.get_instance_transformation().get_matrix(false, false, true, false) * volume.get_volume_transformation().get_matrix();
trafo.translation()(2) += volume.get_sla_shift_z();
m_unscaled_instance_bounding_box.merge(volume.transformed_convex_hull_bounding_box(trafo));
}
}
m_unscaled_instance_bounding_box_dirty = false;
}
void Selection::render_selected_volumes() const

View File

@ -183,6 +183,10 @@ private:
Clipboard m_clipboard;
mutable BoundingBoxf3 m_bounding_box;
mutable bool m_bounding_box_dirty;
// Bounding box of a selection, with no instance scaling applied. This bounding box
// is useful for absolute scaling of tilted objects in world coordinate space.
mutable BoundingBoxf3 m_unscaled_instance_bounding_box;
mutable bool m_unscaled_instance_bounding_box_dirty;
#if ENABLE_RENDER_SELECTION_CENTER
GLUquadricObj* m_quadric;
@ -224,6 +228,8 @@ public:
void add_all();
// Update the selection based on the new instance IDs.
void instances_changed(const std::vector<size_t> &instance_ids_selected);
// Update the selection based on the map from old indices to new indices after m_volumes changed.
// If the current selection is by instance, this call may select newly added volumes, if they belong to already selected instances.
void volumes_changed(const std::vector<size_t> &map_volume_old_to_new);
@ -245,7 +251,7 @@ public:
bool is_from_single_instance() const { return get_instance_idx() != -1; }
bool is_from_single_object() const;
bool contains_volume(unsigned int volume_idx) const { return std::find(m_list.begin(), m_list.end(), volume_idx) != m_list.end(); }
bool contains_volume(unsigned int volume_idx) const { return m_list.find(volume_idx) != m_list.end(); }
bool requires_uniform_scale() const;
// Returns the the object id if the selection is from a single object, otherwise is -1
@ -263,13 +269,16 @@ public:
unsigned int volumes_count() const { return (unsigned int)m_list.size(); }
const BoundingBoxf3& get_bounding_box() const;
// Bounding box of a selection, with no instance scaling applied. This bounding box
// is useful for absolute scaling of tilted objects in world coordinate space.
const BoundingBoxf3& get_unscaled_instance_bounding_box() const;
void start_dragging();
void translate(const Vec3d& displacement, bool local = false);
void rotate(const Vec3d& rotation, TransformationType transformation_type);
void flattening_rotate(const Vec3d& normal);
void scale(const Vec3d& scale, bool local);
void scale(const Vec3d& scale, TransformationType transformation_type);
void mirror(Axis axis);
void translate(unsigned int object_idx, const Vec3d& displacement);
@ -301,6 +310,8 @@ private:
void do_remove_instance(unsigned int object_idx, unsigned int instance_idx);
void do_remove_object(unsigned int object_idx);
void calc_bounding_box() const;
void calc_unscaled_instance_bounding_box() const;
void set_bounding_boxes_dirty() { m_bounding_box_dirty = true; m_unscaled_instance_bounding_box_dirty = true; }
void render_selected_volumes() const;
void render_synchronized_volumes() const;
void render_bounding_box(const BoundingBoxf3& box, float* color) const;

View File

@ -816,6 +816,19 @@ void Tab::load_key_value(const std::string& opt_key, const boost::any& value, bo
update();
}
static wxString support_combo_value_for_config(const DynamicPrintConfig &config, bool is_fff)
{
const std::string support = is_fff ? "support_material" : "supports_enable";
const std::string buildplate_only = is_fff ? "support_material_buildplate_only" : "support_buildplate_only";
return
! config.opt_bool(support) ?
_("None") :
(is_fff && !config.opt_bool("support_material_auto")) ?
_("For support enforcers only") :
(config.opt_bool(buildplate_only) ? _("Support on build plate only") :
_("Everywhere"));
}
void Tab::on_value_change(const std::string& opt_key, const boost::any& value)
{
if (wxGetApp().plater() == nullptr) {
@ -823,23 +836,17 @@ void Tab::on_value_change(const std::string& opt_key, const boost::any& value)
}
const bool is_fff = supports_printer_technology(ptFFF);
ConfigOptionsGroup* og_freq_chng_params = wxGetApp().sidebar().og_freq_chng_params(is_fff);
ConfigOptionsGroup* og_freq_chng_params = wxGetApp().sidebar().og_freq_chng_params(is_fff);
if (opt_key == "fill_density" || opt_key == "pad_enable")
{
boost::any val = og_freq_chng_params->get_config_value(*m_config, opt_key);
og_freq_chng_params->set_value(opt_key, val);
}
if ( is_fff && (opt_key == "support_material" || opt_key == "support_material_buildplate_only") ||
!is_fff && (opt_key == "supports_enable" || opt_key == "support_buildplate_only"))
{
const std::string support = is_fff ? "support_material" : "supports_enable";
const std::string buildplate_only = is_fff ? "support_material_buildplate_only" : "support_buildplate_only";
wxString new_selection = !m_config->opt_bool(support) ? _("None") :
m_config->opt_bool(buildplate_only) ? _("Support on build plate only") :
_("Everywhere");
og_freq_chng_params->set_value("support", new_selection);
}
if (is_fff ?
(opt_key == "support_material" || opt_key == "support_material_auto" || opt_key == "support_material_buildplate_only") :
(opt_key == "supports_enable" || opt_key == "support_buildplate_only"))
og_freq_chng_params->set_value("support", support_combo_value_for_config(*m_config, is_fff));
if (opt_key == "brim_width")
{
@ -965,18 +972,11 @@ void Tab::update_preset_description_line()
void Tab::update_frequently_changed_parameters()
{
auto og_freq_chng_params = wxGetApp().sidebar().og_freq_chng_params(supports_printer_technology(ptFFF));
const bool is_fff = supports_printer_technology(ptFFF);
auto og_freq_chng_params = wxGetApp().sidebar().og_freq_chng_params(is_fff);
if (!og_freq_chng_params) return;
const bool is_fff = supports_printer_technology(ptFFF);
const std::string support = is_fff ? "support_material" : "supports_enable";
const std::string buildplate_only = is_fff ? "support_material_buildplate_only" : "support_buildplate_only";
wxString new_selection = !m_config->opt_bool(support) ? _("None") :
m_config->opt_bool(buildplate_only) ? _("Support on build plate only") :
_("Everywhere");
og_freq_chng_params->set_value("support", new_selection);
og_freq_chng_params->set_value("support", support_combo_value_for_config(*m_config, is_fff));
const std::string updated_value_key = is_fff ? "fill_density" : "pad_enable";
@ -1841,7 +1841,7 @@ void TabPrinter::build_fff()
optgroup = page->new_optgroup(_(L("Capabilities")));
ConfigOptionDef def;
def.type = coInt,
def.default_value = new ConfigOptionInt(1);
def.set_default_value(new ConfigOptionInt(1));
def.label = L("Extruders");
def.tooltip = L("Number of extruders of the printer.");
def.min = 1;
@ -2149,13 +2149,13 @@ PageShp TabPrinter::build_kinematics_page()
def.gui_type = "legend";
def.mode = comAdvanced;
def.tooltip = L("Values in this column are for Full Power mode");
def.default_value = new ConfigOptionString{ L("Full Power") };
def.set_default_value(new ConfigOptionString{ L("Full Power") });
auto option = Option(def, "full_power_legend");
line.append_option(option);
def.tooltip = L("Values in this column are for Silent mode");
def.default_value = new ConfigOptionString{ L("Silent") };
def.set_default_value(new ConfigOptionString{ L("Silent") });
option = Option(def, "silent_legend");
line.append_option(option);

View File

@ -223,8 +223,8 @@ print_config_def()
(void)hv_stores( hv, "labels", newRV_noinc((SV*)av) );
}
if (optdef->default_value != NULL)
(void)hv_stores( hv, "default", ConfigOption_to_SV(*optdef->default_value, *optdef) );
if (optdef->default_value)
(void)hv_stores( hv, "default", ConfigOption_to_SV(*optdef->default_value.get(), *optdef) );
(void)hv_store( options_hv, opt_key.c_str(), opt_key.length(), newRV_noinc((SV*)hv), 0 );
}