mirror of
https://github.com/SoftFever/OrcaSlicer.git
synced 2025-10-23 16:51:21 -06:00
The gizmo is now able to triangulate and show the cut, the triangulated cut is cached
This commit is contained in:
parent
9b7857aaab
commit
bbda1896f9
6 changed files with 150 additions and 48 deletions
|
@ -693,6 +693,16 @@ void TriangleMeshSlicer::init(TriangleMesh *_mesh, throw_on_cancel_callback_type
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void TriangleMeshSlicer::set_up_direction(const Vec3f& up)
|
||||||
|
{
|
||||||
|
m_quaternion.setFromTwoVectors(up, Vec3f::UnitZ());
|
||||||
|
m_use_quaternion = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void TriangleMeshSlicer::slice(const std::vector<float> &z, std::vector<Polygons>* layers, throw_on_cancel_callback_type throw_on_cancel) const
|
void TriangleMeshSlicer::slice(const std::vector<float> &z, std::vector<Polygons>* layers, throw_on_cancel_callback_type throw_on_cancel) const
|
||||||
{
|
{
|
||||||
BOOST_LOG_TRIVIAL(debug) << "TriangleMeshSlicer::slice";
|
BOOST_LOG_TRIVIAL(debug) << "TriangleMeshSlicer::slice";
|
||||||
|
@ -795,7 +805,14 @@ void TriangleMeshSlicer::slice(const std::vector<float> &z, std::vector<Polygons
|
||||||
void TriangleMeshSlicer::_slice_do(size_t facet_idx, std::vector<IntersectionLines>* lines, boost::mutex* lines_mutex,
|
void TriangleMeshSlicer::_slice_do(size_t facet_idx, std::vector<IntersectionLines>* lines, boost::mutex* lines_mutex,
|
||||||
const std::vector<float> &z) const
|
const std::vector<float> &z) const
|
||||||
{
|
{
|
||||||
const stl_facet &facet = this->mesh->stl.facet_start[facet_idx];
|
const stl_facet &facet_orig = this->mesh->stl.facet_start[facet_idx];
|
||||||
|
stl_facet facet = facet_orig;
|
||||||
|
|
||||||
|
if (m_use_quaternion) {
|
||||||
|
facet.vertex[0] = m_quaternion * facet.vertex[0];
|
||||||
|
facet.vertex[1] = m_quaternion * facet.vertex[1];
|
||||||
|
facet.vertex[2] = m_quaternion * facet.vertex[2];
|
||||||
|
}
|
||||||
|
|
||||||
// find facet extents
|
// find facet extents
|
||||||
const float min_z = fminf(facet.vertex[0](2), fminf(facet.vertex[1](2), facet.vertex[2](2)));
|
const float min_z = fminf(facet.vertex[0](2), fminf(facet.vertex[1](2), facet.vertex[2](2)));
|
||||||
|
@ -866,20 +883,36 @@ TriangleMeshSlicer::FacetSliceType TriangleMeshSlicer::slice_facet(
|
||||||
// (external on the right of the line)
|
// (external on the right of the line)
|
||||||
const int *vertices = this->mesh->stl.v_indices[facet_idx].vertex;
|
const int *vertices = this->mesh->stl.v_indices[facet_idx].vertex;
|
||||||
int i = (facet.vertex[1].z() == min_z) ? 1 : ((facet.vertex[2].z() == min_z) ? 2 : 0);
|
int i = (facet.vertex[1].z() == min_z) ? 1 : ((facet.vertex[2].z() == min_z) ? 2 : 0);
|
||||||
|
|
||||||
|
// These are used only if the cut plane is inclined:
|
||||||
|
stl_vertex rotated_a;
|
||||||
|
stl_vertex rotated_b;
|
||||||
|
|
||||||
for (int j = i; j - i < 3; ++j) { // loop through facet edges
|
for (int j = i; j - i < 3; ++j) { // loop through facet edges
|
||||||
int edge_id = this->facets_edges[facet_idx * 3 + (j % 3)];
|
int edge_id = this->facets_edges[facet_idx * 3 + (j % 3)];
|
||||||
int a_id = vertices[j % 3];
|
int a_id = vertices[j % 3];
|
||||||
int b_id = vertices[(j+1) % 3];
|
int b_id = vertices[(j+1) % 3];
|
||||||
const stl_vertex *a = &this->v_scaled_shared[a_id];
|
|
||||||
const stl_vertex *b = &this->v_scaled_shared[b_id];
|
const stl_vertex *a;
|
||||||
|
const stl_vertex *b;
|
||||||
|
if (m_use_quaternion) {
|
||||||
|
rotated_a = m_quaternion * this->v_scaled_shared[a_id];
|
||||||
|
rotated_b = m_quaternion * this->v_scaled_shared[b_id];
|
||||||
|
a = &rotated_a;
|
||||||
|
b = &rotated_b;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
a = &this->v_scaled_shared[a_id];
|
||||||
|
b = &this->v_scaled_shared[b_id];
|
||||||
|
}
|
||||||
|
|
||||||
// Is edge or face aligned with the cutting plane?
|
// Is edge or face aligned with the cutting plane?
|
||||||
if (a->z() == slice_z && b->z() == slice_z) {
|
if (a->z() == slice_z && b->z() == slice_z) {
|
||||||
// Edge is horizontal and belongs to the current layer.
|
// Edge is horizontal and belongs to the current layer.
|
||||||
const stl_vertex &v0 = this->v_scaled_shared[vertices[0]];
|
const stl_vertex &v0 = m_use_quaternion ? stl_vertex(m_quaternion * this->v_scaled_shared[vertices[0]]) : this->v_scaled_shared[vertices[0]];
|
||||||
const stl_vertex &v1 = this->v_scaled_shared[vertices[1]];
|
const stl_vertex &v1 = m_use_quaternion ? stl_vertex(m_quaternion * this->v_scaled_shared[vertices[1]]) : this->v_scaled_shared[vertices[1]];
|
||||||
const stl_vertex &v2 = this->v_scaled_shared[vertices[2]];
|
const stl_vertex &v2 = m_use_quaternion ? stl_vertex(m_quaternion * this->v_scaled_shared[vertices[2]]) : this->v_scaled_shared[vertices[2]];
|
||||||
const stl_normal &normal = this->mesh->stl.facet_start[facet_idx].normal;
|
const stl_normal &normal = m_use_quaternion ? stl_vertex(m_quaternion * this->mesh->stl.facet_start[facet_idx].normal) : this->mesh->stl.facet_start[facet_idx].normal;
|
||||||
// We may ignore this edge for slicing purposes, but we may still use it for object cutting.
|
// We may ignore this edge for slicing purposes, but we may still use it for object cutting.
|
||||||
FacetSliceType result = Slicing;
|
FacetSliceType result = Slicing;
|
||||||
if (min_z == max_z) {
|
if (min_z == max_z) {
|
||||||
|
@ -995,7 +1028,9 @@ TriangleMeshSlicer::FacetSliceType TriangleMeshSlicer::slice_facet(
|
||||||
if (i == line_out->a_id || i == line_out->b_id)
|
if (i == line_out->a_id || i == line_out->b_id)
|
||||||
i = vertices[2];
|
i = vertices[2];
|
||||||
assert(i != line_out->a_id && i != line_out->b_id);
|
assert(i != line_out->a_id && i != line_out->b_id);
|
||||||
line_out->edge_type = (this->v_scaled_shared[i].z() < slice_z) ? feTop : feBottom;
|
line_out->edge_type = ((m_use_quaternion ?
|
||||||
|
m_quaternion * this->v_scaled_shared[i].z()
|
||||||
|
: this->v_scaled_shared[i].z()) < slice_z) ? feTop : feBottom;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return Slicing;
|
return Slicing;
|
||||||
|
|
|
@ -171,6 +171,7 @@ public:
|
||||||
FacetSliceType slice_facet(float slice_z, const stl_facet &facet, const int facet_idx,
|
FacetSliceType slice_facet(float slice_z, const stl_facet &facet, const int facet_idx,
|
||||||
const float min_z, const float max_z, IntersectionLine *line_out) const;
|
const float min_z, const float max_z, IntersectionLine *line_out) const;
|
||||||
void cut(float z, TriangleMesh* upper, TriangleMesh* lower) const;
|
void cut(float z, TriangleMesh* upper, TriangleMesh* lower) const;
|
||||||
|
void set_up_direction(const Vec3f& up);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
const TriangleMesh *mesh;
|
const TriangleMesh *mesh;
|
||||||
|
@ -178,6 +179,10 @@ private:
|
||||||
std::vector<int> facets_edges;
|
std::vector<int> facets_edges;
|
||||||
// Scaled copy of this->mesh->stl.v_shared
|
// Scaled copy of this->mesh->stl.v_shared
|
||||||
std::vector<stl_vertex> v_scaled_shared;
|
std::vector<stl_vertex> v_scaled_shared;
|
||||||
|
// Quaternion that will be used to rotate every facet before the slicing
|
||||||
|
Eigen::Quaternion<float, Eigen::DontAlign> m_quaternion;
|
||||||
|
// Whether or not the above quaterion should be used
|
||||||
|
bool m_use_quaternion = false;
|
||||||
|
|
||||||
void _slice_do(size_t facet_idx, std::vector<IntersectionLines>* lines, boost::mutex* lines_mutex, const std::vector<float> &z) const;
|
void _slice_do(size_t facet_idx, std::vector<IntersectionLines>* lines, boost::mutex* lines_mutex, const std::vector<float> &z) const;
|
||||||
void make_loops(std::vector<IntersectionLine> &lines, Polygons* loops) const;
|
void make_loops(std::vector<IntersectionLine> &lines, Polygons* loops) const;
|
||||||
|
|
|
@ -4432,13 +4432,29 @@ void GLCanvas3D::_resize(unsigned int w, unsigned int h)
|
||||||
_set_current();
|
_set_current();
|
||||||
::glViewport(0, 0, w, h);
|
::glViewport(0, 0, w, h);
|
||||||
|
|
||||||
|
::glMatrixMode(GL_PROJECTION);
|
||||||
|
::glLoadIdentity();
|
||||||
|
|
||||||
|
const BoundingBoxf3& bbox = _max_bounding_box();
|
||||||
|
|
||||||
switch (m_camera.type)
|
switch (m_camera.type)
|
||||||
{
|
{
|
||||||
case Camera::Ortho:
|
case Camera::Ortho:
|
||||||
{
|
{
|
||||||
|
float w2 = w;
|
||||||
|
float h2 = h;
|
||||||
|
float two_zoom = 2.0f * get_camera_zoom();
|
||||||
|
if (two_zoom != 0.0f)
|
||||||
|
{
|
||||||
|
float inv_two_zoom = 1.0f / two_zoom;
|
||||||
|
w2 *= inv_two_zoom;
|
||||||
|
h2 *= inv_two_zoom;
|
||||||
|
}
|
||||||
|
|
||||||
// FIXME: calculate a tighter value for depth will improve z-fighting
|
// FIXME: calculate a tighter value for depth will improve z-fighting
|
||||||
float depth = 5.0f * (float)(_max_bounding_box().max_size());
|
float depth = 5.0f * (float)bbox.max_size();
|
||||||
set_ortho_projection(w, h, -depth, depth);
|
::glOrtho(-w2, w2, -h2, h2, -depth, depth);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// case Camera::Perspective:
|
// case Camera::Perspective:
|
||||||
|
@ -4470,6 +4486,8 @@ void GLCanvas3D::_resize(unsigned int w, unsigned int h)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
::glMatrixMode(GL_MODELVIEW);
|
||||||
|
|
||||||
m_dirty = false;
|
m_dirty = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -4689,22 +4707,6 @@ void GLCanvas3D::_render_axes() const
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void GLCanvas3D::set_ortho_projection(float w, float h, float near, float far) const
|
|
||||||
{
|
|
||||||
float two_zoom = 2.0f * get_camera_zoom();
|
|
||||||
if (two_zoom != 0.0f)
|
|
||||||
{
|
|
||||||
float inv_two_zoom = 1.0f / two_zoom;
|
|
||||||
w *= inv_two_zoom;
|
|
||||||
h *= inv_two_zoom;
|
|
||||||
}
|
|
||||||
::glMatrixMode(GL_PROJECTION);
|
|
||||||
::glLoadIdentity();
|
|
||||||
::glOrtho(-w, w, -h, h, near, far);
|
|
||||||
::glMatrixMode(GL_MODELVIEW);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void GLCanvas3D::_render_objects() const
|
void GLCanvas3D::_render_objects() const
|
||||||
{
|
{
|
||||||
|
|
|
@ -778,9 +778,6 @@ private:
|
||||||
// Returns the view ray line, in world coordinate, at the given mouse position.
|
// Returns the view ray line, in world coordinate, at the given mouse position.
|
||||||
Linef3 mouse_ray(const Point& mouse_pos);
|
Linef3 mouse_ray(const Point& mouse_pos);
|
||||||
|
|
||||||
// Sets current projection matrix to ortho, accounting for current camera zoom.
|
|
||||||
void set_ortho_projection(float w, float h, float near, float far) const;
|
|
||||||
|
|
||||||
void _start_timer();
|
void _start_timer();
|
||||||
void _stop_timer();
|
void _stop_timer();
|
||||||
|
|
||||||
|
|
|
@ -9,6 +9,7 @@
|
||||||
#include "slic3r/GUI/GUI_ObjectSettings.hpp"
|
#include "slic3r/GUI/GUI_ObjectSettings.hpp"
|
||||||
#include "slic3r/GUI/GUI_ObjectList.hpp"
|
#include "slic3r/GUI/GUI_ObjectList.hpp"
|
||||||
#include "slic3r/GUI/PresetBundle.hpp"
|
#include "slic3r/GUI/PresetBundle.hpp"
|
||||||
|
#include "libslic3r/Tesselate.hpp"
|
||||||
|
|
||||||
|
|
||||||
namespace Slic3r {
|
namespace Slic3r {
|
||||||
|
@ -91,12 +92,71 @@ void GLGizmoSlaSupports::on_render(const Selection& selection) const
|
||||||
::glEnable(GL_BLEND);
|
::glEnable(GL_BLEND);
|
||||||
::glEnable(GL_DEPTH_TEST);
|
::glEnable(GL_DEPTH_TEST);
|
||||||
|
|
||||||
render_points(selection, false);
|
// we'll recover current look direction from the modelview matrix (in world coords):
|
||||||
|
Eigen::Matrix<double, 4, 4, Eigen::DontAlign> modelview_matrix;
|
||||||
|
::glGetDoublev(GL_MODELVIEW_MATRIX, modelview_matrix.data());
|
||||||
|
Vec3d direction_to_camera(modelview_matrix.data()[2], modelview_matrix.data()[6], modelview_matrix.data()[10]);
|
||||||
|
|
||||||
|
if (m_quadric != nullptr && selection.is_from_single_instance())
|
||||||
|
render_points(selection, direction_to_camera, false);
|
||||||
|
|
||||||
render_selection_rectangle();
|
render_selection_rectangle();
|
||||||
|
render_clipping_plane(selection, direction_to_camera);
|
||||||
|
|
||||||
::glDisable(GL_BLEND);
|
::glDisable(GL_BLEND);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void GLGizmoSlaSupports::render_clipping_plane(const Selection& selection, const Vec3d& direction_to_camera) const
|
||||||
|
{
|
||||||
|
if (m_clipping_plane_distance == 0.f)
|
||||||
|
return;
|
||||||
|
|
||||||
|
const GLVolume* vol = selection.get_volume(*selection.get_volume_idxs().begin());
|
||||||
|
double z_shift = vol->get_sla_shift_z();
|
||||||
|
Transform3f instance_matrix = vol->get_instance_transformation().get_matrix().cast<float>();
|
||||||
|
Transform3f instance_matrix_no_translation_no_scaling = vol->get_instance_transformation().get_matrix(true,false,true).cast<float>();
|
||||||
|
Transform3f instance_matrix_no_translation = vol->get_instance_transformation().get_matrix(true).cast<float>();
|
||||||
|
Vec3f scaling = vol->get_instance_scaling_factor().cast<float>();
|
||||||
|
|
||||||
|
Vec3f up = instance_matrix_no_translation_no_scaling.inverse() * direction_to_camera.cast<float>().normalized();
|
||||||
|
up = Vec3f(up(0)*scaling(0), up(1)*scaling(1), up(2)*scaling(2));
|
||||||
|
float height = m_active_instance_bb.radius() - m_clipping_plane_distance * 2*m_active_instance_bb.radius();
|
||||||
|
float height_mesh = height;
|
||||||
|
|
||||||
|
if (m_clipping_plane_distance != m_old_clipping_plane_distance
|
||||||
|
|| m_old_direction_to_camera != direction_to_camera) {
|
||||||
|
|
||||||
|
std::vector<ExPolygons> list_of_expolys;
|
||||||
|
m_tms->set_up_direction(up);
|
||||||
|
m_tms->slice(std::vector<float>{height_mesh}, 0.f, &list_of_expolys, [](){});
|
||||||
|
m_triangles = triangulate_expolygons_2f(list_of_expolys[0]);
|
||||||
|
|
||||||
|
m_old_direction_to_camera = direction_to_camera;
|
||||||
|
m_old_clipping_plane_distance = m_clipping_plane_distance;
|
||||||
|
}
|
||||||
|
|
||||||
|
::glPushMatrix();
|
||||||
|
::glTranslated(0.0, 0.0, z_shift);
|
||||||
|
::glMultMatrixf(instance_matrix.data());
|
||||||
|
Eigen::Quaternionf q;
|
||||||
|
q.setFromTwoVectors(Vec3f::UnitZ(), up);
|
||||||
|
Eigen::AngleAxisf aa(q);
|
||||||
|
::glRotatef(aa.angle() * (180./M_PI), aa.axis()(0), aa.axis()(1), aa.axis()(2));
|
||||||
|
::glTranslatef(0.f, 0.f, -0.001f); // to make sure the cut is safely beyond the near clipping plane
|
||||||
|
|
||||||
|
::glBegin(GL_TRIANGLES);
|
||||||
|
::glColor3f(1.0f, 0.37f, 0.0f);
|
||||||
|
for (const Vec2f& point : m_triangles)
|
||||||
|
::glVertex3f(point(0), point(1), height_mesh);
|
||||||
|
::glEnd();
|
||||||
|
|
||||||
|
::glPopMatrix();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
void GLGizmoSlaSupports::render_selection_rectangle() const
|
void GLGizmoSlaSupports::render_selection_rectangle() const
|
||||||
{
|
{
|
||||||
if (!m_selection_rectangle_active)
|
if (!m_selection_rectangle_active)
|
||||||
|
@ -141,14 +201,16 @@ void GLGizmoSlaSupports::on_render_for_picking(const Selection& selection) const
|
||||||
{
|
{
|
||||||
::glEnable(GL_DEPTH_TEST);
|
::glEnable(GL_DEPTH_TEST);
|
||||||
|
|
||||||
render_points(selection, true);
|
// we'll recover current look direction from the modelview matrix (in world coords):
|
||||||
|
Eigen::Matrix<double, 4, 4, Eigen::DontAlign> modelview_matrix;
|
||||||
|
::glGetDoublev(GL_MODELVIEW_MATRIX, modelview_matrix.data());
|
||||||
|
Vec3d direction_to_camera(modelview_matrix.data()[2], modelview_matrix.data()[6], modelview_matrix.data()[10]);
|
||||||
|
|
||||||
|
render_points(selection, direction_to_camera, true);
|
||||||
}
|
}
|
||||||
|
|
||||||
void GLGizmoSlaSupports::render_points(const Selection& selection, bool picking) const
|
void GLGizmoSlaSupports::render_points(const Selection& selection, const Vec3d& direction_to_camera, bool picking) const
|
||||||
{
|
{
|
||||||
if (m_quadric == nullptr || !selection.is_from_single_instance())
|
|
||||||
return;
|
|
||||||
|
|
||||||
if (!picking)
|
if (!picking)
|
||||||
::glEnable(GL_LIGHTING);
|
::glEnable(GL_LIGHTING);
|
||||||
|
|
||||||
|
@ -157,11 +219,6 @@ void GLGizmoSlaSupports::render_points(const Selection& selection, bool picking)
|
||||||
const Transform3d& instance_scaling_matrix_inverse = vol->get_instance_transformation().get_matrix(true, true, false, true).inverse();
|
const Transform3d& instance_scaling_matrix_inverse = vol->get_instance_transformation().get_matrix(true, true, false, true).inverse();
|
||||||
const Transform3d& instance_matrix = vol->get_instance_transformation().get_matrix();
|
const Transform3d& instance_matrix = vol->get_instance_transformation().get_matrix();
|
||||||
|
|
||||||
// we'll recover current look direction from the modelview matrix (in world coords):
|
|
||||||
Eigen::Matrix<double, 4, 4, Eigen::DontAlign> modelview_matrix;
|
|
||||||
::glGetDoublev(GL_MODELVIEW_MATRIX, modelview_matrix.data());
|
|
||||||
Vec3d direction_to_camera(modelview_matrix.data()[2], modelview_matrix.data()[6], modelview_matrix.data()[10]);
|
|
||||||
|
|
||||||
::glPushMatrix();
|
::glPushMatrix();
|
||||||
::glTranslated(0.0, 0.0, z_shift);
|
::glTranslated(0.0, 0.0, z_shift);
|
||||||
::glMultMatrixd(instance_matrix.data());
|
::glMultMatrixd(instance_matrix.data());
|
||||||
|
@ -263,9 +320,6 @@ bool GLGizmoSlaSupports::is_mesh_update_necessary() const
|
||||||
{
|
{
|
||||||
return ((m_state == On) && (m_model_object != nullptr) && !m_model_object->instances.empty())
|
return ((m_state == On) && (m_model_object != nullptr) && !m_model_object->instances.empty())
|
||||||
&& ((m_model_object != m_old_model_object) || m_V.size()==0);
|
&& ((m_model_object != m_old_model_object) || m_V.size()==0);
|
||||||
|
|
||||||
//if (m_state != On || !m_model_object || m_model_object->instances.empty() || ! m_instance_matrix.isApprox(m_source_data.matrix))
|
|
||||||
// return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void GLGizmoSlaSupports::update_mesh()
|
void GLGizmoSlaSupports::update_mesh()
|
||||||
|
@ -273,10 +327,9 @@ void GLGizmoSlaSupports::update_mesh()
|
||||||
wxBusyCursor wait;
|
wxBusyCursor wait;
|
||||||
Eigen::MatrixXf& V = m_V;
|
Eigen::MatrixXf& V = m_V;
|
||||||
Eigen::MatrixXi& F = m_F;
|
Eigen::MatrixXi& F = m_F;
|
||||||
// Composite mesh of all instances in the world coordinate system.
|
|
||||||
// This mesh does not account for the possible Z up SLA offset.
|
// This mesh does not account for the possible Z up SLA offset.
|
||||||
TriangleMesh mesh = m_model_object->raw_mesh();
|
m_mesh = m_model_object->raw_mesh();
|
||||||
const stl_file& stl = mesh.stl;
|
const stl_file& stl = m_mesh.stl;
|
||||||
V.resize(3 * stl.stats.number_of_facets, 3);
|
V.resize(3 * stl.stats.number_of_facets, 3);
|
||||||
F.resize(stl.stats.number_of_facets, 3);
|
F.resize(stl.stats.number_of_facets, 3);
|
||||||
for (unsigned int i=0; i<stl.stats.number_of_facets; ++i) {
|
for (unsigned int i=0; i<stl.stats.number_of_facets; ++i) {
|
||||||
|
@ -291,6 +344,9 @@ void GLGizmoSlaSupports::update_mesh()
|
||||||
|
|
||||||
m_AABB = igl::AABB<Eigen::MatrixXf,3>();
|
m_AABB = igl::AABB<Eigen::MatrixXf,3>();
|
||||||
m_AABB.init(m_V, m_F);
|
m_AABB.init(m_V, m_F);
|
||||||
|
|
||||||
|
m_tms.reset(new TriangleMeshSlicer);
|
||||||
|
m_tms->init(&m_mesh, [](){});
|
||||||
}
|
}
|
||||||
|
|
||||||
// Unprojects the mouse position on the mesh and return the hit point and normal of the facet.
|
// Unprojects the mouse position on the mesh and return the hit point and normal of the facet.
|
||||||
|
|
|
@ -31,6 +31,8 @@ private:
|
||||||
Eigen::MatrixXf m_V; // vertices
|
Eigen::MatrixXf m_V; // vertices
|
||||||
Eigen::MatrixXi m_F; // facets indices
|
Eigen::MatrixXi m_F; // facets indices
|
||||||
igl::AABB<Eigen::MatrixXf,3> m_AABB;
|
igl::AABB<Eigen::MatrixXf,3> m_AABB;
|
||||||
|
TriangleMesh m_mesh;
|
||||||
|
mutable std::vector<Vec2f> m_triangles;
|
||||||
|
|
||||||
class CacheEntry {
|
class CacheEntry {
|
||||||
public:
|
public:
|
||||||
|
@ -61,7 +63,8 @@ private:
|
||||||
virtual void on_render_for_picking(const Selection& selection) const;
|
virtual void on_render_for_picking(const Selection& selection) const;
|
||||||
|
|
||||||
void render_selection_rectangle() const;
|
void render_selection_rectangle() const;
|
||||||
void render_points(const Selection& selection, bool picking = false) const;
|
void render_points(const Selection& selection, const Vec3d& direction_to_camera, bool picking = false) const;
|
||||||
|
void render_clipping_plane(const Selection& selection, const Vec3d& direction_to_camera) const;
|
||||||
bool is_mesh_update_necessary() const;
|
bool is_mesh_update_necessary() const;
|
||||||
void update_mesh();
|
void update_mesh();
|
||||||
void update_cache_entry_normal(unsigned int i) const;
|
void update_cache_entry_normal(unsigned int i) const;
|
||||||
|
@ -74,6 +77,8 @@ private:
|
||||||
float m_density = 100.f;
|
float m_density = 100.f;
|
||||||
mutable std::vector<CacheEntry> m_editing_mode_cache; // a support point and whether it is currently selected
|
mutable std::vector<CacheEntry> m_editing_mode_cache; // a support point and whether it is currently selected
|
||||||
float m_clipping_plane_distance = 0.f;
|
float m_clipping_plane_distance = 0.f;
|
||||||
|
mutable float m_old_clipping_plane_distance = 0.f;
|
||||||
|
mutable Vec3d m_old_direction_to_camera;
|
||||||
|
|
||||||
bool m_selection_rectangle_active = false;
|
bool m_selection_rectangle_active = false;
|
||||||
Vec2d m_selection_rectangle_start_corner;
|
Vec2d m_selection_rectangle_start_corner;
|
||||||
|
@ -85,6 +90,8 @@ private:
|
||||||
int m_canvas_width;
|
int m_canvas_width;
|
||||||
int m_canvas_height;
|
int m_canvas_height;
|
||||||
|
|
||||||
|
mutable std::unique_ptr<TriangleMeshSlicer> m_tms;
|
||||||
|
|
||||||
std::vector<const ConfigOption*> get_config_options(const std::vector<std::string>& keys) const;
|
std::vector<const ConfigOption*> get_config_options(const std::vector<std::string>& keys) const;
|
||||||
bool is_point_clipped(const Vec3d& point, const Vec3d& direction_to_camera, float z_shift) const;
|
bool is_point_clipped(const Vec3d& point, const Vec3d& direction_to_camera, float z_shift) const;
|
||||||
void find_intersecting_facets(const igl::AABB<Eigen::MatrixXf, 3>* aabb, const Vec3f& normal, double offset, std::vector<unsigned int>& out) const;
|
void find_intersecting_facets(const igl::AABB<Eigen::MatrixXf, 3>* aabb, const Vec3f& normal, double offset, std::vector<unsigned int>& out) const;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue