37 #include <pcl/surface/ear_clipping.h> 38 #include <pcl/conversions.h> 39 #include <pcl/pcl_config.h> 45 points_.reset (
new pcl::PointCloud<pcl::PointXYZ>);
47 if (!MeshProcessing::initCompute ())
49 fromPCLPointCloud2 (input_mesh_->cloud, *
points_);
58 output.polygons.clear ();
59 output.cloud = input_mesh_->cloud;
60 for (
int i = 0; i < static_cast<int> (input_mesh_->polygons.size ()); ++i)
68 const size_t n_vertices = vertices.vertices.size ();
72 else if (n_vertices == 3)
74 output.polygons.push_back( vertices );
78 std::vector<uint32_t> remaining_vertices = vertices.vertices;
84 if (remaining_vertices.size() < 3)
return;
86 output.polygons.erase(output.polygons.end(), output.polygons.end() + count);
87 remaining_vertices.resize(n_vertices);
88 for (
size_t v = 0; v < n_vertices; v++)
89 remaining_vertices[v] = vertices.vertices[n_vertices - 1 - v];
101 if (vertices.front () == vertices.back ())
102 vertices.erase (vertices.end () - 1);
105 for (
int u = static_cast<int> (vertices.size ()) - 1, null_iterations = 0;
106 vertices.size () > 2 && null_iterations < static_cast<int >(vertices.size () * 2);
107 ++null_iterations, u = (u+1) % static_cast<int> (vertices.size ()))
109 int v = (u + 1) % static_cast<int> (vertices.size ());
110 int w = (u + 2) % static_cast<int> (vertices.size ());
112 if (vertices.size() == 3 ||
isEar (u, v, w, vertices))
115 triangle.vertices.resize (3);
116 triangle.vertices[0] = vertices[u];
117 triangle.vertices[1] = vertices[v];
118 triangle.vertices[2] = vertices[w];
119 output.polygons.push_back (triangle);
120 vertices.erase (vertices.begin () + v);
132 Eigen::Vector3f p_u, p_v, p_w;
133 p_u =
points_->points[vertices[u]].getVector3fMap();
134 p_v =
points_->points[vertices[v]].getVector3fMap();
135 p_w =
points_->points[vertices[w]].getVector3fMap();
137 const float eps = 1e-15
f;
138 Eigen::Vector3f p_vu, p_vw;
143 Eigen::Vector3f
cross = p_vu.cross(p_vw);
144 if ((cross[2] > 0) || (cross.norm() < eps))
149 for (
int k = 0; k < static_cast<int> (vertices.size ()); k++)
151 if ((k == u) || (k == v) || (k == w))
153 p =
points_->points[vertices[k]].getVector3fMap();
162 Eigen::Vector3f p_i0, p_i1;
163 Eigen::Vector3f p_mid_uw = (p_u + p_w) / 2.0;
165 Eigen::Vector3f p_inf = p_mid_uw + (p_v - p_mid_uw) * 1e15f + p_vu * 1e10f;
166 int intersect_count = 0;
167 for (
int i = 0; i < static_cast<int>(vertices.size()); i++)
169 p_i0 =
points_->points[vertices[i]].getVector3fMap();
170 p_i1 =
points_->points[vertices[(i + 1) % static_cast<int>(vertices.size())]].getVector3fMap();
171 if (
intersect(p_mid_uw, p_inf, p_i0, p_i1))
174 if (intersect_count % 2 == 0)
183 const Eigen::Vector3f& v,
184 const Eigen::Vector3f& w,
185 const Eigen::Vector3f& p)
189 Eigen::Vector3f v0 = w - u;
190 Eigen::Vector3f v1 = v - u;
191 Eigen::Vector3f v2 = p - u;
194 float dot00 = v0.dot(v0);
195 float dot01 = v0.dot(v1);
196 float dot02 = v0.dot(v2);
197 float dot11 = v1.dot(v1);
198 float dot12 = v1.dot(v2);
201 float invDenom = 1 / (dot00 * dot11 - dot01 * dot01);
202 float a = (dot11 * dot02 - dot01 * dot12) * invDenom;
203 float b = (dot00 * dot12 - dot01 * dot02) * invDenom;
206 return (a >= 0) && (b >= 0) && (a + b < 1);
212 const Eigen::Vector3f& p1,
213 const Eigen::Vector3f& p2,
214 const Eigen::Vector3f& p3)
217 Eigen::Vector3f a = p1 - p0;
218 Eigen::Vector3f b = p3 - p2;
219 Eigen::Vector3f c = p2 - p0;
222 if (a.cross(b).norm() == 0)
226 float s = (c.cross(b)).
dot(a.cross(b)) / ((a.cross(b)).norm() * (a.cross(b)).norm());
227 float t = (c.cross(a)).
dot(a.cross(b)) / ((a.cross(b)).norm() * (a.cross(b)).norm());
230 return ((s >= 0 && s <= 1) && (t >= 0 && t <= 1));
bool isInsideTriangle(const Eigen::Vector3f &u, const Eigen::Vector3f &v, const Eigen::Vector3f &w, const Eigen::Vector3f &p)
Check if p is inside the triangle (u,v,w).
TFSIMD_FORCE_INLINE Vector3 cross(const Vector3 &v) const
bool initCompute()
This method should get called before starting the actual computation.
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
size_t triangulateClockwiseVertices(std::vector< uint32_t > &vertices, PolygonMesh &output)
Triangulate one polygon, assume the vertices are clockwise.
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
a Pointer to the point cloud data.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices
void triangulate(const Vertices &vertices, PolygonMesh &output)
Triangulate one polygon.
bool isEar(int u, int v, int w, const std::vector< uint32_t > &vertices)
Check if the triangle (u,v,w) is an ear.
void performProcessing(pcl::PolygonMesh &output)
The actual surface reconstruction method.
bool intersect(const Eigen::Vector3f &p0, const Eigen::Vector3f &p1, const Eigen::Vector3f &p2, const Eigen::Vector3f &p3)
Check if two line segments intersect by themselves.