$search

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

virtual void applyWeighting (std::vector< Cylinder::Ptr > &merge_candidates)
 Weighting of cylinders to be merged.
virtual void computeAttributes (const Eigen::Vector3f &sym_axis, const Eigen::Vector3f &new_normal, const Eigen::Vector3f &new_origin)
 Compute Attributes of cylinder.
void ContoursFromCloud (pcl::PointCloud< pcl::PointXYZ >::ConstPtr in_cloud)
 Assign points from pointcloud to contours of this cylinder.
void ContoursFromList (std::vector< std::vector< Eigen::Vector3f > > &in_list)
 Assign points from input list to contours of this cylinder.
 Cylinder ()
 Constructor of Cylinder object.
void dbg_out (pcl::PointCloud< pcl::PointXYZRGB >::Ptr points, std::string &name)
 Debug output of points to file.
void dump_params (std::string name)
 Debug output of parameters to file.
void getCyl2D (Cylinder &c2d)
 Get 2D cylinder from 3D shape.
void getCyl3D (Cylinder &c3d)
 Get 3d cylinder from 2d shape.
void getPt3D (Eigen::Vector3f &pt2d, Eigen::Vector3f &pt3d)
 Transform Point from 2D to 3D.
void GrabParams (Cylinder &c_src)
 Grab parameters from source cylinder.
virtual void isMergeCandidate (const std::vector< Cylinder::Ptr > &cylinder_array, const merge_config &limits, std::vector< int > &intersections)
 Check for merge candidates.
void makeCyl2D ()
 Transform 3D cylinder to 2D shape.
void makeCyl3D ()
 Transformation to 3D of 2D shape.
virtual void merge (std::vector< Cylinder::Ptr > &c_array)
 Merge cylinders.
void ParamsFromCloud (pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr in_cloud, std::vector< int > &indices)
 Paramter estimation and assignment from pointcloud.
void ParamsFromShapeMsg ()
 Assign paramters from shape message to cylinder.
void printAttributes (std::string &name)
 Debug Output to terminal.
virtual void transform2tf (Eigen::Affine3f &tf)
 Transform cylinder to target frame.

Public Attributes

double h_max_
double h_min_
int merged_limit
Eigen::Vector3f origin_
double r_
Eigen::Vector3f sym_axis

Protected Member Functions

void compensate_offset (Cylinder::Ptr &c_ref)
 Compensate offset.
void getArc (const Eigen::Vector3f &goal, const Eigen::Vector3f &start, float &Tx, bool first)
 Compute arclength between 2 points.

Detailed Description

Class representing Cylinder shapes.

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

Definition at line 105 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 114 of file cylinder.h.


Constructor & Destructor Documentation

cob_3d_mapping::Cylinder::Cylinder ( void   )  [inline]

Constructor of Cylinder object.

Definition at line 121 of file cylinder.h.


Member Function Documentation

void cob_3d_mapping::Cylinder::applyWeighting ( std::vector< Cylinder::Ptr > &  merge_candidates  )  [virtual]

Weighting of cylinders to be merged.

According to the merge weights of the individual cylinders, this cylinder is assigned a merge weight.

Parameters:
[in] merge_candidates Cylinders, that the merge weight of this Cylinder depends on.
See also:
assignWeight()

Definition at line 437 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::compensate_offset ( Cylinder::Ptr c_ref  )  [protected]

Compensate offset.

Transformation accounting for offset in symmetry axis and x,y -direction of origin. This Cylinder is transformed to the Reference Cylinder.

Parameters:
[in] c_ref Reference Cylinder
Note:
Apply this, when two cylinders have to be merged, whose origin and symmetry axis are not perfectly similar.

Definition at line 599 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::computeAttributes ( const Eigen::Vector3f &  sym_axis,
const Eigen::Vector3f &  new_normal,
const Eigen::Vector3f &  new_origin 
) [virtual]

Compute Attributes of cylinder.

Compute attributes of cylinder depending on input parameters.

Parameters:
[in] sym_axis Symmetry axis of cylinder
[in] new_normal Normal of 2d representation of cylinder
[in] new_origin Origin of cylinder

Definition at line 168 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::ContoursFromCloud ( pcl::PointCloud< pcl::PointXYZ >::ConstPtr  in_cloud  ) 

Assign points from pointcloud to contours of this cylinder.

Parameters:
[in] in_cloud Pointcloud containing contour points.

Definition at line 67 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::ContoursFromList ( std::vector< std::vector< Eigen::Vector3f > > &  in_list  ) 

Assign points from input list to contours of this cylinder.

Parameters:
[in] in_list List Vector containing contour points.

Definition at line 83 of file cylinder.cpp.

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

Debug output of points to file.

Parameters:
[in] points Contour points of the Cylinder.
[in] name Name of the output file.

Definition at line 489 of file cylinder.cpp.

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

Debug output of parameters to file.

Parameters:
[in] name Name of the output file.

Definition at line 510 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::getArc ( const Eigen::Vector3f &  goal,
const Eigen::Vector3f &  start,
float &  Tx,
bool  first 
) [protected]

Compute arclength between 2 points.

Parameters:
[in] goal The end point of the arc.
[in] start The start point of the arc.
[out] Tx Translation in x direction, corresponds to the arclength.
[in] first True if goal is first point in a Cylinder contour.
Note:
The arclength is computed based on the radius of the Cylinder and the relative position of the points. Therefore both start and goal have to be in local Cylinder-coordinates and they have to be positioned on the Cylinder surface.

Definition at line 541 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::getCyl2D ( Cylinder c2d  ) 

Get 2D cylinder from 3D shape.

3D shape is transformed to 3D shape and copied.

Parameters:
[out] c2d cylinder , the 2D-shape is copied to.
See also:
Cylinder::makeCyl2D()

Definition at line 348 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::getCyl3D ( Cylinder c3d  ) 

Get 3d cylinder from 2d shape.

2D shape is transformed to 3D shape and copied.

Parameters:
[out] c3d Cylinder, 3D cylinder is copied to.
See also:
Cylinder::makeCyl3D()

Definition at line 244 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::getPt3D ( Eigen::Vector3f &  pt2d,
Eigen::Vector3f &  pt3d 
)

Transform Point from 2D to 3D.

Transformation of Point, that is part of cylinder from flat/2D shape to 3D shape.

Note:
Transformation depends on position relative to normal and radius of the cylinder.
Coordinates have to be in cylinder system.
Parameters:
[in] pt2d Point , part of 2D shape
[out] pt3d Point, part of 3D shape

Definition at line 291 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::GrabParams ( Cylinder c_src  ) 

Grab parameters from source cylinder.

Parameters:
c_src Source cylinder

Definition at line 223 of file cylinder.cpp.

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

Check for merge candidates.

Cylinders are checked, if they have to be merged with this cylinder under the given merge configuration. Parameters of the Cylinders are compared as well if their contours are intersected.

Parameters:
[in] poly_vec Vector of cylinders, that are checked.
[in] merge_config Conditions, under which merge will be performed
[out] intersections Indices of merge candidates

Definition at line 358 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::makeCyl2D (  ) 

Transform 3D cylinder to 2D shape.

Projection of cylinder onto plane , by means of arclength. This way treatment as a polygon is possible.

Definition at line 299 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::makeCyl3D (  ) 

Transformation to 3D of 2D shape.

Transformation of 2D shape to 3D using polar coordinates.

Definition at line 254 of file cylinder.cpp.

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

Merge cylinders.

This cylinder is merged with cylinders in input array. Therefore cylinders are transformed to flat polygons. Then the Polygon merge process is applied. The result is weighted,merged cylinder.

Parameters:
[in] c_array Array of cylinders, cylinder object is merged with.
See also:
Polygon::merge()

Definition at line 397 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::ParamsFromCloud ( pcl::PointCloud< pcl::PointXYZRGB >::ConstPtr  in_cloud,
std::vector< int > &  indices 
)

Paramter estimation and assignment from pointcloud.

Estimation uses pcl::SACSegmentation.Parameters assigned to cylinder accordingly.

Parameters:
[in] in_cloud Input pointcloud
[in] indices Indices of contour points

Definition at line 104 of file cylinder.cpp.

void cob_3d_mapping::Cylinder::ParamsFromShapeMsg (  ) 

Assign paramters from shape message to cylinder.

Assignment and completion of parameter set from shape message to cylinder.

Definition at line 154 of file cylinder.cpp.

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

Debug Output to terminal.

Parameters:
[in] name Name of the output file.

Definition at line 527 of file cylinder.cpp.

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

Transform cylinder to target frame.

Parameters:
[in] trafo Transformation from source frame to target frame.

Definition at line 199 of file cylinder.cpp.


Member Data Documentation

Point on top of cylinder

Definition at line 304 of file cylinder.h.

Point at the bottom of cylinder.

Definition at line 303 of file cylinder.h.

Limit for merge counter

Definition at line 307 of file cylinder.h.

Origin of cylinder.

Definition at line 306 of file cylinder.h.

Radius of cylinder.

Definition at line 302 of file cylinder.h.

Symmetry axis of cylinder. Direction Vector of symmetry axis.

Definition at line 305 of file cylinder.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:41 2013