Merge branch 'master' of https://github.com/prusa3d/PrusaSlicer into et_world_coordinates
This commit is contained in:
commit
4b1e7f6d07
@ -128,13 +128,13 @@ void TriangleSelector::select_patch(const Vec3f& hit, int facet_start,
|
||||
const Vec3f& source, float radius,
|
||||
CursorType cursor_type, EnforcerBlockerType new_state,
|
||||
const Transform3d& trafo, const Transform3d& trafo_no_translate,
|
||||
bool triangle_splitting, float highlight_by_angle_deg)
|
||||
bool triangle_splitting, const ClippingPlane &clp, float highlight_by_angle_deg)
|
||||
{
|
||||
assert(facet_start < m_orig_size_indices);
|
||||
|
||||
// Save current cursor center, squared radius and camera direction, so we don't
|
||||
// have to pass it around.
|
||||
m_cursor = Cursor(hit, source, radius, cursor_type, trafo);
|
||||
m_cursor = Cursor(hit, source, radius, cursor_type, trafo, clp);
|
||||
|
||||
// In case user changed cursor size since last time, update triangle edge limit.
|
||||
// It is necessary to compare the internal radius in m_cursor! radius is in
|
||||
@ -172,15 +172,23 @@ void TriangleSelector::select_patch(const Vec3f& hit, int facet_start,
|
||||
}
|
||||
}
|
||||
|
||||
void TriangleSelector::seed_fill_select_triangles(const Vec3f &hit, int facet_start,
|
||||
const Transform3d& trafo_no_translate,
|
||||
float seed_fill_angle, float highlight_by_angle_deg,
|
||||
bool TriangleSelector::is_facet_clipped(int facet_idx, const ClippingPlane &clp) const
|
||||
{
|
||||
for (int vert_idx : m_triangles[facet_idx].verts_idxs)
|
||||
if (clp.is_active() && clp.is_mesh_point_clipped(m_vertices[vert_idx].v))
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void TriangleSelector::seed_fill_select_triangles(const Vec3f &hit, int facet_start, const Transform3d& trafo_no_translate,
|
||||
const ClippingPlane &clp, float seed_fill_angle, float highlight_by_angle_deg,
|
||||
bool force_reselection)
|
||||
{
|
||||
assert(facet_start < m_orig_size_indices);
|
||||
|
||||
// Recompute seed fill only if the cursor is pointing on facet unselected by seed fill.
|
||||
if (int start_facet_idx = select_unsplit_triangle(hit, facet_start); start_facet_idx >= 0 && m_triangles[start_facet_idx].is_selected_by_seed_fill() && !force_reselection)
|
||||
// Recompute seed fill only if the cursor is pointing on facet unselected by seed fill or a clipping plane is active.
|
||||
if (int start_facet_idx = select_unsplit_triangle(hit, facet_start); start_facet_idx >= 0 && m_triangles[start_facet_idx].is_selected_by_seed_fill() && !force_reselection && !clp.is_active())
|
||||
return;
|
||||
|
||||
this->seed_fill_unselect_all_triangles();
|
||||
@ -215,7 +223,7 @@ void TriangleSelector::seed_fill_select_triangles(const Vec3f &hit, int facet_st
|
||||
// Propagate over the original triangles.
|
||||
for (int neighbor_idx : m_neighbors[current_facet]) {
|
||||
assert(neighbor_idx >= -1);
|
||||
if (neighbor_idx >= 0 && !visited[neighbor_idx]) {
|
||||
if (neighbor_idx >= 0 && !visited[neighbor_idx] && !is_facet_clipped(neighbor_idx, clp)) {
|
||||
// Check if neighbour_facet_idx is satisfies angle in seed_fill_angle and append it to facet_queue if it do.
|
||||
const Vec3f &n1 = m_face_normals[m_triangles[neighbor_idx].source_triangle];
|
||||
const Vec3f &n2 = m_face_normals[m_triangles[current_facet].source_triangle];
|
||||
@ -331,12 +339,12 @@ void TriangleSelector::append_touching_edges(int itriangle, int vertexi, int ver
|
||||
process_subtriangle(touching.second, Partition::Second);
|
||||
}
|
||||
|
||||
void TriangleSelector::bucket_fill_select_triangles(const Vec3f& hit, int facet_start, bool propagate, bool force_reselection)
|
||||
void TriangleSelector::bucket_fill_select_triangles(const Vec3f& hit, int facet_start, const ClippingPlane &clp, bool propagate, bool force_reselection)
|
||||
{
|
||||
int start_facet_idx = select_unsplit_triangle(hit, facet_start);
|
||||
assert(start_facet_idx != -1);
|
||||
// Recompute bucket fill only if the cursor is pointing on facet unselected by bucket fill.
|
||||
if (start_facet_idx == -1 || (m_triangles[start_facet_idx].is_selected_by_seed_fill() && !force_reselection))
|
||||
// Recompute bucket fill only if the cursor is pointing on facet unselected by bucket fill or a clipping plane is active.
|
||||
if (start_facet_idx == -1 || (m_triangles[start_facet_idx].is_selected_by_seed_fill() && !force_reselection && !clp.is_active()))
|
||||
return;
|
||||
|
||||
assert(!m_triangles[start_facet_idx].is_split());
|
||||
@ -379,7 +387,7 @@ void TriangleSelector::bucket_fill_select_triangles(const Vec3f& hit, int facet_
|
||||
|
||||
std::vector<int> touching_triangles = get_all_touching_triangles(current_facet, neighbors[current_facet], neighbors_propagated[current_facet]);
|
||||
for(const int tr_idx : touching_triangles) {
|
||||
if (tr_idx < 0 || visited[tr_idx] || m_triangles[tr_idx].get_state() != start_facet_state)
|
||||
if (tr_idx < 0 || visited[tr_idx] || m_triangles[tr_idx].get_state() != start_facet_state || is_facet_clipped(tr_idx, clp))
|
||||
continue;
|
||||
|
||||
assert(!m_triangles[tr_idx].is_split());
|
||||
@ -1687,11 +1695,12 @@ void TriangleSelector::seed_fill_apply_on_triangles(EnforcerBlockerType new_stat
|
||||
|
||||
TriangleSelector::Cursor::Cursor(
|
||||
const Vec3f& center_, const Vec3f& source_, float radius_world,
|
||||
CursorType type_, const Transform3d& trafo_)
|
||||
CursorType type_, const Transform3d& trafo_, const ClippingPlane &clipping_plane_)
|
||||
: center{center_},
|
||||
source{source_},
|
||||
type{type_},
|
||||
trafo{trafo_.cast<float>()}
|
||||
trafo{trafo_.cast<float>()},
|
||||
clipping_plane(clipping_plane_)
|
||||
{
|
||||
Vec3d sf = Geometry::Transformation(trafo_).get_scaling_factor();
|
||||
if (is_approx(sf(0), sf(1)) && is_approx(sf(1), sf(2))) {
|
||||
@ -1714,22 +1723,19 @@ TriangleSelector::Cursor::Cursor(
|
||||
dir = (center - source).normalized();
|
||||
}
|
||||
|
||||
|
||||
// Is a point (in mesh coords) inside a cursor?
|
||||
bool TriangleSelector::Cursor::is_mesh_point_inside(Vec3f point) const
|
||||
bool TriangleSelector::Cursor::is_mesh_point_inside(const Vec3f &point) const
|
||||
{
|
||||
if (! uniform_scaling)
|
||||
point = trafo * point;
|
||||
const Vec3f transformed_point = uniform_scaling ? point : Vec3f(trafo * point);
|
||||
const Vec3f diff = center - transformed_point;
|
||||
const bool is_point_inside = (type == CIRCLE ? (diff - diff.dot(dir) * dir).squaredNorm() : diff.squaredNorm()) < radius_sqr;
|
||||
|
||||
Vec3f diff = center - point;
|
||||
return (type == CIRCLE ?
|
||||
(diff - diff.dot(dir) * dir).squaredNorm() :
|
||||
diff.squaredNorm())
|
||||
< radius_sqr;
|
||||
if (is_point_inside && clipping_plane.is_active())
|
||||
return !clipping_plane.is_mesh_point_clipped(point);
|
||||
|
||||
return is_point_inside;
|
||||
}
|
||||
|
||||
|
||||
|
||||
// p1, p2, p3 are in mesh coords!
|
||||
bool TriangleSelector::Cursor::is_pointer_in_triangle(const Vec3f& p1_,
|
||||
const Vec3f& p2_,
|
||||
|
@ -4,6 +4,7 @@
|
||||
// #define PRUSASLICER_TRIANGLE_SELECTOR_DEBUG
|
||||
|
||||
|
||||
#include <cfloat>
|
||||
#include "Point.hpp"
|
||||
#include "TriangleMesh.hpp"
|
||||
|
||||
@ -22,6 +23,18 @@ public:
|
||||
POINTER
|
||||
};
|
||||
|
||||
struct ClippingPlane
|
||||
{
|
||||
Vec3f normal;
|
||||
float offset;
|
||||
ClippingPlane() : normal{0.f, 0.f, 1.f}, offset{FLT_MAX} {};
|
||||
explicit ClippingPlane(const std::array<float, 4> &clp) : normal{clp[0], clp[1], clp[2]}, offset{clp[3]} {}
|
||||
|
||||
bool is_active() const { return offset != FLT_MAX; }
|
||||
|
||||
bool is_mesh_point_clipped(const Vec3f &point) const { return normal.dot(point) - offset > 0.f; }
|
||||
};
|
||||
|
||||
std::pair<std::vector<Vec3i>, std::vector<Vec3i>> precompute_all_neighbors() const;
|
||||
void precompute_all_neighbors_recursive(int facet_idx, const Vec3i &neighbors, const Vec3i &neighbors_propagated, std::vector<Vec3i> &neighbors_out, std::vector<Vec3i> &neighbors_normal_out) const;
|
||||
|
||||
@ -47,19 +60,22 @@ public:
|
||||
const Transform3d &trafo, // matrix to get from mesh to world
|
||||
const Transform3d &trafo_no_translate, // matrix to get from mesh to world without translation
|
||||
bool triangle_splitting, // If triangles will be split base on the cursor or not
|
||||
const ClippingPlane &clp, // Clipping plane to limit painting to not clipped facets only
|
||||
float highlight_by_angle_deg = 0.f); // The maximal angle of overhang. If it is set to a non-zero value, it is possible to paint only the triangles of overhang defined by this angle in degrees.
|
||||
|
||||
void seed_fill_select_triangles(const Vec3f &hit, // point where to start
|
||||
int facet_start, // facet of the original mesh (unsplit) that the hit point belongs to
|
||||
const Transform3d &trafo_no_translate, // matrix to get from mesh to world without translation
|
||||
float seed_fill_angle, // the maximal angle between two facets to be painted by the same color
|
||||
float highlight_by_angle_deg = 0.f, // The maximal angle of overhang. If it is set to a non-zero value, it is possible to paint only the triangles of overhang defined by this angle in degrees.
|
||||
bool force_reselection = false); // force reselection of the triangle mesh even in cases that mouse is pointing on the selected triangle
|
||||
void seed_fill_select_triangles(const Vec3f &hit, // point where to start
|
||||
int facet_start, // facet of the original mesh (unsplit) that the hit point belongs to
|
||||
const Transform3d &trafo_no_translate, // matrix to get from mesh to world without translation
|
||||
const ClippingPlane &clp, // Clipping plane to limit painting to not clipped facets only
|
||||
float seed_fill_angle, // the maximal angle between two facets to be painted by the same color
|
||||
float highlight_by_angle_deg = 0.f, // The maximal angle of overhang. If it is set to a non-zero value, it is possible to paint only the triangles of overhang defined by this angle in degrees.
|
||||
bool force_reselection = false); // force reselection of the triangle mesh even in cases that mouse is pointing on the selected triangle
|
||||
|
||||
void bucket_fill_select_triangles(const Vec3f &hit, // point where to start
|
||||
int facet_start, // facet of the original mesh (unsplit) that the hit point belongs to
|
||||
bool propagate, // if bucket fill is propagated to neighbor faces or if it fills the only facet of the modified mesh that the hit point belongs to.
|
||||
bool force_reselection = false); // force reselection of the triangle mesh even in cases that mouse is pointing on the selected triangle
|
||||
void bucket_fill_select_triangles(const Vec3f &hit, // point where to start
|
||||
int facet_start, // facet of the original mesh (unsplit) that the hit point belongs to
|
||||
const ClippingPlane &clp, // Clipping plane to limit painting to not clipped facets only
|
||||
bool propagate, // if bucket fill is propagated to neighbor faces or if it fills the only facet of the modified mesh that the hit point belongs to.
|
||||
bool force_reselection = false); // force reselection of the triangle mesh even in cases that mouse is pointing on the selected triangle
|
||||
|
||||
bool has_facets(EnforcerBlockerType state) const;
|
||||
static bool has_facets(const std::pair<std::vector<std::pair<int, int>>, std::vector<bool>> &data, EnforcerBlockerType test_state);
|
||||
@ -183,8 +199,8 @@ protected:
|
||||
struct Cursor {
|
||||
Cursor() = default;
|
||||
Cursor(const Vec3f& center_, const Vec3f& source_, float radius_world,
|
||||
CursorType type_, const Transform3d& trafo_);
|
||||
bool is_mesh_point_inside(Vec3f pt) const;
|
||||
CursorType type_, const Transform3d& trafo_, const ClippingPlane &clipping_plane_);
|
||||
bool is_mesh_point_inside(const Vec3f &pt) const;
|
||||
bool is_pointer_in_triangle(const Vec3f& p1, const Vec3f& p2, const Vec3f& p3) const;
|
||||
|
||||
Vec3f center;
|
||||
@ -195,6 +211,7 @@ protected:
|
||||
Transform3f trafo;
|
||||
Transform3f trafo_normal;
|
||||
bool uniform_scaling;
|
||||
ClippingPlane clipping_plane;
|
||||
};
|
||||
|
||||
Cursor m_cursor;
|
||||
@ -211,6 +228,7 @@ private:
|
||||
void remove_useless_children(int facet_idx); // No hidden meaning. Triangles are meant.
|
||||
bool is_pointer_in_triangle(int facet_idx) const;
|
||||
bool is_edge_inside_cursor(int facet_idx) const;
|
||||
bool is_facet_clipped(int facet_idx, const ClippingPlane &clp) const;
|
||||
int push_triangle(int a, int b, int c, int source_triangle, EnforcerBlockerType state = EnforcerBlockerType{0});
|
||||
void perform_split(int facet_idx, const Vec3i &neighbors, EnforcerBlockerType old_state);
|
||||
Vec3i child_neighbors(const Triangle &tr, const Vec3i &neighbors, int child_idx) const;
|
||||
|
@ -267,7 +267,8 @@ bool GLGizmoPainterBase::gizmo_event(SLAGizmoEventType action, const Vec2d& mous
|
||||
const ModelObject *mo = m_c->selection_info()->model_object();
|
||||
const ModelInstance *mi = mo->instances[selection.get_instance_idx()];
|
||||
const Transform3d trafo_matrix_not_translate = mi->get_transformation().get_matrix(true) * mo->volumes[m_rr.mesh_id]->get_matrix(true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, m_smart_fill_angle,
|
||||
const Transform3d trafo_matrix = mi->get_transformation().get_matrix() * mo->volumes[m_rr.mesh_id]->get_matrix();
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, this->get_clipping_plane_in_volume_coordinates(trafo_matrix), m_smart_fill_angle,
|
||||
m_paint_on_overhangs_only ? m_highlight_by_angle_threshold_deg : 0.f, true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->request_update_render_data();
|
||||
m_seed_fill_last_mesh_id = m_rr.mesh_id;
|
||||
@ -364,22 +365,22 @@ bool GLGizmoPainterBase::gizmo_event(SLAGizmoEventType action, const Vec2d& mous
|
||||
Vec3f camera_pos = (trafo_matrix.inverse() * camera.get_position()).cast<float>();
|
||||
|
||||
assert(m_rr.mesh_id < int(m_triangle_selectors.size()));
|
||||
const TriangleSelector::ClippingPlane &clp = this->get_clipping_plane_in_volume_coordinates(trafo_matrix);
|
||||
if (m_tool_type == ToolType::SMART_FILL || m_tool_type == ToolType::BUCKET_FILL || (m_tool_type == ToolType::BRUSH && m_cursor_type == TriangleSelector::CursorType::POINTER)) {
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_apply_on_triangles(new_state);
|
||||
if (m_tool_type == ToolType::SMART_FILL)
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, m_smart_fill_angle,
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, clp, m_smart_fill_angle,
|
||||
m_paint_on_overhangs_only ? m_highlight_by_angle_threshold_deg : 0.f, true);
|
||||
else if (m_tool_type == ToolType::BRUSH && m_cursor_type == TriangleSelector::CursorType::POINTER)
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), false, true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), clp, false, true);
|
||||
else if (m_tool_type == ToolType::BUCKET_FILL)
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), true, true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), clp, true, true);
|
||||
|
||||
m_seed_fill_last_mesh_id = -1;
|
||||
} else if (m_tool_type == ToolType::BRUSH)
|
||||
m_triangle_selectors[m_rr.mesh_id]->select_patch(m_rr.hit, int(m_rr.facet), camera_pos, m_cursor_radius, m_cursor_type,
|
||||
new_state, trafo_matrix, trafo_matrix_not_translate, m_triangle_splitting_enabled,
|
||||
new_state, trafo_matrix, trafo_matrix_not_translate, m_triangle_splitting_enabled, clp,
|
||||
m_paint_on_overhangs_only ? m_highlight_by_angle_threshold_deg : 0.f);
|
||||
|
||||
m_triangle_selectors[m_rr.mesh_id]->request_update_render_data();
|
||||
m_last_mouse_click = mouse_position;
|
||||
}
|
||||
@ -430,16 +431,18 @@ bool GLGizmoPainterBase::gizmo_event(SLAGizmoEventType action, const Vec2d& mous
|
||||
if(m_rr.mesh_id != m_seed_fill_last_mesh_id)
|
||||
seed_fill_unselect_all();
|
||||
|
||||
const Transform3d &trafo_matrix = trafo_matrices[m_rr.mesh_id];
|
||||
const Transform3d &trafo_matrix_not_translate = trafo_matrices_not_translate[m_rr.mesh_id];
|
||||
|
||||
assert(m_rr.mesh_id < int(m_triangle_selectors.size()));
|
||||
const TriangleSelector::ClippingPlane &clp = this->get_clipping_plane_in_volume_coordinates(trafo_matrix);
|
||||
if (m_tool_type == ToolType::SMART_FILL)
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, m_smart_fill_angle,
|
||||
m_triangle_selectors[m_rr.mesh_id]->seed_fill_select_triangles(m_rr.hit, int(m_rr.facet), trafo_matrix_not_translate, clp, m_smart_fill_angle,
|
||||
m_paint_on_overhangs_only ? m_highlight_by_angle_threshold_deg : 0.f);
|
||||
else if (m_tool_type == ToolType::BRUSH && m_cursor_type == TriangleSelector::CursorType::POINTER)
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), false);
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), clp, false);
|
||||
else if (m_tool_type == ToolType::BUCKET_FILL)
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->bucket_fill_select_triangles(m_rr.hit, int(m_rr.facet), clp, true);
|
||||
m_triangle_selectors[m_rr.mesh_id]->request_update_render_data();
|
||||
m_seed_fill_last_mesh_id = m_rr.mesh_id;
|
||||
return true;
|
||||
@ -569,6 +572,25 @@ void GLGizmoPainterBase::on_load(cereal::BinaryInputArchive&)
|
||||
m_schedule_update = true;
|
||||
}
|
||||
|
||||
TriangleSelector::ClippingPlane GLGizmoPainterBase::get_clipping_plane_in_volume_coordinates(const Transform3d &trafo) const {
|
||||
const ::Slic3r::GUI::ClippingPlane *const clipping_plane = m_c->object_clipper()->get_clipping_plane();
|
||||
if (clipping_plane == nullptr || !clipping_plane->is_active())
|
||||
return {};
|
||||
|
||||
const Vec3d clp_normal = clipping_plane->get_normal();
|
||||
const double clp_offset = clipping_plane->get_offset();
|
||||
|
||||
const Transform3d trafo_normal = Transform3d(trafo.linear().transpose());
|
||||
const Transform3d trafo_inv = trafo.inverse();
|
||||
|
||||
Vec3d point_on_plane = clp_normal * clp_offset;
|
||||
Vec3d point_on_plane_transformed = trafo_inv * point_on_plane;
|
||||
Vec3d normal_transformed = trafo_normal * clp_normal;
|
||||
auto offset_transformed = float(point_on_plane_transformed.dot(normal_transformed));
|
||||
|
||||
return TriangleSelector::ClippingPlane({float(normal_transformed.x()), float(normal_transformed.y()), float(normal_transformed.z()), offset_transformed});
|
||||
}
|
||||
|
||||
std::array<float, 4> TriangleSelectorGUI::get_seed_fill_color(const std::array<float, 4> &base_color)
|
||||
{
|
||||
return {base_color[0] * 0.75f, base_color[1] * 0.75f, base_color[2] * 0.75f, 1.f};
|
||||
|
@ -184,6 +184,8 @@ protected:
|
||||
|
||||
ClippingPlaneDataWrapper get_clipping_plane_data() const;
|
||||
|
||||
TriangleSelector::ClippingPlane get_clipping_plane_in_volume_coordinates(const Transform3d &trafo) const;
|
||||
|
||||
private:
|
||||
bool is_mesh_point_clipped(const Vec3d& point, const Transform3d& trafo) const;
|
||||
void update_raycast_cache(const Vec2d& mouse_position,
|
||||
|
@ -732,6 +732,10 @@ bool GLGizmosManager::on_mouse(wxMouseEvent& evt)
|
||||
}
|
||||
else if (evt.LeftUp() && m_current == Flatten && m_gizmos[m_current]->get_hover_id() != -1) {
|
||||
// to avoid to loose the selection when user clicks an the white faces of a different object while the Flatten gizmo is active
|
||||
#if ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
|
||||
selection.stop_dragging();
|
||||
wxGetApp().obj_manipul()->set_dirty();
|
||||
#endif // ENABLE_OUT_OF_BED_DETECTION_IMPROVEMENTS
|
||||
processed = true;
|
||||
}
|
||||
else if (evt.RightUp() && (m_current == FdmSupports || m_current == Seam || m_current == MmuSegmentation) && !m_parent.is_mouse_dragging()) {
|
||||
|
@ -53,6 +53,7 @@ public:
|
||||
m_data[2] = norm_dir.z();
|
||||
}
|
||||
void set_offset(double offset) { m_data[3] = offset; }
|
||||
double get_offset() const { return m_data[3]; }
|
||||
Vec3d get_normal() const { return Vec3d(m_data[0], m_data[1], m_data[2]); }
|
||||
bool is_active() const { return m_data[3] != DBL_MAX; }
|
||||
static ClippingPlane ClipsNothing() { return ClippingPlane(Vec3d(0., 0., 1.), DBL_MAX); }
|
||||
|
Loading…
Reference in New Issue
Block a user