All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends
Classes | Public Types | Public Member Functions | Static Public Member Functions | Static Protected Member Functions | Protected Attributes
pcl::ObjectModel Class Reference

Saves 3D information about an object. More...

#include <object_model.h>

List of all members.

Classes

struct  ValidationPoints

Public Types

typedef PointCloud< PointTypePointCloudType
typedef PointXYZ PointType

Public Member Functions

void addNoise (float max_noise)
void addSimulatedView (const Eigen::Vector3f &direction, float angular_resolution=deg2rad(0.5f), float distance=-1.0, std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *views=NULL)
void addView (const Eigen::Affine3f &viewer_pose, float angular_resolution)
 Same as above, directly adding it to views_.
void clear (bool keep_point_cloud=false)
 Erase all data stored in the model - if keep_point_cloud is true point_cloud_ will stay unchanged.
void clearViews ()
 Erase all views and connected information.
void createView (const Eigen::Affine3f &viewer_pose, float angular_resolution, RangeImage &view) const
 Get a range image of the object, seen from the given pose.
Eigen::Affine3f doFastICP (const Eigen::Affine3f &initial_guess, const RangeImage &range_image, int search_radius=3, int no_of_surface_points_to_use=25, int no_of_border_points_to_use=10, int num_iterations=10, float max_distance_start=-1.0f, float max_distance_end=-1.0f) const
 Improve the transformation given by doing ICP using very few already cacluated points (using the validation points)
Eigen::Affine3f doSlowICP (const Eigen::Affine3f &initial_guess, const RangeImage &range_image, int search_radius, int num_iterations, float max_distance_start, float max_distance_end) const
 Improve the transformation given by doing ICP on a view simulation.
void extractInterestPoints (int view_ix, float support_size, NarfKeypoint &interest_point_detector, PointCloud< InterestPoint > &interest_points) const
 Get interest points for a certain view.
void extractNARFsForCompleteSurface (unsigned int descriptor_size, float size_in_world, bool rotation_invariant, std::vector< std::vector< Narf * > * > &features) const
void extractNARFsForInterestPoints (unsigned int descriptor_size, float size_in_world, bool rotation_invariant, NarfKeypoint &interest_point_detector, std::vector< std::vector< Narf * > * > &features) const
const Eigen::Vector3fgetCenter () const
 Get the model's center point.
int getClosestValidationPointViewIdx (const Eigen::Affine3f &pose) const
 Find the index of the view that has the most similar viewpoint to the given transformation.
int getId () const
 Get the id of the object.
float getMaxAngleSize (const Eigen::Affine3f &viewer_pose) const
 Get the size of the object as an angle, when seen from the given pose.
float getMaximumPlaneSize (float initial_max_plane_error) const
 Calculates the maximum plane size in the model.
const std::string & getName () const
 Get the name of the object.
const PointCloudTypegetPointCloud () const
 Get the point cloud of the object.
PointCloudTypegetPointCloud ()
 Get the point cloud of the object - non const.
float getRadius () const
 Get the model's radius.
void getTransformedPointCloud (const Eigen::Affine3f &transformation, PointCloudType &output) const
 Get the model point cloud transformed by the given transformation.
const std::vector
< ValidationPoints > & 
getValidationPoints () const
 Get the validation points for the different views.
const RangeImage & getView (int index) const
 Get a certain view of the model.
Eigen::Affine3f getViewerPose (const Eigen::Vector3f &viewpoint) const
 Get the pose, that looks at the model's center from the given position and oriented upright (i.e. along 0,-1,0)
const std::vector< RangeImage,
Eigen::aligned_allocator
< RangeImage > > & 
getViews () const
 Get the list of views from the model.
bool isSingleViewModel () const
 Check if the object is a single view object (if false point_cloud_ is considered to be complete)
 ObjectModel ()
void sampleViews2D (int no_of_views=10, int first_layer=0, int last_layer=0, float angular_resolution=deg2rad(0.5f), float distance=-1.0f, std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *views=NULL)
void sampleViews3D (float sample_angular_resolution=deg2rad(40.0f), float angular_resolution=deg2rad(0.4f), float distance=-1.0f, std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *views=NULL)
void setId (int id)
 Set the id of the object.
void setIsSingleViewModel (bool is_single_view_model)
 Set the information if the object is a single view object (if false point_cloud_ is considered to be complete)
void setName (const std::string name)
 Set the name of the object.
void updateCenterAndRadius ()
 Recalculate the models center and radius, meaning the sphere that includes the complete object.
void updateValidationPoints (unsigned int no_of_surface_points=50, unsigned int no_of_border_points=25, float sample_resolution=deg2rad(20.0f), NarfKeypoint *interest_point_detector=NULL, float support_size=-1.0f)
virtual ~ObjectModel ()

Static Public Member Functions

template<typename FeatureType >
static void freeFeatureListMemory (std::vector< std::vector< FeatureType * > * > &feature_list)
 Free memory allocated in feature list.

Static Protected Member Functions

static void getUniformlyDistributedPoints (const std::vector< Eigen::Vector3f > &points, int no_of_points, std::vector< Eigen::Vector3f > &result)

Protected Attributes

Eigen::Vector3f center_
int id_
bool is_single_view_model_
std::string name_
PointCloudType point_cloud_
float radius_
std::vector< ValidationPointsvalidation_points_
std::vector< RangeImage,
Eigen::aligned_allocator
< RangeImage > > 
views_
std::vector< RangeImage,
Eigen::aligned_allocator
< RangeImage > > 
views_for_validation_points_

Detailed Description

Saves 3D information about an object.

Definition at line 62 of file object_model.h.


Member Typedef Documentation

Definition at line 67 of file object_model.h.

typedef PointXYZ pcl::ObjectModel::PointType

Definition at line 66 of file object_model.h.


Constructor & Destructor Documentation

Constructor

Definition at line 62 of file object_model.cpp.

Destructor

Definition at line 67 of file object_model.cpp.


Member Function Documentation

void pcl::ObjectModel::addNoise ( float  max_noise)

Adds noise to the models point cloud. Warning: This calls clear, so everything has to be recalculated for the model afterwards!

Definition at line 501 of file object_model.cpp.

void pcl::ObjectModel::addSimulatedView ( const Eigen::Vector3f direction,
float  angular_resolution = deg2rad(0.5f),
float  distance = -1.0,
std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *  views = NULL 
)

Add a certain perspective of the object to the model

Parameters:
directionfrom the center at which the object should be captured
angular_resolutionof the simulated range image
distancethe distance of the simulated viewpoint to the oject (default is 5 times the models radius)
viewslist of vies. If not set, views_ is used

Definition at line 165 of file object_model.cpp.

void pcl::ObjectModel::addView ( const Eigen::Affine3f &  viewer_pose,
float  angular_resolution 
)

Same as above, directly adding it to views_.

Definition at line 195 of file object_model.cpp.

void pcl::ObjectModel::clear ( bool  keep_point_cloud = false)

Erase all data stored in the model - if keep_point_cloud is true point_cloud_ will stay unchanged.

Definition at line 72 of file object_model.cpp.

Erase all views and connected information.

Definition at line 84 of file object_model.cpp.

void pcl::ObjectModel::createView ( const Eigen::Affine3f &  viewer_pose,
float  angular_resolution,
RangeImage &  view 
) const

Get a range image of the object, seen from the given pose.

Definition at line 202 of file object_model.cpp.

Eigen::Affine3f pcl::ObjectModel::doFastICP ( const Eigen::Affine3f &  initial_guess,
const RangeImage &  range_image,
int  search_radius = 3,
int  no_of_surface_points_to_use = 25,
int  no_of_border_points_to_use = 10,
int  num_iterations = 10,
float  max_distance_start = -1.0f,
float  max_distance_end = -1.0f 
) const

Improve the transformation given by doing ICP using very few already cacluated points (using the validation points)

Definition at line 392 of file object_model.cpp.

Eigen::Affine3f pcl::ObjectModel::doSlowICP ( const Eigen::Affine3f &  initial_guess,
const RangeImage &  range_image,
int  search_radius,
int  num_iterations,
float  max_distance_start,
float  max_distance_end 
) const

Improve the transformation given by doing ICP on a view simulation.

Definition at line 477 of file object_model.cpp.

void pcl::ObjectModel::extractInterestPoints ( int  view_ix,
float  support_size,
NarfKeypoint &  interest_point_detector,
PointCloud< InterestPoint > &  interest_points 
) const

Get interest points for a certain view.

Definition at line 243 of file object_model.cpp.

void pcl::ObjectModel::extractNARFsForCompleteSurface ( unsigned int  descriptor_size,
float  size_in_world,
bool  rotation_invariant,
std::vector< std::vector< Narf * > * > &  features 
) const

Extract NARF features from every pixel in the views of the model

Parameters:
descriptordetermines the descriptor length
size_in_worldsupport size of the feature
featuresreturned list of lists of features

Definition at line 220 of file object_model.cpp.

void pcl::ObjectModel::extractNARFsForInterestPoints ( unsigned int  descriptor_size,
float  size_in_world,
bool  rotation_invariant,
NarfKeypoint &  interest_point_detector,
std::vector< std::vector< Narf * > * > &  features 
) const

Extract NARF features from border interest point (see range_image_interest_point_detector.h)

Parameters:
descriptordetermines the descriptor length
size_in_worldsupport size of the feature
featuresreturned list of lists of features

Definition at line 255 of file object_model.cpp.

template<typename FeatureType >
void pcl::ObjectModel::freeFeatureListMemory ( std::vector< std::vector< FeatureType * > * > &  feature_list) [inline, static]

Free memory allocated in feature list.

Definition at line 41 of file object_model.hpp.

const Eigen::Vector3f& pcl::ObjectModel::getCenter ( ) const [inline]

Get the model's center point.

Definition at line 213 of file object_model.h.

int pcl::ObjectModel::getClosestValidationPointViewIdx ( const Eigen::Affine3f &  pose) const [inline]

Find the index of the view that has the most similar viewpoint to the given transformation.

Definition at line 55 of file object_model.hpp.

int pcl::ObjectModel::getId ( ) const [inline]

Get the id of the object.

Definition at line 199 of file object_model.h.

float pcl::ObjectModel::getMaxAngleSize ( const Eigen::Affine3f &  viewer_pose) const

Get the size of the object as an angle, when seen from the given pose.

Definition at line 190 of file object_model.cpp.

float pcl::ObjectModel::getMaximumPlaneSize ( float  initial_max_plane_error) const

Calculates the maximum plane size in the model.

Definition at line 516 of file object_model.cpp.

const std::string& pcl::ObjectModel::getName ( ) const [inline]

Get the name of the object.

Definition at line 201 of file object_model.h.

Get the point cloud of the object.

Definition at line 203 of file object_model.h.

Get the point cloud of the object - non const.

Definition at line 205 of file object_model.h.

float pcl::ObjectModel::getRadius ( ) const [inline]

Get the model's radius.

Definition at line 211 of file object_model.h.

void pcl::ObjectModel::getTransformedPointCloud ( const Eigen::Affine3f &  transformation,
PointCloudType output 
) const

Get the model point cloud transformed by the given transformation.

Definition at line 279 of file object_model.cpp.

void pcl::ObjectModel::getUniformlyDistributedPoints ( const std::vector< Eigen::Vector3f > &  points,
int  no_of_points,
std::vector< Eigen::Vector3f > &  result 
) [static, protected]

Distributes no_of_points of the given points over the surface. result[0] will be point_indices[0] and result[1] will be the point from point_indices, that is farthest away from result[0] and so on. Thereby the points 0...i in the result vector have maximal distances to each other

Definition at line 361 of file object_model.cpp.

Get the validation points for the different views.

Definition at line 215 of file object_model.h.

const RangeImage& pcl::ObjectModel::getView ( int  index) const [inline]

Get a certain view of the model.

Definition at line 209 of file object_model.h.

Affine3f pcl::ObjectModel::getViewerPose ( const Eigen::Vector3f viewpoint) const

Get the pose, that looks at the model's center from the given position and oriented upright (i.e. along 0,-1,0)

Definition at line 210 of file object_model.cpp.

const std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> >& pcl::ObjectModel::getViews ( ) const [inline]

Get the list of views from the model.

Definition at line 207 of file object_model.h.

Check if the object is a single view object (if false point_cloud_ is considered to be complete)

Definition at line 217 of file object_model.h.

void pcl::ObjectModel::sampleViews2D ( int  no_of_views = 10,
int  first_layer = 0,
int  last_layer = 0,
float  angular_resolution = deg2rad(0.5f),
float  distance = -1.0f,
std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *  views = NULL 
)

Use the point_cloud_ member to create a number of sample views of the object from a points surrounding the object at a fixed height. This is useful for object that typically only appear upright, like a chair for example. ! Please call updateCenterAndRadius() before using this !

Parameters:
no_of_viewsthe number of sampled views, that will be added to views_
first_layerfirst layer to be computed. 0 is on the middle height of the object, every other is either one half object height above (for positive values) or below (negative values). All layers from first_layer to last_layer will be computed.
last_layerlast layer to be computed. See above for more details.
angular_resolutionof the simulated range images
distancethe distance of the simulated viewpoint to the oject (default is 5 times the models radius)

Definition at line 112 of file object_model.cpp.

void pcl::ObjectModel::sampleViews3D ( float  sample_angular_resolution = deg2rad(40.0f),
float  angular_resolution = deg2rad(0.4f),
float  distance = -1.0f,
std::vector< RangeImage, Eigen::aligned_allocator< RangeImage > > *  views = NULL 
)

Use the point_cloud_ member to create a number of sample views around the object. ! Please call updateCenterAndRadius() before using this !

Parameters:
sample_angular_resolutiontheangular distance between the sampled positions. Should be in (0.0, deg2rad(90.0)]
angular_resolutionof the simulated range images
distancethe distance of the simulated viewpoint to the oject (default is 5 times the models radius)

Definition at line 134 of file object_model.cpp.

void pcl::ObjectModel::setId ( int  id) [inline]

Set the id of the object.

Definition at line 223 of file object_model.h.

void pcl::ObjectModel::setIsSingleViewModel ( bool  is_single_view_model) [inline]

Set the information if the object is a single view object (if false point_cloud_ is considered to be complete)

Definition at line 227 of file object_model.h.

void pcl::ObjectModel::setName ( const std::string  name) [inline]

Set the name of the object.

Definition at line 225 of file object_model.h.

Recalculate the models center and radius, meaning the sphere that includes the complete object.

Definition at line 91 of file object_model.cpp.

void pcl::ObjectModel::updateValidationPoints ( unsigned int  no_of_surface_points = 50,
unsigned int  no_of_border_points = 25,
float  sample_resolution = deg2rad(20.0f),
NarfKeypoint *  interest_point_detector = NULL,
float  support_size = -1.0f 
)

Recalculates the validation points for the object.

Parameters:
no_of_surface_pointsmaximum size of the set of surface points
no_of_border_points_to_usemaximum size of the set of border points
sample_resolutionangular distance between the sampled views used to calculate the validation points
interest_point_detectorif !=NULL, the surface points will be selected from the interest points
support_sizeused for the interest point extraction

Definition at line 284 of file object_model.cpp.


Member Data Documentation

Definition at line 243 of file object_model.h.

int pcl::ObjectModel::id_ [protected]

Definition at line 237 of file object_model.h.

Definition at line 245 of file object_model.h.

std::string pcl::ObjectModel::name_ [protected]

Definition at line 238 of file object_model.h.

Definition at line 239 of file object_model.h.

Definition at line 244 of file object_model.h.

Definition at line 242 of file object_model.h.

std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> > pcl::ObjectModel::views_ [protected]

Definition at line 240 of file object_model.h.

std::vector<RangeImage, Eigen::aligned_allocator<RangeImage> > pcl::ObjectModel::views_for_validation_points_ [protected]

Definition at line 241 of file object_model.h.


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


chair_recognition
Author(s): Jan Metzger
autogenerated on Wed Dec 26 2012 15:54:48