Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
cob_3d_mapping_tools::PointGenerator< PointT > Class Template Reference

Point cloud generator for simple shapes. More...

#include <point_generator.h>

List of all members.

Public Types

typedef pcl::PointCloud< PointTPointCloud
typedef boost::shared_ptr
< const PointCloud
PointCloudConstPtr
typedef boost::shared_ptr
< PointCloud
PointCloudPtr

Public Member Functions

void generateBox (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_1, const Eigen::Vector3f &direction_2, const float &corner_size, const float &height)
 Generates a box.
void generateBox (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_1, const Eigen::Vector3f &direction_2, const Eigen::Vector3f &direction_3, const float &corner_size)
 Generates a box.
void generateCircle (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &rotation_axis, const Eigen::Vector3f &radius, const float &angle=2 *M_PI, const uint32_t &color=0xffffff)
 Generates points in a circle.
void generateCirclePlane (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &rotation_axis, const float &radius)
 Generates a circle shaped plane.
void generateCirclePlane (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &rotation_axis, const Eigen::Vector3f &radius, const float &angle=2 *M_PI)
 Generates a filled arc.
void generateCone (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction, const float &radius_base, const float &radius_peak=0.0f)
 Generates a full cone.
void generateCorner (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_1, const Eigen::Vector3f &direction_2, const Eigen::Vector3f &direction_3, const float &corner_size=0.0f)
 Generates a corner.
void generateCylinder (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction, const float &radius)
 Generates a full cylinder.
void generateCylinder (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction, const Eigen::Vector3f &radius, const float &angle)
 Generates a cylinder.
void generateEdge (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_edge, const Eigen::Vector3f &direction_depth)
 Generates an edge shaped from two perpendicular planes.
void generateEdge (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_edge, const Eigen::Vector3f &direction_1, const Eigen::Vector3f &direction_2)
 Generates an edge shaped by two intersecting planes.
void generateHandle (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &rotation_axis, const Eigen::Vector3f &radius_curvature, const float &radius_handle, const float &angle)
 Generates a handle (or a torus)
void generateLine (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction, const uint32_t &color=0xffffff)
 Generates points in a line.
void generatePlane (const float &step_size, const Eigen::Vector3f &origin, const Eigen::Vector3f &direction_1, const Eigen::Vector3f &direction_2)
 Generates quadrangle plane.
void generateSphere (const float &step_size, const Eigen::Vector3f &center, const Eigen::Vector3f &rotation_axis, const float &radius, const float &angle=M_PI)
 Generates a hemisphere.
void generateSphere (const float &step_size, const Eigen::Vector3f &center, const float &radius)
 Generates a full sphere.
 PointGenerator ()
float random ()
void setGaussianNoise (const float &sigma)
 Define a Gaussian noise on the shapes to be generated.
void setOutputCloud (PointCloudPtr &cloud)
 Set the pointer to the output point cloud.
 ~PointGenerator ()

Protected Member Functions

void addSinglePoint (const Eigen::Vector3f &point, const uint32_t &color=0xffffff)
Eigen::Vector3f getArbitraryPerpendicularNormalized (const Eigen::Vector3f &vector)
 produces a random normalized arbitrary prependicular vector
Eigen::Vector3f randomVector ()
int round (float f)

Protected Attributes

PointCloudPtr cloud_
boost::normal_distribution< float > n_dist_
boost::variate_generator
< boost::mt19937
&, boost::normal_distribution
< float > > 
n_rng_
float noise_
int rgba_index_
boost::mt19937 rng_

Detailed Description

template<typename PointT>
class cob_3d_mapping_tools::PointGenerator< PointT >

Point cloud generator for simple shapes.

Provides a set of functions to add synthetic shapes to a existing point cloud. Combining some functions allows to create whole artificial scenes.

Definition at line 86 of file point_generator.h.


Member Typedef Documentation

Definition at line 95 of file point_generator.h.

template<typename PointT>
typedef boost::shared_ptr<const PointCloud> cob_3d_mapping_tools::PointGenerator< PointT >::PointCloudConstPtr

Definition at line 97 of file point_generator.h.

template<typename PointT>
typedef boost::shared_ptr<PointCloud> cob_3d_mapping_tools::PointGenerator< PointT >::PointCloudPtr

Definition at line 96 of file point_generator.h.


Constructor & Destructor Documentation

template<typename PointT >
PointGenerator::PointGenerator ( )

Empty constructor

Definition at line 73 of file point_generator.cpp.

template<typename PointT >
PointGenerator::~PointGenerator ( )

Empty destructor

Definition at line 80 of file point_generator.cpp.


Member Function Documentation

template<typename PointT >
void PointGenerator::addSinglePoint ( const Eigen::Vector3f &  point,
const uint32_t &  color = 0xffffff 
) [protected]

Definition at line 565 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateBox ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_1,
const Eigen::Vector3f &  direction_2,
const float &  corner_size,
const float &  height 
)

Generates a box.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting edge of the box
[in]direction_1the first direction vector
[in]direction_2the second direction vector
[in]corner_sizethe size how big the corners should be labeled
[in]heightsets the size of the third direction, defined by the cross product of the first two vectors

Definition at line 299 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateBox ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_1,
const Eigen::Vector3f &  direction_2,
const Eigen::Vector3f &  direction_3,
const float &  corner_size 
)

Generates a box.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting edge of the box
[in]direction_1the first direction vector
[in]direction_2the second direction vector
[in]direction_3the third direction vector
[in]corner_sizethe size how big the corners should be labeled

Definition at line 311 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCircle ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  rotation_axis,
const Eigen::Vector3f &  radius,
const float &  angle = 2 * M_PI,
const uint32_t &  color = 0xffffff 
)

Generates points in a circle.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of the circle
[in]rotation_axisa vector defining the axis the circle is rotating around
[in]radiusa vector perpendicular to rotation_axis. Its length defines the size of the circle.
[in]angledefine a angle (in rad) to generate an arc starting at the radius vector.
[in]colorthe color assigned to the generated points (default: white)

Definition at line 120 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCirclePlane ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  rotation_axis,
const float &  radius 
)

Generates a circle shaped plane.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe chenter of the circle plane
[in]rotation_axisa vector defining the axis the cicle is rotating around
[in]radiusdefining the size of the circle in meters

Definition at line 186 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCirclePlane ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  rotation_axis,
const Eigen::Vector3f &  radius,
const float &  angle = 2 * M_PI 
)

Generates a filled arc.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of the arc
[in]rotation_axisa vector defining the axis the circle is rotating around
[in]radiusa vector perpendicular to rotation_axis. Its length defines the size of the circle.
[in]angledefine a angle (in rad) to generate an arc starting at the radius vector.

Definition at line 196 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCone ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction,
const float &  radius_base,
const float &  radius_peak = 0.0f 
)

Generates a full cone.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of bottom
[in]radius_baseradius at the bottom
[in]radius_peakradius at the top

Definition at line 476 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCorner ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_1,
const Eigen::Vector3f &  direction_2,
const Eigen::Vector3f &  direction_3,
const float &  corner_size = 0.0f 
)

Generates a corner.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting point of the corner
[in]direction_1the first direction vector relative to the origin
[in]direction_2the second direction vector relative to the origin
[in]direction_3the third direction vector relative to the origin
[in]corner_sizeif not set, the length of direction_1 is used as the size

Definition at line 264 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCylinder ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction,
const float &  radius 
)

Generates a full cylinder.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of bottom
[in]directionthe rotation axis of the cylinder, the length determines its height
[in]radiusthe radius of the cylinder

Definition at line 442 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateCylinder ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction,
const Eigen::Vector3f &  radius,
const float &  angle 
)

Generates a cylinder.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of bottom
[in]directionthe rotation axis of the cylinder, the length determines its height
[in]radiusthe radius of the cylinder
[in]anglethe angle starting from the radius vector

Definition at line 452 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateEdge ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_edge,
const Eigen::Vector3f &  direction_depth 
)

Generates an edge shaped from two perpendicular planes.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting point of the edge
[in]direction_edgethe direction vector pointing to the end point of the edge
[in]direction_depththe vector defining the direction and length of the first of the planes. The other plane's direction is determined from the cross product of both.

Definition at line 231 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateEdge ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_edge,
const Eigen::Vector3f &  direction_1,
const Eigen::Vector3f &  direction_2 
)

Generates an edge shaped by two intersecting planes.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting point of the edge
[in]direction_edgethe direction vector pointing to the end point of the edge
[in]direction_1...
[in]direction_2...

Definition at line 243 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateHandle ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  rotation_axis,
const Eigen::Vector3f &  radius_curvature,
const float &  radius_handle,
const float &  angle 
)

Generates a handle (or a torus)

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe center of the torus
[in]rotation_axisthe rotation axis of the torus
[in]radius_curvaturethe size of the torus
[in]radius_handlethe thickness of the torus
[in]anglethe rotation angle (in rad) starting at radius_curvature vector

Definition at line 541 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateLine ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction,
const uint32_t &  color = 0xffffff 
)

Generates points in a line.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting point of the line
[in]directionthe direction relative from the origin pointing to the end of the line
[in]colorthe color assigned to the generated points (default: white)

Definition at line 84 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generatePlane ( const float &  step_size,
const Eigen::Vector3f &  origin,
const Eigen::Vector3f &  direction_1,
const Eigen::Vector3f &  direction_2 
)

Generates quadrangle plane.

Parameters:
[in]step_sizethe distance between each generated point
[in]originthe starting edge of the plane
[in]direction_1the first direction vector relative to the origin
[in]direction_2the second direction vector relative to the origin

Definition at line 213 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateSphere ( const float &  step_size,
const Eigen::Vector3f &  center,
const Eigen::Vector3f &  rotation_axis,
const float &  radius,
const float &  angle = M_PI 
)

Generates a hemisphere.

Parameters:
[in]step_sizethe distance between each generated point
[in]centerof the sphere
[in]rotation_axisthe rotation axis vector
[in]radiusthe size of the hemisphere
[in]anglethe height of the hemisphere

Definition at line 504 of file point_generator.cpp.

template<typename PointT >
void PointGenerator::generateSphere ( const float &  step_size,
const Eigen::Vector3f &  center,
const float &  radius 
)

Generates a full sphere.

Parameters:
[in]step_sizethe distance between each generated point
[in]centerthe center of the sphere
[in]radiusthe radius of the sphere in meters

Definition at line 533 of file point_generator.cpp.

template<typename PointT>
Eigen::Vector3f cob_3d_mapping_tools::PointGenerator< PointT >::getArbitraryPerpendicularNormalized ( const Eigen::Vector3f &  vector) [inline, protected]

produces a random normalized arbitrary prependicular vector

Parameters:
[in]vectorinput vector
Returns:
a random vector perpendicular to vector

Definition at line 359 of file point_generator.h.

template<typename PointT>
float cob_3d_mapping_tools::PointGenerator< PointT >::random ( ) [inline]

Definition at line 337 of file point_generator.h.

template<typename PointT>
Eigen::Vector3f cob_3d_mapping_tools::PointGenerator< PointT >::randomVector ( ) [inline, protected]

Definition at line 349 of file point_generator.h.

template<typename PointT>
int cob_3d_mapping_tools::PointGenerator< PointT >::round ( float  f) [inline, protected]

Definition at line 344 of file point_generator.h.

template<typename PointT>
void cob_3d_mapping_tools::PointGenerator< PointT >::setGaussianNoise ( const float &  sigma) [inline]

Define a Gaussian noise on the shapes to be generated.

Parameters:
[in]sigmastrength of noise in meters

Definition at line 119 of file point_generator.h.

template<typename PointT>
void cob_3d_mapping_tools::PointGenerator< PointT >::setOutputCloud ( PointCloudPtr cloud) [inline]

Set the pointer to the output point cloud.

Parameters:
[out]cloudpointer to the output point cloud

Definition at line 103 of file point_generator.h.


Member Data Documentation

template<typename PointT>
PointCloudPtr cob_3d_mapping_tools::PointGenerator< PointT >::cloud_ [protected]

Definition at line 369 of file point_generator.h.

template<typename PointT>
boost::normal_distribution<float> cob_3d_mapping_tools::PointGenerator< PointT >::n_dist_ [protected]

Definition at line 377 of file point_generator.h.

template<typename PointT>
boost::variate_generator<boost::mt19937&, boost::normal_distribution<float> > cob_3d_mapping_tools::PointGenerator< PointT >::n_rng_ [protected]

Definition at line 379 of file point_generator.h.

template<typename PointT>
float cob_3d_mapping_tools::PointGenerator< PointT >::noise_ [protected]

Definition at line 372 of file point_generator.h.

template<typename PointT>
int cob_3d_mapping_tools::PointGenerator< PointT >::rgba_index_ [protected]

Definition at line 371 of file point_generator.h.

template<typename PointT>
boost::mt19937 cob_3d_mapping_tools::PointGenerator< PointT >::rng_ [protected]

Definition at line 375 of file point_generator.h.


The documentation for this class was generated from the following files:


cob_3d_mapping_tools
Author(s): Georg Arbeiter
autogenerated on Wed Aug 26 2015 11:04:27