36 #ifndef JSK_PCL_ROS_EAR_CLIPPING_PATCHED_H_ 37 #define JSK_PCL_ROS_EAR_CLIPPING_PATCHED_H_ 39 #include <pcl/point_types.h> 40 #include <pcl/surface/processing.h> 57 using MeshProcessing::input_mesh_;
58 using MeshProcessing::initCompute;
66 pcl::PointCloud<pcl::PointXYZ>::Ptr
points_;
76 performProcessing (pcl::PolygonMesh &output);
83 triangulate (
const Vertices& vertices, PolygonMesh& output);
90 triangulateClockwiseVertices (std::vector<uint32_t>& vertices, PolygonMesh& output);
99 isEar (
int u,
int v,
int w,
const std::vector<uint32_t>& vertices);
108 isInsideTriangle (
const Eigen::Vector3f& u,
109 const Eigen::Vector3f& v,
110 const Eigen::Vector3f& w,
111 const Eigen::Vector3f& p);
118 crossProduct (
const Eigen::Vector2f& p1,
const Eigen::Vector2f& p2)
const 120 return p1[0]*p2[1] - p1[1]*p2[0];
130 intersect (
const Eigen::Vector3f& p0,
131 const Eigen::Vector3f& p1,
132 const Eigen::Vector3f& p2,
133 const Eigen::Vector3f& p3);
EarClippingPatched()
Empty constructor.
boost::shared_ptr< const EarClippingPatched > ConstPtr
The ear clipping triangulation algorithm. The code is inspired by Flavien Brebion implementation...
boost::shared_ptr< EarClippingPatched > Ptr
pcl::PointCloud< pcl::PointXYZ >::Ptr points_
a Pointer to the point cloud data.
float crossProduct(const Eigen::Vector2f &p1, const Eigen::Vector2f &p2) const
Compute the cross product between 2D vectors.
std::vector< Eigen::Vector3f, Eigen::aligned_allocator< Eigen::Vector3f > > Vertices