mirror of
https://git.mirrors.martin98.com/https://github.com/prusa3d/PrusaSlicer.git
synced 2025-10-02 01:23:15 +08:00
Emboss text along base line(object cut)
- need alignment of text(center, left, right) - (NOTE) edit text change its position + add polygon point
This commit is contained in:
parent
ea2b214741
commit
af0ef21ce3
@ -1321,15 +1321,31 @@ std::vector<ExPolygons> Emboss::text2vshapes(FontFileWithCache &font_with_cache,
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#include <boost/range/adaptor/reversed.hpp>
|
||||||
unsigned Emboss::get_count_lines(const std::wstring& ws)
|
unsigned Emboss::get_count_lines(const std::wstring& ws)
|
||||||
{
|
{
|
||||||
if (ws.empty())
|
if (ws.empty())
|
||||||
return 0;
|
return 0;
|
||||||
|
unsigned prev_count = 0;
|
||||||
|
for (wchar_t wc : ws)
|
||||||
|
if (wc == '\n')
|
||||||
|
++prev_count;
|
||||||
|
else
|
||||||
|
break;
|
||||||
|
|
||||||
|
unsigned post_count = 0;
|
||||||
|
for (wchar_t wc : boost::adaptors::reverse(ws))
|
||||||
|
if (wc == '\n')
|
||||||
|
++post_count;
|
||||||
|
else
|
||||||
|
break;
|
||||||
|
|
||||||
unsigned count = 1;
|
unsigned count = 1;
|
||||||
for (wchar_t wc : ws)
|
for (wchar_t wc : ws)
|
||||||
if (wc == '\n')
|
if (wc == '\n')
|
||||||
++count;
|
++count;
|
||||||
return count;
|
|
||||||
|
return count - prev_count - post_count;
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned Emboss::get_count_lines(const std::string &text)
|
unsigned Emboss::get_count_lines(const std::string &text)
|
||||||
@ -1730,6 +1746,178 @@ std::optional<Vec2d> Emboss::OrthoProject::unproject(const Vec3d &p, double *dep
|
|||||||
return Vec2d(pp.x(), pp.y());
|
return Vec2d(pp.x(), pp.y());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// sample slice
|
||||||
|
namespace {
|
||||||
|
|
||||||
|
// using coor2 = int64_t;
|
||||||
|
using Coord2 = double;
|
||||||
|
using P2 = Eigen::Matrix<Coord2, 2, 1, Eigen::DontAlign>;
|
||||||
|
|
||||||
|
bool point_in_distance(const Coord2 &distance_sq, PolygonPoint &polygon_point, const size_t &i, const Slic3r::Polygon &polygon, bool is_first, bool is_reverse = false)
|
||||||
|
{
|
||||||
|
size_t s = polygon.size();
|
||||||
|
size_t ii = (i + polygon_point.index) % s;
|
||||||
|
|
||||||
|
// second point of line
|
||||||
|
const Point &p = polygon[ii];
|
||||||
|
Point p_d = p - polygon_point.point;
|
||||||
|
|
||||||
|
P2 p_d2 = p_d.cast<Coord2>();
|
||||||
|
Coord2 p_distance_sq = p_d2.squaredNorm();
|
||||||
|
if (p_distance_sq < distance_sq)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
// found line
|
||||||
|
if (is_first) {
|
||||||
|
// on same line
|
||||||
|
// center also lay on line
|
||||||
|
// new point is distance moved from point by direction
|
||||||
|
polygon_point.point += p_d * sqrt(distance_sq / p_distance_sq);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// line cross circle
|
||||||
|
|
||||||
|
// start point of line
|
||||||
|
size_t ii2 = (is_reverse) ? (ii + 1) % s : (ii + s - 1) % s;
|
||||||
|
polygon_point.index = (is_reverse) ? ii : ii2;
|
||||||
|
const Point &p2 = polygon[ii2];
|
||||||
|
|
||||||
|
Point line_dir = p2 - p;
|
||||||
|
P2 line_dir2 = line_dir.cast<Coord2>();
|
||||||
|
|
||||||
|
Coord2 a = line_dir2.dot(line_dir2);
|
||||||
|
Coord2 b = 2 * p_d2.dot(line_dir2);
|
||||||
|
Coord2 c = p_d2.dot(p_d2) - distance_sq;
|
||||||
|
|
||||||
|
double discriminant = b * b - 4 * a * c;
|
||||||
|
if (discriminant < 0) {
|
||||||
|
assert(false);
|
||||||
|
// no intersection
|
||||||
|
polygon_point.point = p;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// ray didn't totally miss sphere,
|
||||||
|
// so there is a solution to
|
||||||
|
// the equation.
|
||||||
|
discriminant = sqrt(discriminant);
|
||||||
|
|
||||||
|
// either solution may be on or off the ray so need to test both
|
||||||
|
// t1 is always the smaller value, because BOTH discriminant and
|
||||||
|
// a are nonnegative.
|
||||||
|
double t1 = (-b - discriminant) / (2 * a);
|
||||||
|
double t2 = (-b + discriminant) / (2 * a);
|
||||||
|
|
||||||
|
double t = std::min(t1, t2);
|
||||||
|
if (t < 0. || t > 1.) {
|
||||||
|
// Bad intersection
|
||||||
|
assert(false);
|
||||||
|
polygon_point.point = p;
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
polygon_point.point = p + (t * line_dir2).cast<Point::coord_type>();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void point_in_distance(int32_t distance, PolygonPoint &p, const Slic3r::Polygon &polygon)
|
||||||
|
{
|
||||||
|
Coord2 distance_sq = static_cast<Coord2>(distance) * distance;
|
||||||
|
bool is_first = true;
|
||||||
|
for (size_t i = 1; i < polygon.size(); ++i) {
|
||||||
|
if (point_in_distance(distance_sq, p, i, polygon, is_first))
|
||||||
|
return;
|
||||||
|
is_first = false;
|
||||||
|
}
|
||||||
|
// There is not point on polygon with this distance
|
||||||
|
}
|
||||||
|
|
||||||
|
void point_in_reverse_distance(int32_t distance, PolygonPoint &p, const Slic3r::Polygon &polygon)
|
||||||
|
{
|
||||||
|
Coord2 distance_sq = static_cast<Coord2>(distance) * distance;
|
||||||
|
bool is_first = true;
|
||||||
|
bool is_reverse = true;
|
||||||
|
for (size_t i = polygon.size(); i > 0; --i) {
|
||||||
|
if (point_in_distance(distance_sq, p, i, polygon, is_first, is_reverse))
|
||||||
|
return;
|
||||||
|
is_first = false;
|
||||||
|
}
|
||||||
|
// There is not point on polygon with this distance
|
||||||
|
}
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
// calculate rotation, need copy of polygon point
|
||||||
|
double Emboss::calculate_angle(int32_t distance, PolygonPoint polygon_point, const Polygon &polygon)
|
||||||
|
{
|
||||||
|
PolygonPoint polygon_point2 = polygon_point; // copy
|
||||||
|
point_in_distance(distance, polygon_point, polygon);
|
||||||
|
point_in_reverse_distance(distance, polygon_point2, polygon);
|
||||||
|
|
||||||
|
Point surface_dir = polygon_point2.point - polygon_point.point;
|
||||||
|
Point norm(-surface_dir.y(), surface_dir.x());
|
||||||
|
Vec2d norm_d = norm.cast<double>();
|
||||||
|
//norm_d.normalize();
|
||||||
|
return std::atan2(norm_d.y(), norm_d.x());
|
||||||
|
}
|
||||||
|
|
||||||
|
std::vector<double> Emboss::calculate_angles(int32_t distance, const PolygonPoints& polygon_points, const Polygon &polygon)
|
||||||
|
{
|
||||||
|
std::vector<double> result;
|
||||||
|
result.reserve(polygon_points.size());
|
||||||
|
for(const PolygonPoint& pp: polygon_points)
|
||||||
|
result.emplace_back(calculate_angle(distance, pp, polygon));
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
PolygonPoints Emboss::sample_slice(const TextLine &slice, const BoundingBoxes &bbs, int32_t center_x, double scale)
|
||||||
|
{
|
||||||
|
// find BB in center of line
|
||||||
|
size_t first_right_index = 0;
|
||||||
|
for (const BoundingBox &bb : bbs)
|
||||||
|
if (bb.min.x() > center_x) {
|
||||||
|
break;
|
||||||
|
} else {
|
||||||
|
++first_right_index;
|
||||||
|
}
|
||||||
|
|
||||||
|
PolygonPoints samples(bbs.size());
|
||||||
|
int32_t shapes_x_cursor = center_x;
|
||||||
|
|
||||||
|
PolygonPoint cursor = slice.start; //copy
|
||||||
|
|
||||||
|
auto create_sample = [&] //polygon_cursor, &polygon_line_index, &line_bbs, &shapes_x_cursor, &shape_scale, &em_2_polygon, &line, &offsets]
|
||||||
|
(const BoundingBox &bb, bool is_reverse) {
|
||||||
|
if (!bb.defined)
|
||||||
|
return cursor;
|
||||||
|
Point letter_center = bb.center();
|
||||||
|
int32_t shape_distance = shapes_x_cursor - letter_center.x();
|
||||||
|
shapes_x_cursor = letter_center.x();
|
||||||
|
double distance_mm = shape_distance * scale;
|
||||||
|
int32_t distance_polygon = static_cast<int32_t>(std::round(scale_(distance_mm)));
|
||||||
|
if (is_reverse)
|
||||||
|
point_in_distance(distance_polygon, cursor, slice.polygon);
|
||||||
|
else
|
||||||
|
point_in_reverse_distance(distance_polygon, cursor, slice.polygon);
|
||||||
|
return cursor;
|
||||||
|
};
|
||||||
|
|
||||||
|
// calc transformation for letters on the Right side from center
|
||||||
|
bool is_reverse = true;
|
||||||
|
for (size_t index = first_right_index; index < bbs.size(); ++index)
|
||||||
|
samples[index] = create_sample(bbs[index], is_reverse);
|
||||||
|
|
||||||
|
// calc transformation for letters on the Left side from center
|
||||||
|
shapes_x_cursor = center_x;
|
||||||
|
cursor = slice.start; // copy
|
||||||
|
is_reverse = false;
|
||||||
|
for (size_t index_plus_one = first_right_index; index_plus_one > 0; --index_plus_one) {
|
||||||
|
size_t index = index_plus_one - 1;
|
||||||
|
samples[index] = create_sample(bbs[index], is_reverse);
|
||||||
|
}
|
||||||
|
return samples;
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef REMOVE_SPIKES
|
#ifdef REMOVE_SPIKES
|
||||||
#include <Geometry.hpp>
|
#include <Geometry.hpp>
|
||||||
void priv::remove_spikes(Polygon &polygon, const SpikeDesc &spike_desc)
|
void priv::remove_spikes(Polygon &polygon, const SpikeDesc &spike_desc)
|
||||||
|
@ -8,6 +8,7 @@
|
|||||||
#include <admesh/stl.h> // indexed_triangle_set
|
#include <admesh/stl.h> // indexed_triangle_set
|
||||||
#include "Polygon.hpp"
|
#include "Polygon.hpp"
|
||||||
#include "ExPolygon.hpp"
|
#include "ExPolygon.hpp"
|
||||||
|
#include "BoundingBox.hpp"
|
||||||
#include "TextConfiguration.hpp"
|
#include "TextConfiguration.hpp"
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
@ -403,7 +404,44 @@ namespace Emboss
|
|||||||
Vec3d project(const Vec3d &point) const override;
|
Vec3d project(const Vec3d &point) const override;
|
||||||
std::optional<Vec2d> unproject(const Vec3d &p, double * depth = nullptr) const override;
|
std::optional<Vec2d> unproject(const Vec3d &p, double * depth = nullptr) const override;
|
||||||
};
|
};
|
||||||
} // namespace Emboss
|
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Define polygon for draw letters
|
||||||
|
/// </summary>
|
||||||
|
struct TextLine
|
||||||
|
{
|
||||||
|
// slice of object
|
||||||
|
Polygon polygon;
|
||||||
|
|
||||||
|
// point laying on polygon closest to zero
|
||||||
|
PolygonPoint start;
|
||||||
|
|
||||||
|
// offset of text line in volume mm
|
||||||
|
float y;
|
||||||
|
};
|
||||||
|
using TextLines = std::vector<TextLine>;
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Sample slice polygon by bounding boxes centers
|
||||||
|
/// slice start point has shape_center_x coor
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="slice">Polygon and start point</param>
|
||||||
|
/// <param name="bbs">Bounding boxes of letter on one line</param>
|
||||||
|
/// <param name="center_x">Center x coor of bbs line</param>
|
||||||
|
/// <param name="scale">Scale for bbs</param>
|
||||||
|
/// <returns>Sampled polygon by bounding boxes</returns>
|
||||||
|
PolygonPoints sample_slice(const TextLine &slice, const BoundingBoxes &bbs, int32_t center_x, double scale);
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Calculate angle for polygon point
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="distance">Distance for found normal in point</param>
|
||||||
|
/// <param name="polygon_point">Select point on polygon</param>
|
||||||
|
/// <param name="polygon">Polygon know neighbor of point</param>
|
||||||
|
/// <returns>angle(atan2) of normal in polygon point</returns>
|
||||||
|
double calculate_angle(int32_t distance, PolygonPoint polygon_point, const Polygon &polygon);
|
||||||
|
std::vector<double> calculate_angles(int32_t distance, const PolygonPoints& polygon_points, const Polygon &polygon);
|
||||||
|
|
||||||
|
} // namespace Emboss
|
||||||
} // namespace Slic3r
|
} // namespace Slic3r
|
||||||
#endif // slic3r_Emboss_hpp_
|
#endif // slic3r_Emboss_hpp_
|
||||||
|
@ -266,6 +266,21 @@ bool polygons_match(const Polygon &l, const Polygon &r);
|
|||||||
Polygon make_circle(double radius, double error);
|
Polygon make_circle(double radius, double error);
|
||||||
Polygon make_circle_num_segments(double radius, size_t num_segments);
|
Polygon make_circle_num_segments(double radius, size_t num_segments);
|
||||||
|
|
||||||
|
/// <summary>
|
||||||
|
/// Define point laying on polygon
|
||||||
|
/// keep index of polygon line and point coordinate
|
||||||
|
/// </summary>
|
||||||
|
struct PolygonPoint
|
||||||
|
{
|
||||||
|
// index of line inside of polygon
|
||||||
|
// 0 .. from point polygon[0] to polygon[1]
|
||||||
|
size_t index;
|
||||||
|
|
||||||
|
// Point, which lay on line defined by index
|
||||||
|
Point point;
|
||||||
|
};
|
||||||
|
using PolygonPoints = std::vector<PolygonPoint>;
|
||||||
|
|
||||||
} // Slic3r
|
} // Slic3r
|
||||||
|
|
||||||
// start Boost
|
// start Boost
|
||||||
|
@ -403,6 +403,8 @@ bool GLGizmoEmboss::on_mouse_for_rotation(const wxMouseEvent &mouse_event)
|
|||||||
angle_opt = angle;
|
angle_opt = angle;
|
||||||
m_style_manager.get_font_prop().angle = angle_opt;
|
m_style_manager.get_font_prop().angle = angle_opt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
volume_transformation_changing();
|
||||||
}
|
}
|
||||||
return used;
|
return used;
|
||||||
}
|
}
|
||||||
@ -421,14 +423,8 @@ bool GLGizmoEmboss::on_mouse_for_translate(const wxMouseEvent &mouse_event)
|
|||||||
bool is_dragging = m_surface_drag.has_value();
|
bool is_dragging = m_surface_drag.has_value();
|
||||||
|
|
||||||
// End with surface dragging?
|
// End with surface dragging?
|
||||||
if (was_dragging && !is_dragging) {
|
if (was_dragging && !is_dragging)
|
||||||
// Update surface by new position
|
volume_transformation_changed();
|
||||||
if (m_volume->text_configuration->style.prop.use_surface)
|
|
||||||
process();
|
|
||||||
|
|
||||||
// Show correct value of height & depth inside of inputs
|
|
||||||
calculate_scale();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Start with dragging
|
// Start with dragging
|
||||||
else if (!was_dragging && is_dragging) {
|
else if (!was_dragging && is_dragging) {
|
||||||
@ -452,6 +448,8 @@ bool GLGizmoEmboss::on_mouse_for_translate(const wxMouseEvent &mouse_event)
|
|||||||
|
|
||||||
m_style_manager.get_style().prop.angle = calc_up(gl_volume->world_matrix(), priv::up_limit);
|
m_style_manager.get_style().prop.angle = calc_up(gl_volume->world_matrix(), priv::up_limit);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
volume_transformation_changing();
|
||||||
}
|
}
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
@ -552,6 +550,36 @@ bool GLGizmoEmboss::on_mouse(const wxMouseEvent &mouse_event)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void GLGizmoEmboss::volume_transformation_changing()
|
||||||
|
{
|
||||||
|
if (m_volume == nullptr || !m_volume->text_configuration.has_value()) {
|
||||||
|
assert(false);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
const FontProp &prop = m_volume->text_configuration->style.prop;
|
||||||
|
if (prop.per_glyph)
|
||||||
|
init_text_lines();
|
||||||
|
}
|
||||||
|
|
||||||
|
void GLGizmoEmboss::volume_transformation_changed()
|
||||||
|
{
|
||||||
|
if (m_volume == nullptr || !m_volume->text_configuration.has_value()) {
|
||||||
|
assert(false);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const FontProp &prop = m_volume->text_configuration->style.prop;
|
||||||
|
if (prop.per_glyph)
|
||||||
|
init_text_lines();
|
||||||
|
|
||||||
|
// Update surface by new position
|
||||||
|
if (prop.use_surface || prop.per_glyph)
|
||||||
|
process();
|
||||||
|
|
||||||
|
// Show correct value of height & depth inside of inputs
|
||||||
|
calculate_scale();
|
||||||
|
}
|
||||||
|
|
||||||
bool GLGizmoEmboss::on_init()
|
bool GLGizmoEmboss::on_init()
|
||||||
{
|
{
|
||||||
m_rotate_gizmo.init();
|
m_rotate_gizmo.init();
|
||||||
@ -848,9 +876,7 @@ void GLGizmoEmboss::on_stop_dragging()
|
|||||||
|
|
||||||
m_rotate_start_angle.reset();
|
m_rotate_start_angle.reset();
|
||||||
|
|
||||||
// recalculate for surface cut
|
volume_transformation_changed();
|
||||||
const FontProp &font_prop = m_style_manager.get_style().prop;
|
|
||||||
if (font_prop.use_surface) process();
|
|
||||||
}
|
}
|
||||||
void GLGizmoEmboss::on_dragging(const UpdateData &data) { m_rotate_gizmo.dragging(data); }
|
void GLGizmoEmboss::on_dragging(const UpdateData &data) { m_rotate_gizmo.dragging(data); }
|
||||||
|
|
||||||
@ -1263,7 +1289,11 @@ bool GLGizmoEmboss::process()
|
|||||||
if (!m_style_manager.is_active_font()) return false;
|
if (!m_style_manager.is_active_font()) return false;
|
||||||
|
|
||||||
DataUpdate data{priv::create_emboss_data_base(m_text, m_style_manager, m_job_cancel), m_volume->id()};
|
DataUpdate data{priv::create_emboss_data_base(m_text, m_style_manager, m_job_cancel), m_volume->id()};
|
||||||
|
if (data.text_configuration.style.prop.per_glyph){
|
||||||
|
if (!m_text_lines.is_init())
|
||||||
|
init_text_lines();
|
||||||
|
data.text_lines = m_text_lines.get_lines(); // copy
|
||||||
|
}
|
||||||
std::unique_ptr<Job> job = nullptr;
|
std::unique_ptr<Job> job = nullptr;
|
||||||
|
|
||||||
// check cutting from source mesh
|
// check cutting from source mesh
|
||||||
|
@ -82,6 +82,9 @@ protected:
|
|||||||
std::string get_gizmo_leaving_text() const override { return _u8L("Leave emboss gizmo"); }
|
std::string get_gizmo_leaving_text() const override { return _u8L("Leave emboss gizmo"); }
|
||||||
std::string get_action_snapshot_name() const override { return _u8L("Embossing actions"); }
|
std::string get_action_snapshot_name() const override { return _u8L("Embossing actions"); }
|
||||||
private:
|
private:
|
||||||
|
void volume_transformation_changing();
|
||||||
|
void volume_transformation_changed();
|
||||||
|
|
||||||
static EmbossStyles create_default_styles();
|
static EmbossStyles create_default_styles();
|
||||||
// localized default text
|
// localized default text
|
||||||
bool init_create(ModelVolumeType volume_type);
|
bool init_create(ModelVolumeType volume_type);
|
||||||
|
@ -1,6 +1,7 @@
|
|||||||
#include "EmbossJob.hpp"
|
#include "EmbossJob.hpp"
|
||||||
|
|
||||||
#include <stdexcept>
|
#include <stdexcept>
|
||||||
|
#include <type_traits>
|
||||||
|
|
||||||
#include <libslic3r/Model.hpp>
|
#include <libslic3r/Model.hpp>
|
||||||
#include <libslic3r/Format/OBJ.hpp> // load_obj for default mesh
|
#include <libslic3r/Format/OBJ.hpp> // load_obj for default mesh
|
||||||
@ -247,8 +248,8 @@ void UpdateJob::process(Ctl &ctl)
|
|||||||
throw priv::JobException("Created text volume is empty. Change text or font.");
|
throw priv::JobException("Created text volume is empty. Change text or font.");
|
||||||
|
|
||||||
// center triangle mesh
|
// center triangle mesh
|
||||||
Vec3d shift = m_result.bounding_box().center();
|
//Vec3d shift = m_result.bounding_box().center();
|
||||||
m_result.translate(-shift.cast<float>());
|
//m_result.translate(-shift.cast<float>());
|
||||||
}
|
}
|
||||||
|
|
||||||
void UpdateJob::finalize(bool canceled, std::exception_ptr &eptr)
|
void UpdateJob::finalize(bool canceled, std::exception_ptr &eptr)
|
||||||
@ -286,6 +287,8 @@ SurfaceVolumeData::ModelSources create_volume_sources(const ModelVolume *text_vo
|
|||||||
return create_sources(volumes, text_volume->id().id);
|
return create_sources(volumes, text_volume->id().id);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
} // namespace Slic3r::GUI::Emboss
|
} // namespace Slic3r::GUI::Emboss
|
||||||
|
|
||||||
/////////////////
|
/////////////////
|
||||||
@ -360,6 +363,8 @@ bool priv::check(const DataBase &input, bool check_fontfile, bool use_surface)
|
|||||||
res &= !input.volume_name.empty();
|
res &= !input.volume_name.empty();
|
||||||
assert(input.text_configuration.style.prop.use_surface == use_surface);
|
assert(input.text_configuration.style.prop.use_surface == use_surface);
|
||||||
res &= input.text_configuration.style.prop.use_surface == use_surface;
|
res &= input.text_configuration.style.prop.use_surface == use_surface;
|
||||||
|
assert(input.text_configuration.style.prop.per_glyph == !input.text_lines.empty());
|
||||||
|
res &= input.text_configuration.style.prop.per_glyph == !input.text_lines.empty();
|
||||||
return res;
|
return res;
|
||||||
}
|
}
|
||||||
bool priv::check(const DataCreateVolume &input, bool is_main_thread) {
|
bool priv::check(const DataCreateVolume &input, bool is_main_thread) {
|
||||||
@ -425,10 +430,16 @@ ExPolygons priv::create_shape(DataBase &input, Fnc was_canceled) {
|
|||||||
return text2shapes(font, text, prop, was_canceled);
|
return text2shapes(font, text, prop, was_canceled);
|
||||||
}
|
}
|
||||||
|
|
||||||
template<typename Fnc>
|
#define STORE_SAMPLING
|
||||||
TriangleMesh priv::try_create_mesh(DataBase &input, Fnc was_canceled)
|
#ifdef STORE_SAMPLING
|
||||||
|
#include "libslic3r/SVG.hpp"
|
||||||
|
#endif // STORE_SAMPLING
|
||||||
|
namespace {
|
||||||
|
template<typename Fnc> TriangleMesh create_mesh_per_glyph(DataBase &input, Fnc was_canceled)
|
||||||
{
|
{
|
||||||
if (!input.text_lines.empty()){
|
// method use square of coord stored into int64_t
|
||||||
|
static_assert(std::is_same<Point::coord_type, int32_t>());
|
||||||
|
|
||||||
FontFileWithCache &font = input.font_file;
|
FontFileWithCache &font = input.font_file;
|
||||||
const TextConfiguration &tc = input.text_configuration;
|
const TextConfiguration &tc = input.text_configuration;
|
||||||
assert(get_count_lines(tc.text) == input.text_lines.size());
|
assert(get_count_lines(tc.text) == input.text_lines.size());
|
||||||
@ -441,10 +452,13 @@ TriangleMesh priv::try_create_mesh(DataBase &input, Fnc was_canceled)
|
|||||||
if (shapes.empty())
|
if (shapes.empty())
|
||||||
return {};
|
return {};
|
||||||
|
|
||||||
|
const FontFile &ff = *font.font_file;
|
||||||
|
double shape_scale = get_shape_scale(prop, ff);
|
||||||
|
|
||||||
BoundingBox extents; // whole text to find center
|
BoundingBox extents; // whole text to find center
|
||||||
// separate lines of text to vector
|
// separate lines of text to vector
|
||||||
std::vector<BoundingBoxes> bbs(count_lines);
|
std::vector<BoundingBoxes> bbs(count_lines);
|
||||||
size_t line_index = 0;
|
size_t text_line_index = 0;
|
||||||
// s_i .. shape index
|
// s_i .. shape index
|
||||||
for (size_t s_i = 0; s_i < shapes.size(); ++s_i) {
|
for (size_t s_i = 0; s_i < shapes.size(); ++s_i) {
|
||||||
const ExPolygons &shape = shapes[s_i];
|
const ExPolygons &shape = shapes[s_i];
|
||||||
@ -453,61 +467,98 @@ TriangleMesh priv::try_create_mesh(DataBase &input, Fnc was_canceled)
|
|||||||
bb = get_extents(shape);
|
bb = get_extents(shape);
|
||||||
extents.merge(bb);
|
extents.merge(bb);
|
||||||
}
|
}
|
||||||
BoundingBoxes &line_bbs = bbs[line_index];
|
BoundingBoxes &line_bbs = bbs[text_line_index];
|
||||||
line_bbs.push_back(bb);
|
line_bbs.push_back(bb);
|
||||||
if (ws[s_i] == '\n')
|
if (ws[s_i] == '\n')
|
||||||
++line_index;
|
++text_line_index;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
double projec_scale = shape_scale / SHAPE_SCALE;
|
||||||
|
double depth = prop.emboss / projec_scale;
|
||||||
|
auto projectZ = std::make_unique<ProjectZ>(depth);
|
||||||
|
auto scale_tr = Eigen::Scaling(projec_scale);
|
||||||
|
|
||||||
|
// half of font em size for direction of letter emboss
|
||||||
|
double em_2_mm = prop.size_in_mm / 2.;
|
||||||
|
int32_t em_2_polygon = static_cast<int32_t>(std::round(scale_(em_2_mm)));
|
||||||
|
|
||||||
Point center = extents.center();
|
Point center = extents.center();
|
||||||
size_t s_i_offset = 0; // shape index offset(for next lines)
|
size_t s_i_offset = 0; // shape index offset(for next lines)
|
||||||
for (line_index = 0; line_index < input.text_lines.size(); ++line_index) {
|
indexed_triangle_set result;
|
||||||
const BoundingBoxes &line_bbs = bbs[line_index];
|
for (text_line_index = 0; text_line_index < input.text_lines.size(); ++text_line_index) {
|
||||||
// find BB in center of line
|
const BoundingBoxes &line_bbs = bbs[text_line_index];
|
||||||
size_t first_right_index = 0;
|
const TextLine &line = input.text_lines[text_line_index];
|
||||||
for (const BoundingBox &bb : line_bbs)
|
// IMPROVE: do not precalculate samples do it inline - store result its
|
||||||
if (bb.min.x() > center.x()) {
|
PolygonPoints samples = sample_slice(line, line_bbs, center.x(), shape_scale);
|
||||||
break;
|
std::vector<double> angles = calculate_angles(em_2_polygon, samples, line.polygon);
|
||||||
} else {
|
|
||||||
++first_right_index;
|
|
||||||
}
|
|
||||||
|
|
||||||
// calc transformation for letters on the Right side from center
|
for (size_t i = 0; i < line_bbs.size(); ++i) {
|
||||||
for (size_t index = first_right_index; index != line_bbs.size(); ++index) {
|
const BoundingBox &line_bb = line_bbs[i];
|
||||||
const BoundingBox &bb = line_bbs[index];
|
if (!line_bb.defined)
|
||||||
Point letter_center = bb.center();
|
continue;
|
||||||
|
|
||||||
|
Vec2d to_zero_vec = line_bb.center().cast<double>() * shape_scale; // [in mm]
|
||||||
|
auto to_zero = Eigen::Translation<double, 3>(-to_zero_vec.x(), 0., 0.);
|
||||||
|
|
||||||
const ExPolygons &letter_shape = shapes[s_i_offset + index];
|
const double &angle = angles[i];
|
||||||
}
|
auto rotate = Eigen::AngleAxisd(angle + M_PI_2, Vec3d::UnitY());
|
||||||
|
|
||||||
// calc transformation for letters on the Left side from center
|
const PolygonPoint &sample = samples[i];
|
||||||
for (size_t index = first_right_index; index < line_bbs.size(); --index) {
|
Vec2d offset_vec = unscale(sample.point); // [in mm]
|
||||||
|
auto offset_tr = Eigen::Translation<double, 3>(offset_vec.x(), 0., -offset_vec.y());
|
||||||
|
|
||||||
}
|
//Transform3d tr = offset_tr * rotate * to_zero * scale_tr;
|
||||||
|
Transform3d tr = offset_tr * rotate * to_zero * scale_tr;
|
||||||
|
//Transform3d tr = Transform3d::Identity() * scale_tr;
|
||||||
|
const ExPolygons &letter_shape = shapes[s_i_offset + i];
|
||||||
|
|
||||||
size_t s_i = s_i_offset; // shape index
|
|
||||||
|
|
||||||
s_i_offset += line_bbs.size();
|
|
||||||
}
|
|
||||||
|
|
||||||
// create per letter transformation
|
|
||||||
const FontFile &ff = *input.font_file.font_file;
|
|
||||||
// NOTE: SHAPE_SCALE is applied in ProjectZ
|
|
||||||
double scale = get_shape_scale(prop, ff) / SHAPE_SCALE;
|
|
||||||
double depth = prop.emboss / scale;
|
|
||||||
auto projectZ = std::make_unique<ProjectZ>(depth);
|
auto projectZ = std::make_unique<ProjectZ>(depth);
|
||||||
auto scale_tr = Eigen::Scaling(scale);
|
ProjectTransform project(std::move(projectZ), tr);
|
||||||
|
indexed_triangle_set glyph_its = polygons2model(letter_shape, project);
|
||||||
|
its_merge(result, std::move(glyph_its));
|
||||||
|
}
|
||||||
|
s_i_offset += line_bbs.size();
|
||||||
|
|
||||||
for (wchar_t wc: ws){
|
#ifdef STORE_SAMPLING
|
||||||
|
{ // Debug store polygon
|
||||||
|
//std::string stl_filepath = "C:/data/temp/line" + std::to_string(text_line_index) + "_model.stl";
|
||||||
|
//bool suc = its_write_stl_ascii(stl_filepath.c_str(), "label", result);
|
||||||
|
|
||||||
|
BoundingBox bbox = get_extents(line.polygon);
|
||||||
|
std::string file_path = "C:/data/temp/line" + std::to_string(text_line_index) + "_letter_position.svg";
|
||||||
|
SVG svg(file_path, bbox);
|
||||||
|
svg.draw(line.polygon);
|
||||||
|
int32_t radius = bbox.size().x() / 300;
|
||||||
|
for (size_t i = 0; i < samples.size(); i++) {
|
||||||
|
const PolygonPoint &pp = samples[i];
|
||||||
|
const Point& p = pp.point;
|
||||||
|
svg.draw(p, "green", radius);
|
||||||
|
std::string label = std::string(" ")+tc.text[i];
|
||||||
|
svg.draw_text(p, label.c_str(), "black");
|
||||||
|
|
||||||
|
double a = angles[i];
|
||||||
|
double length = 3.0 * radius;
|
||||||
|
Point n(length * std::cos(a), length * std::sin(a));
|
||||||
|
svg.draw(Slic3r::Line(p - n, p + n), "Lime");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif // STORE_SAMPLING
|
||||||
}
|
}
|
||||||
|
|
||||||
// ProjectTransform project(std::move(projectZ), )
|
// ProjectTransform project(std::move(projectZ), )
|
||||||
// if (was_canceled()) return {};
|
// if (was_canceled()) return {};
|
||||||
//return TriangleMesh(polygons2model(shapes, project));
|
return TriangleMesh(result);
|
||||||
//indexed_triangle_set result;
|
}
|
||||||
|
} // namespace
|
||||||
|
|
||||||
|
|
||||||
|
template<typename Fnc>
|
||||||
|
TriangleMesh priv::try_create_mesh(DataBase &input, Fnc was_canceled)
|
||||||
|
{
|
||||||
|
if (!input.text_lines.empty()) {
|
||||||
|
TriangleMesh tm = create_mesh_per_glyph(input, was_canceled);
|
||||||
|
if (!tm.empty())
|
||||||
|
return tm;
|
||||||
}
|
}
|
||||||
|
|
||||||
ExPolygons shapes = priv::create_shape(input, was_canceled);
|
ExPolygons shapes = priv::create_shape(input, was_canceled);
|
||||||
|
@ -35,7 +35,7 @@ struct DataBase
|
|||||||
|
|
||||||
// Define per letter projection on one text line
|
// Define per letter projection on one text line
|
||||||
// [optional] It is not used when empty
|
// [optional] It is not used when empty
|
||||||
TextLines text_lines;
|
Slic3r::Emboss::TextLines text_lines;
|
||||||
};
|
};
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
@ -220,7 +220,6 @@ SurfaceVolumeData::ModelSources create_sources(const ModelVolumePtrs &volumes, s
|
|||||||
/// <returns>Source data for cut surface from</returns>
|
/// <returns>Source data for cut surface from</returns>
|
||||||
SurfaceVolumeData::ModelSources create_volume_sources(const ModelVolume *text_volume);
|
SurfaceVolumeData::ModelSources create_volume_sources(const ModelVolume *text_volume);
|
||||||
|
|
||||||
|
|
||||||
/// <summary>
|
/// <summary>
|
||||||
/// Update text volume to use surface from object
|
/// Update text volume to use surface from object
|
||||||
/// </summary>
|
/// </summary>
|
||||||
@ -235,7 +234,6 @@ public:
|
|||||||
void process(Ctl &ctl) override;
|
void process(Ctl &ctl) override;
|
||||||
void finalize(bool canceled, std::exception_ptr &eptr) override;
|
void finalize(bool canceled, std::exception_ptr &eptr) override;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace Slic3r::GUI
|
} // namespace Slic3r::GUI
|
||||||
|
|
||||||
#endif // slic3r_EmbossJob_hpp_
|
#endif // slic3r_EmbossJob_hpp_
|
||||||
|
@ -20,10 +20,10 @@
|
|||||||
#include "slic3r/GUI/3DScene.hpp"
|
#include "slic3r/GUI/3DScene.hpp"
|
||||||
|
|
||||||
using namespace Slic3r;
|
using namespace Slic3r;
|
||||||
|
using namespace Slic3r::Emboss;
|
||||||
using namespace Slic3r::GUI;
|
using namespace Slic3r::GUI;
|
||||||
|
|
||||||
namespace {
|
namespace {
|
||||||
|
|
||||||
const Slic3r::Polygon *largest(const Slic3r::Polygons &polygons)
|
const Slic3r::Polygon *largest(const Slic3r::Polygons &polygons)
|
||||||
{
|
{
|
||||||
if (polygons.empty())
|
if (polygons.empty())
|
||||||
@ -45,8 +45,8 @@ const Slic3r::Polygon *largest(const Slic3r::Polygons &polygons)
|
|||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
indexed_triangle_set create_its(const Slic3r::Polygon &polygon, float width_half) {
|
indexed_triangle_set its_create_belt(const Slic3r::Polygon &polygon, float width_half) {
|
||||||
// Improve: Create torus instead of flat path (with model overlaps)
|
// Improve: Create torus instead of flat belt path (with model overlaps)
|
||||||
assert(!polygon.empty());
|
assert(!polygon.empty());
|
||||||
if (polygon.empty())
|
if (polygon.empty())
|
||||||
return {};
|
return {};
|
||||||
@ -86,65 +86,89 @@ indexed_triangle_set create_its(const Slic3r::Polygon &polygon, float width_half
|
|||||||
model.indices.emplace_back(b2, t2, b1);
|
model.indices.emplace_back(b2, t2, b1);
|
||||||
prev_i = i;
|
prev_i = i;
|
||||||
}
|
}
|
||||||
|
|
||||||
return model;
|
return model;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* GLModel create_model(const Slic3r::Polygon &polygon, float width_half = 0.5f, ColorRGBA color = ColorRGBA(0.f, 1.f, .2f, 0.5f))
|
indexed_triangle_set its_create_torus(const Slic3r::Polygon &polygon, float radius, size_t steps = 20)
|
||||||
{
|
{
|
||||||
// Improve: Create torus instead of flat path (with model overlaps)
|
|
||||||
assert(!polygon.empty());
|
assert(!polygon.empty());
|
||||||
if (polygon.empty())
|
if (polygon.empty())
|
||||||
return {};
|
return {};
|
||||||
|
|
||||||
// add a small positive offset to avoid z-fighting
|
size_t count = polygon.size();
|
||||||
float offset = static_cast<float>(scale_(0.015f));
|
if (count < 3)
|
||||||
Polygons polygons_expanded = expand(polygon, offset);
|
|
||||||
const Slic3r::Polygon *polygon_expanded_ptr = largest(polygons_expanded);
|
|
||||||
assert(polygon_expanded_ptr != nullptr);
|
|
||||||
if (polygon_expanded_ptr == nullptr || polygon_expanded_ptr->empty())
|
|
||||||
return {};
|
return {};
|
||||||
const Slic3r::Polygon &polygon_expanded = *polygon_expanded_ptr;
|
|
||||||
|
|
||||||
// inspired by 3DScene.cpp void GLVolume::SinkingContours::update()
|
// convert and scale to float
|
||||||
GLModel::Geometry init_data;
|
std::vector<Vec2f> points_d;
|
||||||
init_data.format = {GLModel::Geometry::EPrimitiveType::Triangles, GUI::GLModel::Geometry::EVertexLayout::P3};
|
points_d.reserve(count);
|
||||||
init_data.color = color;
|
for (const Point &point : polygon.points)
|
||||||
|
points_d.push_back(unscale(point).cast<float>());
|
||||||
|
|
||||||
size_t count = polygon_expanded.size();
|
// pre calculate normalized line directions
|
||||||
init_data.reserve_vertices(2 * count);
|
auto calc_line_norm = [](const Vec2f &f, const Vec2f &s) -> Vec2f { return (s - f).normalized(); };
|
||||||
init_data.reserve_indices(2 * count);
|
std::vector<Vec2f> line_norm(points_d.size());
|
||||||
|
for (size_t i = 0; i < count - 1; ++i)
|
||||||
|
line_norm[i] = calc_line_norm(points_d[i], points_d[i + 1]);
|
||||||
|
line_norm.back() = calc_line_norm(points_d.back(), points_d.front());
|
||||||
|
|
||||||
for (const Point &point : polygon_expanded.points) {
|
// calculate normals for each point
|
||||||
Vec2f point_d = unscale(point).cast<float>();
|
auto calc_norm = [](const Vec2f &prev, const Vec2f &next) -> Vec2f {
|
||||||
Vec3f vertex(point_d.x(), point_d.y(), width_half);
|
Vec2f dir = prev + next;
|
||||||
init_data.add_vertex(vertex);
|
return Vec2f(-dir.x(), dir.y());
|
||||||
vertex.z() *= -1;
|
};
|
||||||
init_data.add_vertex(vertex);
|
std::vector<Vec2f> points_norm(points_d.size());
|
||||||
|
points_norm.front() = calc_norm(line_norm.back(), line_norm[1]);
|
||||||
|
for (size_t i = 1; i < points_d.size() - 1; ++i)
|
||||||
|
points_norm[i] = calc_norm(line_norm[i - 1], line_norm[i + 1]);
|
||||||
|
points_norm.back() = calc_norm(line_norm[points_d.size() - 2], line_norm.front());
|
||||||
|
|
||||||
|
// precalculate sinus and cosinus
|
||||||
|
double angle_step = 2 * M_PI / steps;
|
||||||
|
std::vector<std::pair<double, float>> sin_cos;
|
||||||
|
sin_cos.reserve(steps);
|
||||||
|
for (size_t s = 0; s < steps; ++s) {
|
||||||
|
double angle = s * angle_step;
|
||||||
|
sin_cos.emplace_back(
|
||||||
|
radius * std::sin(angle),
|
||||||
|
static_cast<float>(radius * std::cos(angle))
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
// create torus model along polygon path
|
||||||
|
indexed_triangle_set model;
|
||||||
|
model.vertices.reserve(steps * count);
|
||||||
|
model.indices.reserve(2 * steps * count);
|
||||||
|
for (size_t i = 0; i < count; ++i) {
|
||||||
|
const Vec2f point_d = points_d[i];
|
||||||
|
const Vec2f norm = points_norm[i];
|
||||||
|
for (const auto &[s, c] : sin_cos) {
|
||||||
|
Vec2f xy = s * norm + point_d;
|
||||||
|
model.vertices.emplace_back(xy.x(), xy.y(), c);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
unsigned int prev_i = count - 1;
|
unsigned int prev_i = count - 1;
|
||||||
for (unsigned int i = 0; i < count; ++i) {
|
for (unsigned int i = 0; i < count; ++i) {
|
||||||
|
// TODO: solve <180, =180 and >180 angle
|
||||||
|
// to not create self intersection
|
||||||
|
|
||||||
// t .. top
|
// t .. top
|
||||||
// b .. bottom
|
// b .. bottom
|
||||||
unsigned int t1 = prev_i * 2;
|
unsigned int prev_t = (prev_i+1) * steps - 1;
|
||||||
unsigned int b1 = t1 + 1;
|
unsigned int t = (i+1) * steps - 1;
|
||||||
unsigned int t2 = i * 2;
|
for (size_t s = 0; s < steps; ++s) {
|
||||||
unsigned int b2 = t2 + 1;
|
unsigned int prev_b = prev_i * steps + s;
|
||||||
init_data.add_triangle(t1, b1, t2);
|
unsigned int b = i * steps + s;
|
||||||
init_data.add_triangle(b2, t2, b1);
|
model.indices.emplace_back(prev_t, prev_b, t);
|
||||||
|
model.indices.emplace_back(b, t, prev_b);
|
||||||
|
prev_t = prev_b;
|
||||||
|
t = b;
|
||||||
|
}
|
||||||
prev_i = i;
|
prev_i = i;
|
||||||
}
|
}
|
||||||
|
return model;
|
||||||
|
}
|
||||||
// line .. y offset from volume(define line for sliced polygon)
|
|
||||||
|
|
||||||
|
|
||||||
GLModel gl_model;
|
|
||||||
gl_model.init_from(std::move(init_data));
|
|
||||||
return gl_model;
|
|
||||||
}*/
|
|
||||||
|
|
||||||
|
|
||||||
// select closest contour for each line
|
// select closest contour for each line
|
||||||
TextLines select_closest_contour(const std::vector<Polygons> &line_contours) {
|
TextLines select_closest_contour(const std::vector<Polygons> &line_contours) {
|
||||||
@ -181,41 +205,53 @@ TextLines select_closest_contour(const std::vector<Polygons> &line_contours) {
|
|||||||
expolygons[index.expolygons_index].holes[index.hole_index()];
|
expolygons[index.expolygons_index].holes[index.hole_index()];
|
||||||
|
|
||||||
Point hit_point_int = hit_point.cast<Point::coord_type>();
|
Point hit_point_int = hit_point.cast<Point::coord_type>();
|
||||||
TextLine tl{polygon, index.point_index, hit_point_int};
|
TextLine tl{polygon, PolygonPoint{index.point_index, hit_point_int}};
|
||||||
result.emplace_back(tl);
|
result.emplace_back(tl);
|
||||||
}
|
}
|
||||||
return result;
|
return result;
|
||||||
}
|
}
|
||||||
|
|
||||||
GLModel create_model(const TextLines &lines, const std::vector<float> &line_centers)
|
inline Eigen::AngleAxis<double> get_rotation() { return Eigen::AngleAxis(-M_PI_2, Vec3d::UnitX()); }
|
||||||
|
|
||||||
|
indexed_triangle_set create_its(const TextLines &lines)
|
||||||
{
|
{
|
||||||
double model_half_width = 0.5; // [in volume mm]
|
const float model_half_width = 0.75; // [in volume mm]
|
||||||
ColorRGBA color(.7f, .7f, .7f, .7f); // Gray
|
|
||||||
|
|
||||||
indexed_triangle_set its;
|
indexed_triangle_set its;
|
||||||
auto rot = Eigen::AngleAxis(M_PI_2, Vec3d::UnitX());
|
|
||||||
|
|
||||||
assert(lines.size() == line_centers.size());
|
|
||||||
// create model from polygons
|
// create model from polygons
|
||||||
for (size_t i = 0; i < lines.size(); ++i) {
|
for (const TextLine &line : lines) {
|
||||||
const Slic3r::Polygon &polygon = lines[i].polygon;
|
const Slic3r::Polygon &polygon = line.polygon;
|
||||||
if (polygon.empty()) continue;
|
if (polygon.empty()) continue;
|
||||||
double line_center = line_centers[i];
|
indexed_triangle_set line_its = its_create_belt(polygon, model_half_width);
|
||||||
indexed_triangle_set line_its = create_its(polygon, model_half_width);
|
//indexed_triangle_set line_its = its_create_torus(polygon, model_half_width);
|
||||||
auto transl = Eigen::Translation3d(0., -line_center, 0.);
|
auto transl = Eigen::Translation3d(0., -line.y, 0.);
|
||||||
Transform3d tr = transl * rot;
|
Transform3d tr = transl * get_rotation();
|
||||||
its_transform(line_its, tr);
|
its_transform(line_its, tr);
|
||||||
its_merge(its, line_its);
|
its_merge(its, line_its);
|
||||||
}
|
}
|
||||||
|
return its;
|
||||||
|
}
|
||||||
|
|
||||||
GLModel gl_model;
|
GLModel::Geometry create_geometry(const TextLines &lines)
|
||||||
gl_model.init_from(its);
|
{
|
||||||
gl_model.set_color(color);
|
indexed_triangle_set its = create_its(lines);
|
||||||
return gl_model;
|
|
||||||
|
GLModel::Geometry geometry;
|
||||||
|
geometry.format = {GLModel::Geometry::EPrimitiveType::Triangles, GUI::GLModel::Geometry::EVertexLayout::P3};
|
||||||
|
ColorRGBA color(.7f, .7f, .7f, .7f); // Transparent Gray
|
||||||
|
geometry.color = color;
|
||||||
|
|
||||||
|
geometry.reserve_vertices(its.vertices.size());
|
||||||
|
for (Vec3f vertex : its.vertices)
|
||||||
|
geometry.add_vertex(vertex);
|
||||||
|
|
||||||
|
geometry.reserve_indices(its.indices.size() * 3);
|
||||||
|
for (Vec3i t : its.indices)
|
||||||
|
geometry.add_triangle(t[0], t[1], t[2]);
|
||||||
|
return geometry;
|
||||||
}
|
}
|
||||||
} // namespace
|
} // namespace
|
||||||
|
|
||||||
void TextLinesModel::init(const Selection &selection, double line_height)
|
void TextLinesModel::init(const Selection &selection, double line_height, double line_offset)
|
||||||
{
|
{
|
||||||
const GLVolume *gl_volume_ptr = selection.get_first_volume();
|
const GLVolume *gl_volume_ptr = selection.get_first_volume();
|
||||||
if (gl_volume_ptr == nullptr)
|
if (gl_volume_ptr == nullptr)
|
||||||
@ -240,16 +276,15 @@ void TextLinesModel::init(const Selection &selection, double line_height)
|
|||||||
if (count_lines == 0)
|
if (count_lines == 0)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
double first_line_center = -((count_lines / 2) * line_height) - ((count_lines % 2 == 0)? line_height/2. : 0.);
|
double first_line_center = line_offset + (count_lines / 2) * line_height - ((count_lines % 2 == 0) ? line_height / 2. : 0.);
|
||||||
std::vector<float> line_centers(count_lines);
|
std::vector<float> line_centers(count_lines);
|
||||||
for (size_t i = 0; i < count_lines; ++i)
|
for (size_t i = 0; i < count_lines; ++i)
|
||||||
line_centers[i] = static_cast<float>(first_line_center + i * line_height);
|
line_centers[i] = static_cast<float>(first_line_center - i * line_height);
|
||||||
|
|
||||||
const Transform3d &mv_trafo = gl_volume.get_volume_transformation().get_matrix();
|
const Transform3d &mv_trafo = gl_volume.get_volume_transformation().get_matrix();
|
||||||
|
|
||||||
// contour transformation
|
// contour transformation
|
||||||
auto rot = Eigen::AngleAxis(M_PI_2, Vec3d::UnitX());
|
Transform3d c_trafo = mv_trafo * get_rotation();
|
||||||
Transform3d c_trafo = mv_trafo * rot;
|
|
||||||
Transform3d c_trafo_inv = c_trafo.inverse();
|
Transform3d c_trafo_inv = c_trafo.inverse();
|
||||||
|
|
||||||
std::vector<Polygons> line_contours(count_lines);
|
std::vector<Polygons> line_contours(count_lines);
|
||||||
@ -275,7 +310,19 @@ void TextLinesModel::init(const Selection &selection, double line_height)
|
|||||||
}
|
}
|
||||||
|
|
||||||
m_lines = select_closest_contour(line_contours);
|
m_lines = select_closest_contour(line_contours);
|
||||||
m_model = create_model(m_lines, line_centers);
|
assert(m_lines.size() == count_lines);
|
||||||
|
assert(line_centers.size() == count_lines);
|
||||||
|
for (size_t i = 0; i < count_lines; ++i)
|
||||||
|
m_lines[i].y = line_centers[i];
|
||||||
|
|
||||||
|
m_model.reset();
|
||||||
|
//*
|
||||||
|
m_model.init_from(create_geometry(m_lines));
|
||||||
|
/*/
|
||||||
|
ColorRGBA color(.7f, .7f, .7f, .7f); // Transparent Gray
|
||||||
|
m_model.set_color(color);
|
||||||
|
m_model.init_from(create_its(m_lines));
|
||||||
|
//*/
|
||||||
}
|
}
|
||||||
|
|
||||||
void TextLinesModel::render(const Transform3d &text_world)
|
void TextLinesModel::render(const Transform3d &text_world)
|
||||||
|
@ -7,40 +7,26 @@
|
|||||||
#include <libslic3r/Emboss.hpp>
|
#include <libslic3r/Emboss.hpp>
|
||||||
#include "slic3r/GUI/GLModel.hpp"
|
#include "slic3r/GUI/GLModel.hpp"
|
||||||
|
|
||||||
|
|
||||||
namespace Slic3r::GUI {
|
namespace Slic3r::GUI {
|
||||||
|
|
||||||
class Selection;
|
class Selection;
|
||||||
|
|
||||||
/// <summary>
|
|
||||||
/// Define polygon for draw letters
|
|
||||||
/// </summary>
|
|
||||||
struct TextLine
|
|
||||||
{
|
|
||||||
// slice of object
|
|
||||||
Polygon polygon;
|
|
||||||
|
|
||||||
// index to point in polygon which starts line, which is closest to zero
|
|
||||||
size_t start_index;
|
|
||||||
|
|
||||||
// Point on line closest to zero
|
|
||||||
Point start_point;
|
|
||||||
};
|
|
||||||
using TextLines = std::vector<TextLine>;
|
|
||||||
|
|
||||||
class TextLinesModel
|
class TextLinesModel
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// line_height in mm
|
/// <summary>
|
||||||
void init(const Selection &selection, double line_height);
|
/// Initialize model and lines
|
||||||
|
/// </summary>
|
||||||
|
/// <param name="selection">Must be selected text volume</param>
|
||||||
|
/// <param name="line_height">Height of text line with spacing [in mm]</param>
|
||||||
|
/// <param name="line_offset">Offset of base line from center [in mm]</param>
|
||||||
|
void init(const Selection &selection, double line_height, double line_offset = 0.);
|
||||||
void render(const Transform3d &text_world);
|
void render(const Transform3d &text_world);
|
||||||
|
|
||||||
bool is_init() const { return m_model.is_initialized(); }
|
bool is_init() const { return m_model.is_initialized(); }
|
||||||
void reset() { m_model.reset(); }
|
void reset() { m_model.reset(); }
|
||||||
const TextLines &get_lines() const { return m_lines; }
|
const Slic3r::Emboss::TextLines &get_lines() const { return m_lines; }
|
||||||
static double calc_line_height(const Slic3r::Emboss::FontFile& ff, const FontProp& fp);
|
static double calc_line_height(const Slic3r::Emboss::FontFile& ff, const FontProp& fp);
|
||||||
private:
|
private:
|
||||||
TextLines m_lines;
|
Slic3r::Emboss::TextLines m_lines;
|
||||||
|
|
||||||
// Keep model for visualization text lines
|
// Keep model for visualization text lines
|
||||||
GLModel m_model;
|
GLModel m_model;
|
||||||
|
Loading…
x
Reference in New Issue
Block a user