Class representing Cylinder shapes. More...
#include <cylinder.h>
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) |
Class representing Cylinder shapes.
Definition at line 116 of file cylinder.h.
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.
cob_3d_mapping::Cylinder::Cylinder | ( | ) | [inline] |
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.
[in] | id | A unique id. |
[in] | origin | The origin of the cylinder. |
[in] | sym_axis | The symmetry axis of the cylinder. |
[in] | radius | The radius of the cylinder. |
[in] | contours_3d | The 3D contour points of the cylinder (represented by separate contours). |
[in] | holes | A vector showing which contour is a hole. |
[in] | color | The 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.
[in] | id | A unique id. |
[in] | origin | The origin of the cylinder. |
[in] | sym_axis | The symmetry axis of the cylinder. |
[in] | radius | The radius of the cylinder. |
[in] | contours_3d | The 3D contour points of the cylinder (represented by separate contours). |
[in] | holes | A vector showing which contour is a hole. |
[in] | color | The color of the cylinder. |
Definition at line 139 of file cylinder.cpp.
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.
[in] | origin | The origin of the cylinder. |
[in] | z_axis | The 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.
[in] | origin | The origin of the cylinder. |
[in] | contours_3d | The 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.
[in] | points | Contour points of the Cylinder. |
[in] | name | Name 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.
[in] | name | Name 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.
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.
[in] | cylinder_array | The cylinders to be checked. |
[out] | intersections | Indices 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.
[in] | poly_vec | The 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.
[in] | name | Name 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.
[in] | contours_3d | The 3D contours. |
Reimplemented from cob_3d_mapping::Polygon.
Definition at line 186 of file cylinder.cpp.
void cob_3d_mapping::Cylinder::setParamsFrom | ( | Polygon::Ptr & | p | ) | [virtual] |
Obtain the params of this from another cylinder.
[in] | p | The 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.
[in] | tf | Transformation 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.
[out] | tri_list | The 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.
[in] | sym_axis | Symmetry axis of cylinder |
[in] | origin | Origin of cylinder |
[in] | z_axis | z axis of cylinder |
Definition at line 281 of file cylinder.cpp.
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.
double cob_3d_mapping::Cylinder::r_ |
Radius of cylinder.
Definition at line 283 of file cylinder.h.
Eigen::Vector3f cob_3d_mapping::Cylinder::sym_axis_ |
Symmetry axis of cylinder. Direction vector of symmetry axis.
Definition at line 286 of file cylinder.h.