Class representing Polygon shapes. More...
#include <polygon.h>
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_ |
Class representing Polygon shapes.
typedef boost::shared_ptr<const Polygon> cob_3d_mapping::Polygon::ConstPtr |
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.
cob_3d_mapping::Polygon::Polygon | ( | ) | [inline] |
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.
normal | Normal of the polygon |
d | Parameter from plane equation ax+by+cz=d Get axes of coordinate system on plane. |
Calculation of axes cartesian coordinate system using one given axis.
normal | Axis coordinate system is oriented to. |
v | Axis orthogonal to normal |
u | Axis completing the Gaussian three-leg Copy GPC structure Smooth contours of GPC structure |
Outline of GPC structure is smoothed using a path smoothing algorithm.
gpc_in | Input GPC structure |
gpc_out | Output 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.
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.
[in] | external_trafo | from 2D to 3D |
[in] | gpc_p | Input 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.
[in] | poly_vec | Vector 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.
Definition at line 603 of file polygon.cpp.
double cob_3d_mapping::Polygon::computeArea3d | ( | ) | const |
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.
[in] | poly_vec | Polygons, that weighting is performed with |
[out] | p_average | Resultant polygon. |
Definition at line 628 of file polygon.cpp.
Eigen::Vector3f cob_3d_mapping::Polygon::computeCentroid | ( | ) |
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.
float cob_3d_mapping::Polygon::computeSimilarity | ( | const Polygon::Ptr & | poly | ) | const |
Compute similarity of two polygons.
Similarity of Polygons is computed based on parameters and overlap.
[in] | poly | Polygon, the similarity is calculated with. |
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.
[out] | pose | Orientation of bounding box, as an affine transformation matrix. |
[out] | min_pt | Minimal boundary of bounding box. |
[out] | max_pt | Maximal boundary of bounding box. Output of contour vertices to file. |
[in] | name | Name of output file |
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.
[in] | Polygon,the | overlap is computed with. |
[out] | Relative | overlap of the polygons. |
[out] | Absolute | overlap of the polygons. |
Definition at line 416 of file polygon.cpp.
std::vector<std::vector<Eigen::Vector2f> > cob_3d_mapping::Polygon::getContours2D | ( | ) | [inline] |
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.
[in] | external_trafo | Affine transformation. |
[out] | Resultant | GPC 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.
[in] | poly | Polygon for calculation of intersection. |
[out] | gpc_intersection | GPC 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.
[in] | poly_vec | Vector of Polygons, that are checked. |
[out] | intersections | Vector 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] |
bool cob_3d_mapping::Polygon::isIntersectedWith | ( | const Polygon::Ptr & | poly | ) | const [virtual] |
Check for intersection of two polygons.
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.
[in] | poly_vec | Vector with merge candidate Polygons |
Definition at line 472 of file polygon.cpp.
void cob_3d_mapping::Polygon::mergeDifference | ( | Polygon::Ptr & | p_merge | ) |
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.
[in] | poly_vec | Vector of merge candidate Polygons. |
[in] | p_average | Polygon providing the resultant parameters. |
Definition at line 506 of file polygon.cpp.
size_t cob_3d_mapping::Polygon::outerContourIndex | ( | ) | const [inline] |
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] |
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.
void cob_3d_mapping::Polygon::setParamsFrom | ( | Polygon::Ptr & | p | ) | [virtual] |
Reimplemented in cob_3d_mapping::Cylinder.
Definition at line 681 of file polygon.cpp.
Smooth contours of polygon.
Outline of polygon is smoothed.
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.
[in] | trafo | Affine 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.
Definition at line 278 of file polygon.cpp.
std::vector<std::vector<Eigen::Vector2f> > cob_3d_mapping::Polygon::contours_ |
double cob_3d_mapping::Polygon::d_ |
DominantColor cob_3d_mapping::Polygon::d_color_ [protected] |
std::vector<bool> cob_3d_mapping::Polygon::holes_ |
Eigen::Vector3f cob_3d_mapping::Polygon::normal_ |