$search

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 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

Detailed Description

Class representing Polygon shapes.

Note:
Comparison and Merging of Polygons is handled.

Definition at line 108 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 119 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 114 of file polygon.h.


Constructor & Destructor Documentation

cob_3d_mapping::Polygon::Polygon (  )  [inline]

Constructor for Polygon object.

Definition at line 125 of file polygon.h.


Member Function Documentation

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.

Parameters:
[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.

Parameters:
[in] poly_vec Polygons, that weighting is performed with
[out] p_average Resultant polygon.
See also:
cob_3d_mapping::merge_config
assignWeight()

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.

Parameters:
[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.

See also:
cob_3d_mapping::merge_config

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.

Parameters:
[in] new_normal Normal of Polygon.
[in] new_centroid Centroid of Polygon.

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.

Parameters:
[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.

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

Definition at line 323 of file polygon.cpp.

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

Output of contour vertices to file.

Parameters:
[in] name Name of output file
Todo:
Change output path to value on individual system

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.

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

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.

Parameters:
[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.

Parameters:
[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.

Parameters:
[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.

Note:
The coordinate system on the plane is determined by the orgin and the Z-axis. The other axes are calculated arbitrarily.
Parameters:
[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.

Note:
The coordinate system on the plane is determined by the orgin and the normal, which serves as one axis. The other axes are calculated arbitrarily.
Parameters:
[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.

Parameters:
[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]

Check for similar polygon parameters.

Check is performed based on merge settings of Polygons.

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

Definition at line 302 of file polygon.h.

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

Check for intersection of two polygons.

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

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.

Parameters:
[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.

Parameters:
[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]

Get index of first non-hole conour.

Returns:
Index of first non-hole contour.

Definition at line 137 of file polygon.h.

void cob_3d_mapping::Polygon::smoothPolygon (  ) 

Smooth contours of polygon.

Outline of polygon is smoothed.

See also:
smoothGpcStructure()

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.

Parameters:
[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.

Parameters:
[in] trafo Transforamtion, that is applied to the conoturs of this Polygon.

Definition at line 614 of file polygon.cpp.


Member Data Documentation

EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::vector<std::vector<Eigen::Vector3f> > cob_3d_mapping::Polygon::contours

Contours of polygon sturcure.

Definition at line 400 of file polygon.h.

Definition at line 402 of file polygon.h.

std::vector<bool> cob_3d_mapping::Polygon::holes

Bool vector indicating holes in polygon structure

Definition at line 404 of file polygon.h.

Definition at line 406 of file polygon.h.

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

Definition at line 405 of file polygon.h.

Normal of polygons structure.

Definition at line 401 of file polygon.h.

Transformation from world coordinate system to cvoordinate system on polygon.

Definition at line 403 of file polygon.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


cob_3d_mapping_common
Author(s): Georg Arbeiter
autogenerated on Fri Mar 1 15:17:42 2013