Public Types | Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes
cob_3d_mapping::Polygon Class Reference

Class representing Polygon shapes. More...

#include <polygon.h>

Inheritance diagram for cob_3d_mapping::Polygon:
Inheritance graph
[legend]

List of all members.

Public Types

typedef boost::shared_ptr
< const Polygon
ConstPtr
 Const. Polygon pointer.
typedef boost::shared_ptr
< Polygon
Ptr
 Polygon pointer.

Public Member Functions

void assignWeight ()
 Assign merge weight to Polygon.
double computeArea3d () const
 Computation of area of 2D polygon.
Eigen::Vector3f computeCentroid ()
 Computation of centroid of polygn.
Eigen::Vector3f computeCentroid (std::vector< std::vector< Eigen::Vector3f > > &contours_3d)
void computePose (std::vector< std::vector< Eigen::Vector3f > > &contours_3d)
float computeSimilarity (const Polygon::Ptr &poly) const
 Compute similarity of two polygons.
void debugOutput (std::string name)
 Computation of bounding box and pose of structure.
bool getContourOverlap (const Polygon::Ptr &poly, float &rel_overlap, int &abs_overlap) const
 Compute overlap of two Polygons.
std::vector< std::vector
< Eigen::Vector2f > > 
getContours2D ()
virtual std::vector
< std::vector< Eigen::Vector3f > > 
getContours3D ()
virtual void getMergeCandidates (const std::vector< Polygon::Ptr > &poly_vec, std::vector< int > &intersections) const
 Check for merge candidates.
bool hasSimilarParametersWith (const Polygon::Ptr &poly) const
 Check for similar polygon parameters.
virtual bool isIntersectedWith (const Polygon::Ptr &poly) const
 Check for intersection of two polygons.
virtual void merge (std::vector< Polygon::Ptr > &poly_vec)
 Merging of polygons.
void mergeDifference (Polygon::Ptr &p_merge)
size_t outerContourIndex () const
 Get index of first non-hole contour.
 Polygon ()
 Constructor for Polygon object.
 Polygon (unsigned int id, Eigen::Vector3f normal, Eigen::Vector3f centroid, std::vector< std::vector< Eigen::Vector3f > > &contours_3d, std::vector< bool > holes, std::vector< float > color)
 Get point on polygon.
 Polygon (unsigned int id, Eigen::Vector3f normal, Eigen::Vector3f centroid, std::vector< pcl::PointCloud< pcl::PointXYZ > > &contours_3d, std::vector< bool > holes, std::vector< float > color)
virtual void projectContour (const Polygon &p, std::vector< std::vector< Eigen::Vector2f > > &contours) const
void setContours2D (std::vector< std::vector< Eigen::Vector2f > > &contours_2d)
virtual void setContours3D (std::vector< std::vector< Eigen::Vector3f > > &contours_3d)
virtual void setParamsFrom (Polygon::Ptr &p)
void smoothContours ()
 Smooth contours of polygon.
virtual void transform (const Eigen::Affine3f &trafo)
 Transform polygon to target coordinate system.
virtual void triangulate (list< TPPLPoly > &tri_list) const
virtual void updateAttributes (const Eigen::Vector3f &new_normal, const Eigen::Vector3f &new_centroid)
 Compute attributes for Polygon.

Public Attributes

std::vector< std::vector
< Eigen::Vector2f > > 
contours_
double d_
std::vector< bool > holes_
MergeConfig merge_settings_
double merge_weight_
Eigen::Vector3f normal_

Protected Member Functions

void applyGpcStructure (const gpc_polygon *gpc_p)
 Conversion from GPC structure to polygon.
void assignID (const std::vector< Polygon::Ptr > &poly_vec)
 Assign ID to Polygon.
virtual void computeAverage (const std::vector< Polygon::Ptr > &poly_vec, Polygon::Ptr &p_average)
 Average polygon is calculated.
void getGpcStructure (gpc_polygon *gpc_p, const std::vector< std::vector< Eigen::Vector2f > > &contours) const
 Get 2D GPC structure from polygon.
void getIntersection (const Polygon::Ptr &poly, gpc_polygon *gpc_intersection) const
 Get intersection of two polygons.
void mergeUnion (std::vector< Polygon::Ptr > &poly_vec, Polygon::Ptr &p_average)
 Calculate merge union of Polygons.

Protected Attributes

DominantColor d_color_

Detailed Description

Class representing Polygon shapes.

Note:
Comparison and Merging of Polygons is handled.

Definition at line 120 of file polygon.h.


Member Typedef Documentation

typedef boost::shared_ptr<const Polygon> cob_3d_mapping::Polygon::ConstPtr

Const. Polygon pointer.

Const boost shared pointer to polygon.

Definition at line 131 of file polygon.h.

typedef boost::shared_ptr<Polygon> cob_3d_mapping::Polygon::Ptr

Polygon pointer.

Boost shared pointer to polygon.

Reimplemented from cob_3d_mapping::Shape.

Reimplemented in cob_3d_mapping::Cylinder.

Definition at line 126 of file polygon.h.


Constructor & Destructor Documentation

Constructor for Polygon object.

Definition at line 136 of file polygon.h.

cob_3d_mapping::Polygon::Polygon ( unsigned int  id,
Eigen::Vector3f  normal,
Eigen::Vector3f  centroid,
std::vector< std::vector< Eigen::Vector3f > > &  contours_3d,
std::vector< bool >  holes,
std::vector< float >  color 
)

Get point on polygon.

Point on polygon is calculated with distance d in normal direction.

Parameters:
normalNormal of the polygon
dParameter from plane equation ax+by+cz=d Get axes of coordinate system on plane.

Calculation of axes cartesian coordinate system using one given axis.

Parameters:
normalAxis coordinate system is oriented to.
vAxis orthogonal to normal
uAxis completing the Gaussian three-leg Copy GPC structure Smooth contours of GPC structure

Outline of GPC structure is smoothed using a path smoothing algorithm.

Parameters:
gpc_inInput GPC structure
gpc_outOutput GPC structure

Definition at line 178 of file polygon.cpp.

cob_3d_mapping::Polygon::Polygon ( unsigned int  id,
Eigen::Vector3f  normal,
Eigen::Vector3f  centroid,
std::vector< pcl::PointCloud< pcl::PointXYZ > > &  contours_3d,
std::vector< bool >  holes,
std::vector< float >  color 
)

Definition at line 201 of file polygon.cpp.


Member Function Documentation

void cob_3d_mapping::Polygon::applyGpcStructure ( const gpc_polygon gpc_p) [protected]

Conversion from GPC structure to polygon.

Transformation from 2D GPC structure to 3D polygon object using an external transformation.

Parameters:
[in]external_trafofrom 2D to 3D
[in]gpc_pInput GPC structure

Definition at line 717 of file polygon.cpp.

void cob_3d_mapping::Polygon::assignID ( const std::vector< Polygon::Ptr > &  poly_vec) [protected]

Assign ID to Polygon.

Lowest ID of input vector is assigned to Polygon.

Parameters:
[in]poly_vecVector with Polygon pointers.

Definition at line 617 of file polygon.cpp.

Assign merge weight to Polygon.

Assignment of merge weight to Polygon object depending on weighting method. The weighting method is determined from the merge_config parameters.

See also:
cob_3d_mapping::merge_config

Definition at line 603 of file polygon.cpp.

Computation of area of 2D polygon.

This method is only suitable for polygons with no expansion in z-direction. Computation of area of 3D polygon.

This method is suitable for all polygons.

Definition at line 835 of file polygon.cpp.

void cob_3d_mapping::Polygon::computeAverage ( const std::vector< Polygon::Ptr > &  poly_vec,
Polygon::Ptr p_average 
) [protected, virtual]

Average polygon is calculated.

Merge settings - configuring assignment of weight and merge processes Calculation of average polygon based on merge weights of individual polygons.

Parameters:
[in]poly_vecPolygons, that weighting is performed with
[out]p_averageResultant polygon.
See also:
cob_3d_mapping::merge_config
assignWeight()

Definition at line 628 of file polygon.cpp.

Computation of centroid of polygn.

Definition at line 772 of file polygon.cpp.

Eigen::Vector3f cob_3d_mapping::Polygon::computeCentroid ( std::vector< std::vector< Eigen::Vector3f > > &  contours_3d)

Definition at line 805 of file polygon.cpp.

void cob_3d_mapping::Polygon::computePose ( std::vector< std::vector< Eigen::Vector3f > > &  contours_3d)

Definition at line 760 of file polygon.cpp.

Compute similarity of two polygons.

Similarity of Polygons is computed based on parameters and overlap.

Parameters:
[in]polyPolygon, the similarity is calculated with.
Returns:
Similarity of polygons.

Definition at line 459 of file polygon.cpp.

void cob_3d_mapping::Polygon::debugOutput ( std::string  name)

Computation of bounding box and pose of structure.

Parameters:
[out]poseOrientation of bounding box, as an affine transformation matrix.
[out]min_ptMinimal boundary of bounding box.
[out]max_ptMaximal boundary of bounding box. Output of contour vertices to file.
[in]nameName of output file
Todo:
Change output path to value on individual system

Definition at line 881 of file polygon.cpp.

bool cob_3d_mapping::Polygon::getContourOverlap ( const Polygon::Ptr poly,
float &  rel_overlap,
int &  abs_overlap 
) const

Compute overlap of two Polygons.

Relative overlap and absolute overlap of two Polygons is computed.

Parameters:
[in]Polygon,theoverlap is computed with.
[out]Relativeoverlap of the polygons.
[out]Absoluteoverlap of the polygons.
Returns:
bool true if there is some overlap.

Definition at line 416 of file polygon.cpp.

std::vector<std::vector<Eigen::Vector2f> > cob_3d_mapping::Polygon::getContours2D ( ) [inline]

Definition at line 175 of file polygon.h.

std::vector< std::vector< Eigen::Vector3f > > cob_3d_mapping::Polygon::getContours3D ( ) [virtual]

Reimplemented in cob_3d_mapping::Cylinder.

Definition at line 260 of file polygon.cpp.

void cob_3d_mapping::Polygon::getGpcStructure ( gpc_polygon gpc_p,
const std::vector< std::vector< Eigen::Vector2f > > &  contours 
) const [protected]

Get 2D GPC structure from polygon.

Transformation from 3D to 2D is performed with given transformation.

Parameters:
[in]external_trafoAffine transformation.
[out]ResultantGPC structure.

Definition at line 691 of file polygon.cpp.

void cob_3d_mapping::Polygon::getIntersection ( const Polygon::Ptr poly,
gpc_polygon gpc_intersection 
) const [protected]

Get intersection of two polygons.

GPC methods are used to calculate the intersection.

Parameters:
[in]polyPolygon for calculation of intersection.
[out]gpc_intersectionGPC structure of the intersection of the Polygons.

Definition at line 393 of file polygon.cpp.

void cob_3d_mapping::Polygon::getMergeCandidates ( const std::vector< Polygon::Ptr > &  poly_vec,
std::vector< int > &  intersections 
) const [virtual]

Check for merge candidates.

Parameters:
[in]poly_vecVector of Polygons, that are checked.
[out]intersectionsVector with indices of merge candidates.

Definition at line 372 of file polygon.cpp.

bool cob_3d_mapping::Polygon::hasSimilarParametersWith ( const Polygon::Ptr poly) const [inline]

Check for similar polygon parameters.

Check is performed based on merge settings of Polygons.

Parameters:
[in]polyPolygon, whose parameters are compared to this Polygon.

Definition at line 283 of file polygon.h.

bool cob_3d_mapping::Polygon::isIntersectedWith ( const Polygon::Ptr poly) const [virtual]

Check for intersection of two polygons.

Parameters:
[in]polyPolygon, this Polygon is checked for intersections with.
Returns:
bool True if polygons are intersected.

Definition at line 382 of file polygon.cpp.

void cob_3d_mapping::Polygon::merge ( std::vector< Polygon::Ptr > &  poly_vec) [virtual]

Merging of polygons.

Complete merge process for this polygon with a vector of merge candidates. Merging is performed relative to an average Polygon.

Parameters:
[in]poly_vecVector with merge candidate Polygons

Definition at line 472 of file polygon.cpp.

Definition at line 484 of file polygon.cpp.

void cob_3d_mapping::Polygon::mergeUnion ( std::vector< Polygon::Ptr > &  poly_vec,
Polygon::Ptr p_average 
) [protected]

Calculate merge union of Polygons.

The union of contours and the resultant parameters are computed with respect to an average Polygon.Results are stored in Polygon object the method is called for.

Parameters:
[in]poly_vecVector of merge candidate Polygons.
[in]p_averagePolygon providing the resultant parameters.

Definition at line 506 of file polygon.cpp.

size_t cob_3d_mapping::Polygon::outerContourIndex ( ) const [inline]

Get index of first non-hole contour.

Returns:
Index of first non-hole contour.

Definition at line 164 of file polygon.h.

void cob_3d_mapping::Polygon::projectContour ( const Polygon p,
std::vector< std::vector< Eigen::Vector2f > > &  contours 
) const [virtual]

Definition at line 584 of file polygon.cpp.

void cob_3d_mapping::Polygon::setContours2D ( std::vector< std::vector< Eigen::Vector2f > > &  contours_2d) [inline]

Definition at line 174 of file polygon.h.

void cob_3d_mapping::Polygon::setContours3D ( std::vector< std::vector< Eigen::Vector3f > > &  contours_3d) [virtual]

Reimplemented in cob_3d_mapping::Cylinder.

Definition at line 237 of file polygon.cpp.

Reimplemented in cob_3d_mapping::Cylinder.

Definition at line 681 of file polygon.cpp.

Smooth contours of polygon.

Outline of polygon is smoothed.

See also:
smoothGpcStructure()

Definition at line 321 of file polygon.cpp.

void cob_3d_mapping::Polygon::transform ( const Eigen::Affine3f &  trafo) [virtual]

Transform polygon to target coordinate system.

Polygon is transformed with input transformation. Operation is applied to both parameters and contour points.

Parameters:
[in]trafoAffine transformation to target coordinate system

Implements cob_3d_mapping::Shape.

Definition at line 297 of file polygon.cpp.

void cob_3d_mapping::Polygon::triangulate ( list< TPPLPoly > &  tri_list) const [virtual]

Reimplemented in cob_3d_mapping::Cylinder.

Definition at line 852 of file polygon.cpp.

void cob_3d_mapping::Polygon::updateAttributes ( const Eigen::Vector3f &  new_normal,
const Eigen::Vector3f &  new_centroid 
) [virtual]

Compute attributes for Polygon.

Set of attributes is completed with respect to the input parameters.

Parameters:
[in]new_normalNormal of Polygon.
[in]new_centroidCentroid of Polygon.

Definition at line 278 of file polygon.cpp.


Member Data Documentation

std::vector<std::vector<Eigen::Vector2f> > cob_3d_mapping::Polygon::contours_

Contours of polygon structure.

Definition at line 349 of file polygon.h.

Definition at line 351 of file polygon.h.

Definition at line 415 of file polygon.h.

Bool vector indicating holes in polygon structure

Definition at line 353 of file polygon.h.

Definition at line 355 of file polygon.h.

Merge weight of polygon - regulating its influence in merge processes.

Definition at line 354 of file polygon.h.

Normal of polygons structure.

Definition at line 350 of file polygon.h.


The documentation for this class was generated from the following files:


cob_3d_mapping_common
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:02:19