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

Class representing Cylinder shapes. More...

#include <cylinder.h>

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

List of all members.

Public Types

typedef boost::shared_ptr
< Cylinder
Ptr
 Cylinder pointer.

Public Member Functions

void computeHeight ()
 Compute the height of the cylinder.
void computePose (Eigen::Vector3f origin, Eigen::Vector3f z_axis)
 Compute the pose from origin and z axis.
void computePose (Eigen::Vector3f origin, std::vector< std::vector< Eigen::Vector3f > > &contours_3d)
 Compute the pose from origin and a 3D contour.
 Cylinder ()
 Construct empty Cylinder object.
 Cylinder (unsigned int id, Eigen::Vector3f origin, Eigen::Vector3f sym_axis, double radius, std::vector< std::vector< Eigen::Vector3f > > &contours_3d, std::vector< bool > holes, std::vector< float > color)
 Construct Cylinder object from parameters.
 Cylinder (unsigned int id, Eigen::Vector3f origin, Eigen::Vector3f sym_axis, double radius, std::vector< pcl::PointCloud< pcl::PointXYZ > > &contours_3d, std::vector< bool > holes, std::vector< float > color)
 Construct Cylinder object from parameters.
void dbgOut (pcl::PointCloud< pcl::PointXYZRGB >::Ptr points, std::string &name)
 Debug output of points to file.
void dumpParams (std::string name)
 Debug output of parameters to file.
virtual std::vector
< std::vector< Eigen::Vector3f > > 
getContours3D ()
 Get the contours of the cylinder as 3D points.
virtual void getMergeCandidates (const std::vector< Polygon::Ptr > &cylinder_array, std::vector< int > &intersections)
 Find merge candidates.
virtual void merge (std::vector< Polygon::Ptr > &poly_vec)
 Merge cylinders.
void printAttributes (std::string &name)
 Debug Output to terminal.
virtual void setContours3D (std::vector< std::vector< Eigen::Vector3f > > &contours_3d)
 Set the 2D contours of the cylinder from 3D points.
virtual void setParamsFrom (Polygon::Ptr &p)
 Obtain the params of this from another cylinder.
virtual void transform (Eigen::Affine3f &tf)
 Transform the cylinder by tf.
void triangulate (list< TPPLPoly > &tri_list) const
 Triangulate surface polygons from the contours.
virtual void updateAttributes (const Eigen::Vector3f &sym_axis, const Eigen::Vector3f &origin, const Eigen::Vector3f &z_axis)
 Compute Attributes (pose, sym axis) of cylinder.

Public Attributes

double h_max_
double h_min_
double r_
Eigen::Vector3f sym_axis_

Protected Member Functions

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

Detailed Description

Class representing Cylinder shapes.

Note:
Cylinder Parameter Estimation can be performed.
Cylinder Merging is handled.

Definition at line 116 of file cylinder.h.


Member Typedef Documentation

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

Cylinder pointer.

Boost shared pointer to cylinder.

Reimplemented from cob_3d_mapping::Polygon.

Definition at line 124 of file cylinder.h.


Constructor & Destructor Documentation

Construct empty Cylinder object.

Definition at line 129 of file cylinder.h.

cob_3d_mapping::Cylinder::Cylinder ( unsigned int  id,
Eigen::Vector3f  origin,
Eigen::Vector3f  sym_axis,
double  radius,
std::vector< std::vector< Eigen::Vector3f > > &  contours_3d,
std::vector< bool >  holes,
std::vector< float >  color 
)

Construct Cylinder object from parameters.

Parameters:
[in]idA unique id.
[in]originThe origin of the cylinder.
[in]sym_axisThe symmetry axis of the cylinder.
[in]radiusThe radius of the cylinder.
[in]contours_3dThe 3D contour points of the cylinder (represented by separate contours).
[in]holesA vector showing which contour is a hole.
[in]colorThe color of the cylinder.

Definition at line 115 of file cylinder.cpp.

cob_3d_mapping::Cylinder::Cylinder ( unsigned int  id,
Eigen::Vector3f  origin,
Eigen::Vector3f  sym_axis,
double  radius,
std::vector< pcl::PointCloud< pcl::PointXYZ > > &  contours_3d,
std::vector< bool >  holes,
std::vector< float >  color 
)

Construct Cylinder object from parameters.

Parameters:
[in]idA unique id.
[in]originThe origin of the cylinder.
[in]sym_axisThe symmetry axis of the cylinder.
[in]radiusThe radius of the cylinder.
[in]contours_3dThe 3D contour points of the cylinder (represented by separate contours).
[in]holesA vector showing which contour is a hole.
[in]colorThe color of the cylinder.

Definition at line 139 of file cylinder.cpp.


Member Function Documentation

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

Definition at line 428 of file cylinder.cpp.

Compute the height of the cylinder.

Definition at line 262 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::computePose ( Eigen::Vector3f  origin,
Eigen::Vector3f  z_axis 
)

Compute the pose from origin and z axis.

Parameters:
[in]originThe origin of the cylinder.
[in]z_axisThe z_axis (perpendicular to the sym_axis) of the cylinder.

Definition at line 255 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::computePose ( Eigen::Vector3f  origin,
std::vector< std::vector< Eigen::Vector3f > > &  contours_3d 
)

Compute the pose from origin and a 3D contour.

Parameters:
[in]originThe origin of the cylinder.
[in]contours_3dThe 3D contour of the cylinder.

Definition at line 244 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::dbgOut ( pcl::PointCloud< pcl::PointXYZRGB >::Ptr  points,
std::string &  name 
)

Debug output of points to file.

Parameters:
[in]pointsContour points of the Cylinder.
[in]nameName of the output file.

Definition at line 635 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::dumpParams ( std::string  name)

Debug output of parameters to file.

Parameters:
[in]nameName of the output file.

Definition at line 656 of file cylinder.cpp.

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

Get the contours of the cylinder as 3D points.

Returns:
The 3D contours.

Reimplemented from cob_3d_mapping::Polygon.

Definition at line 216 of file cylinder.cpp.

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

Find merge candidates.

Parameters:
[in]cylinder_arrayThe cylinders to be checked.
[out]intersectionsIndices of merge candidates.

Definition at line 389 of file cylinder.cpp.

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

Merge cylinders.

Parameters:
[in]poly_vecThe cylinders to be merged with this.

Definition at line 482 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::printAttributes ( std::string &  name)

Debug Output to terminal.

Parameters:
[in]nameName of the output file.

Definition at line 673 of file cylinder.cpp.

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

Set the 2D contours of the cylinder from 3D points.

Parameters:
[in]contours_3dThe 3D contours.

Reimplemented from cob_3d_mapping::Polygon.

Definition at line 186 of file cylinder.cpp.

Obtain the params of this from another cylinder.

Parameters:
[in]pThe cylinder the parameters are copied from.

Reimplemented from cob_3d_mapping::Polygon.

Definition at line 298 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::transform ( Eigen::Affine3f &  tf) [virtual]

Transform the cylinder by tf.

Parameters:
[in]tfTransformation to be applied.

Definition at line 312 of file cylinder.cpp.

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

Triangulate surface polygons from the contours.

Parameters:
[out]tri_listThe list of polygons.

Reimplemented from cob_3d_mapping::Polygon.

Definition at line 336 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::updateAttributes ( const Eigen::Vector3f &  sym_axis,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  z_axis 
) [virtual]

Compute Attributes (pose, sym axis) of cylinder.

Compute attributes of cylinder depending on input parameters.

Parameters:
[in]sym_axisSymmetry axis of cylinder
[in]originOrigin of cylinder
[in]z_axisz axis of cylinder

Definition at line 281 of file cylinder.cpp.


Member Data Documentation

Point on top of cylinder

Definition at line 285 of file cylinder.h.

Point at the bottom of cylinder.

Definition at line 284 of file cylinder.h.

Radius of cylinder.

Definition at line 283 of file cylinder.h.

Symmetry axis of cylinder. Direction vector of symmetry axis.

Definition at line 286 of file cylinder.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