$search
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 | applyGpcStructure (const Eigen::Affine3f &external_trafo, const gpc_polygon *gpc_p) |
Conversion from GPC structure to polygon. | |
virtual void | applyWeighting (const std::vector< Polygon::Ptr > &poly_vec, Polygon::Ptr &p_average) |
Average polygon is calculated. | |
void | assignID (const std::vector< Polygon::Ptr > &poly_vec) |
Assign ID to Polygon. | |
void | assignWeight () |
Assign merge weight to Polygon. | |
double | computeArea () const |
Computation of area of 2D polygon. | |
double | computeArea3d () const |
Computation of area of 3D polygon. | |
virtual void | computeAttributes (const Eigen::Vector3f &new_normal, const Eigen::Vector4f &new_centroid) |
Compute attributes for Polygon. | |
void | computeCentroid () |
Computation of centroid of polygn. | |
void | computePoseAndBoundingBox (Eigen::Affine3f &pose, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt) |
Computation of bounding box and pose of structure. | |
float | computeSimilarity (const Polygon::Ptr &poly) const |
Compute similarity of two polygons. | |
void | debug_output (std::string name) |
Output of contour vertices to file. | |
bool | getContourOverlap (const Polygon::Ptr &poly, float &rel_overlap, int &abs_overlap) const |
Compute overlap of two Polygons. | |
void | getGpcStructure (const Eigen::Affine3f &external_trafo, gpc_polygon *gpc_p) const |
Get 2D GPC structure from polygon. | |
void | getIntersection (const Polygon::Ptr &poly, gpc_polygon *gpc_intersection) const |
Get intersection of two polygons. | |
virtual void | getMergeCandidates (const std::vector< Polygon::Ptr > &poly_vec, std::vector< int > &intersections) const |
Check for merge candidates. | |
void | getTransformationFromPlaneToWorld (const Eigen::Vector3f z_axis, const Eigen::Vector3f &normal, const Eigen::Vector3f &origin, Eigen::Affine3f &transformation) |
compute Transformation from world coordinate system to coordinate system on polygon plane. | |
void | getTransformationFromPlaneToWorld (const Eigen::Vector3f &normal, const Eigen::Vector3f &origin, Eigen::Affine3f &transformation) const |
compute Transformation from world coordinate system to coordinate system on polygon plane. | |
void | getTransformedContours (const Eigen::Affine3f &trafo, std::vector< std::vector< Eigen::Vector3f > > &new_contours) const |
Transform polygon contours with given transformation and return copy. | |
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 | merge_union (std::vector< Polygon::Ptr > &poly_vec, Polygon::Ptr &p_average) |
Calculate merge union of Polygons. | |
size_t | outerContourIndex () const |
Get index of first non-hole conour. | |
Polygon () | |
Constructor for Polygon object. | |
void | smoothPolygon () |
Smooth contours of polygon. | |
virtual void | transform2tf (const Eigen::Affine3f &trafo) |
Transform polygon to target coordinate system. | |
void | TransformContours (const Eigen::Affine3f &trafo) |
Transform polygon contours with given transformation. | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::vector< std::vector < Eigen::Vector3f > > | contours |
double | d |
std::vector< bool > | holes |
merge_config | merge_settings_ |
double | merge_weight_ |
Eigen::Vector3f | normal |
Eigen::Affine3f | transform_from_world_to_plane |
Class representing Polygon shapes.
Definition at line 108 of file polygon.h.
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] |
void cob_3d_mapping::Polygon::applyGpcStructure | ( | const Eigen::Affine3f & | external_trafo, | |
const gpc_polygon * | gpc_p | |||
) |
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 471 of file polygon.cpp.
void cob_3d_mapping::Polygon::applyWeighting | ( | const std::vector< Polygon::Ptr > & | poly_vec, | |
Polygon::Ptr & | p_average | |||
) | [virtual] |
Average polygon is calculated.
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 402 of file polygon.cpp.
void cob_3d_mapping::Polygon::assignID | ( | const std::vector< Polygon::Ptr > & | poly_vec | ) |
Assign ID to Polygon.
Lowest ID of input vector is assigned to Polygon.
[in] | poly_vec | Vector with Polygon pointers. |
Definition at line 391 of file polygon.cpp.
void cob_3d_mapping::Polygon::assignWeight | ( | ) |
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 377 of file polygon.cpp.
double cob_3d_mapping::Polygon::computeArea | ( | ) | const |
Computation of area of 2D polygon.
This method is only suitable for polygons with no expansion in z-direction.
Definition at line 533 of file polygon.cpp.
double cob_3d_mapping::Polygon::computeArea3d | ( | ) | const |
Computation of area of 3D polygon.
This method is suitable for all polygons.
Definition at line 567 of file polygon.cpp.
void cob_3d_mapping::Polygon::computeAttributes | ( | const Eigen::Vector3f & | new_normal, | |
const Eigen::Vector4f & | new_centroid | |||
) | [virtual] |
Compute attributes for Polygon.
Set of attributes is completed with respect to the input paramers.
Definition at line 208 of file polygon.cpp.
void cob_3d_mapping::Polygon::computeCentroid | ( | ) |
Computation of centroid of polygn.
Definition at line 503 of file polygon.cpp.
void cob_3d_mapping::Polygon::computePoseAndBoundingBox | ( | Eigen::Affine3f & | pose, | |
Eigen::Vector4f & | min_pt, | |||
Eigen::Vector4f & | max_pt | |||
) |
Computation of bounding box and pose of structure.
[out] | pose | Orientation of bounding box, as an affine transformation matrix. |
[out] | min_pt | Mininmal boundary of bounding box. |
[out] | max_pt | Maximal boundary of bounding box. |
Definition at line 641 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 323 of file polygon.cpp.
void cob_3d_mapping::Polygon::debug_output | ( | std::string | name | ) |
Output of contour vertices to file.
[in] | name | Name of output file |
Definition at line 667 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 282 of file polygon.cpp.
void cob_3d_mapping::Polygon::getGpcStructure | ( | const Eigen::Affine3f & | external_trafo, | |
gpc_polygon * | gpc_p | |||
) | const |
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 445 of file polygon.cpp.
void cob_3d_mapping::Polygon::getIntersection | ( | const Polygon::Ptr & | poly, | |
gpc_polygon * | gpc_intersection | |||
) | const |
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 270 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 250 of file polygon.cpp.
void cob_3d_mapping::Polygon::getTransformationFromPlaneToWorld | ( | const Eigen::Vector3f | z_axis, | |
const Eigen::Vector3f & | normal, | |||
const Eigen::Vector3f & | origin, | |||
Eigen::Affine3f & | transformation | |||
) |
compute Transformation from world coordinate system to coordinate system on polygon plane.
[in] | z_axis | Z-Axis of the coordinate system on the plane. |
[in] | origin | Origin of coordinate system on plane. |
[out] | transformation | The resultant transformation. |
Definition at line 602 of file polygon.cpp.
void cob_3d_mapping::Polygon::getTransformationFromPlaneToWorld | ( | const Eigen::Vector3f & | normal, | |
const Eigen::Vector3f & | origin, | |||
Eigen::Affine3f & | transformation | |||
) | const |
compute Transformation from world coordinate system to coordinate system on polygon plane.
[in] | normal | Normal of plane, serves as one axis. |
[in] | origin | Origin of coordinate system on plane. |
[out] | transformation | The resultant transformation. |
Definition at line 590 of file polygon.cpp.
void cob_3d_mapping::Polygon::getTransformedContours | ( | const Eigen::Affine3f & | trafo, | |
std::vector< std::vector< Eigen::Vector3f > > & | new_contours | |||
) | const |
Transform polygon contours with given transformation and return copy.
[in] | trafo | Transformation, which is applied. |
[out] | new_contours | Transformed copy of the contours of this Polygon. |
Definition at line 627 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 259 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 336 of file polygon.cpp.
void cob_3d_mapping::Polygon::merge_union | ( | std::vector< Polygon::Ptr > & | poly_vec, | |
Polygon::Ptr & | p_average | |||
) |
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 346 of file polygon.cpp.
size_t cob_3d_mapping::Polygon::outerContourIndex | ( | ) | const [inline] |
void cob_3d_mapping::Polygon::smoothPolygon | ( | ) |
Smooth contours of polygon.
Outline of polygon is smoothed.
Definition at line 235 of file polygon.cpp.
void cob_3d_mapping::Polygon::transform2tf | ( | 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 219 of file polygon.cpp.
void cob_3d_mapping::Polygon::TransformContours | ( | const Eigen::Affine3f & | trafo | ) |
Transform polygon contours with given transformation.
[in] | trafo | Transforamtion, that is applied to the conoturs of this Polygon. |
Definition at line 614 of file polygon.cpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::vector<std::vector<Eigen::Vector3f> > cob_3d_mapping::Polygon::contours |
double cob_3d_mapping::Polygon::d |
std::vector<bool> cob_3d_mapping::Polygon::holes |
Eigen::Vector3f cob_3d_mapping::Polygon::normal |
Eigen::Affine3f cob_3d_mapping::Polygon::transform_from_world_to_plane |