#include <plane.h>
Public Types | |
typedef std::vector < cob_3d_mapping_msgs::Shape, Eigen::aligned_allocator < cob_3d_mapping_msgs::Shape > > | tShapeMarker |
typedef std::vector < pcl::Vertices > | tVertices |
Public Member Functions | |
visualization_msgs::Marker | AddPlanePoints (pcl::PointCloud< pcl::PointXYZ >::Ptr plane_cloud, int max_poly_size) |
std::list< TPPLPoly > & | getMesh () |
visualization_msgs::Marker & | getMeshMarker () |
ClipperLib::ExPolygons & | getPolygons () |
tShapeMarker & | getShapeMarker () |
visualization_msgs::Marker | NewPlanePoints (pcl::PointCloud< pcl::PointXYZ >::Ptr plane_cloud) |
PlaneExt (but_plane_detector::Plane< float > plane) | |
void | setColor (std_msgs::ColorRGBA &new_color) |
void | setPolygons (ClipperLib::ExPolygons &polys) |
void | TriangulatePlanePolygon () |
Public Attributes | |
std_msgs::ColorRGBA | color |
Protected Member Functions | |
tVertices | ComputeConcaveHull (pcl::PointCloud< pcl::PointXYZ >::Ptr &plane_cloud, pcl::PointCloud< pcl::PointXYZ >::Ptr &plane_hull) |
bool | ConcaveHullJoinCurrent (pcl::PointCloud< pcl::PointXYZ >::Ptr &plane_hull, tVertices &polygon_indices, int max_poly_size) |
void | ConcaveHullRewrite (pcl::PointCloud< pcl::PointXYZ >::Ptr &plane_hull, tVertices &polygon_indices) |
ClipperLib::ExPolygons | PolygonizeConcaveHull (pcl::PointCloud< pcl::PointXYZ >::Ptr &plane_hull, tVertices &polygon_indices) |
Protected Attributes | |
pcl::ModelCoefficients::Ptr | planeCoefficients |
ClipperLib::ExPolygons | planePolygonsClipper |
double | planeShift |
Eigen::Affine3f | planeTransXY |
visualization_msgs::Marker | planeTriangles |
tShapeMarker | planeTrianglesSRS |
Eigen::Quaternion< float > | rotationQuaternion |
Static Protected Attributes | |
static const int | MAX_POLYS = 1000 |
typedef std::vector<cob_3d_mapping_msgs::Shape, Eigen::aligned_allocator<cob_3d_mapping_msgs::Shape> > srs_env_model_percp::PlaneExt::tShapeMarker |
srs_env_model_percp::PlaneExt::PlaneExt | ( | but_plane_detector::Plane< float > | plane | ) |
visualization_msgs::Marker srs_env_model_percp::PlaneExt::AddPlanePoints | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | plane_cloud, |
int | max_poly_size | ||
) |
PlaneExt::tVertices srs_env_model_percp::PlaneExt::ComputeConcaveHull | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | plane_cloud, |
pcl::PointCloud< pcl::PointXYZ >::Ptr & | plane_hull | ||
) | [protected] |
bool srs_env_model_percp::PlaneExt::ConcaveHullJoinCurrent | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | plane_hull, |
tVertices & | polygon_indices, | ||
int | max_poly_size | ||
) | [protected] |
void srs_env_model_percp::PlaneExt::ConcaveHullRewrite | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | plane_hull, |
tVertices & | polygon_indices | ||
) | [protected] |
Get Mesh structure
visualization_msgs::Marker & srs_env_model_percp::PlaneExt::getMeshMarker | ( | ) |
visualization_msgs::Marker srs_env_model_percp::PlaneExt::NewPlanePoints | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr | plane_cloud | ) |
ClipperLib::ExPolygons srs_env_model_percp::PlaneExt::PolygonizeConcaveHull | ( | pcl::PointCloud< pcl::PointXYZ >::Ptr & | plane_hull, |
tVertices & | polygon_indices | ||
) | [protected] |
void srs_env_model_percp::PlaneExt::setColor | ( | std_msgs::ColorRGBA & | new_color | ) |
void srs_env_model_percp::PlaneExt::setPolygons | ( | ClipperLib::ExPolygons & | polys | ) |
std_msgs::ColorRGBA srs_env_model_percp::PlaneExt::color |
const int srs_env_model_percp::PlaneExt::MAX_POLYS = 1000 [static, protected] |
double srs_env_model_percp::PlaneExt::planeShift [protected] |
Eigen::Affine3f srs_env_model_percp::PlaneExt::planeTransXY [protected] |
visualization_msgs::Marker srs_env_model_percp::PlaneExt::planeTriangles [protected] |
Eigen::Quaternion<float> srs_env_model_percp::PlaneExt::rotationQuaternion [protected] |