Descriptor3D is the abstract base class for all descriptors that operate on 3-D data. All inheriting classes define all necessary parameters in their constructor. Hence, after instantiation, all descriptors can compute feature values through the compute() method. The number of feature values the descriptor generates on success is given by getResultSize() More...
#include <descriptor_3d.h>
Public Member Functions | |
virtual void | clearShared ()=0 |
Clears the shared information this Descriptor3D is using so the information is computed from scratch on the next compute() call. | |
void | compute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< std::vector< float > > &results) |
Computes feature values for each specified interest point. | |
void | compute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< std::vector< float > > &results) |
Computes feature values for each interest region of points. | |
Descriptor3D () | |
Abstract constructor. | |
virtual std::string | getName () const =0 |
Returns a string that is unique for the current param settings. | |
unsigned int | getResultSize () const |
Returns the number of feature values this descriptor computes on success. | |
virtual | ~Descriptor3D ()=0 |
Static Public Member Functions | |
Utility methods | |
static unsigned int | computeAndConcatFeatures (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< Descriptor3D * > &descriptors_3d, std::vector< boost::shared_array< const float > > &concatenated_features) |
Utility function to compute multiple descriptor feature around interest points and concatenate the results into a single vector. | |
static unsigned int | computeAndConcatFeatures (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< Descriptor3D * > &descriptors_3d, std::vector< boost::shared_array< const float > > &concatenated_features) |
Utility function to compute multiple descriptor feature around interest regions and concatenate the results into a single vector. | |
Public Attributes | |
bool | debug_ |
Whether to display the features as they are computed. | |
Protected Member Functions | |
virtual void | doComputation (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts, std::vector< std::vector< float > > &results)=0 |
Does the actual computation after any pre-computations. | |
virtual void | doComputation (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices, std::vector< std::vector< float > > &results)=0 |
Does the actual computation after any pre-computations. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts)=0 |
Method to do any setup pre-computation necessary for the inheriting descriptor. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices)=0 |
Method to do any setup pre-computation necessary for the inheriting descriptor. | |
Protected Attributes | |
unsigned int | result_size_ |
The number of feature values the inheriting descriptor computes on success. | |
bool | result_size_defined_ |
Flag if the inheriting descriptor has defined the result size. | |
Static Private Member Functions | |
static void | concatenateFeatures (const std::vector< std::vector< std::vector< float > > > &all_descriptor_results, const unsigned int nbr_samples, const unsigned int nbr_concatenated_vals, std::vector< boost::shared_array< const float > > &concatenated_features) |
Concatenates the resulting feature descriptor values. |
Descriptor3D is the abstract base class for all descriptors that operate on 3-D data. All inheriting classes define all necessary parameters in their constructor. Hence, after instantiation, all descriptors can compute feature values through the compute() method. The number of feature values the descriptor generates on success is given by getResultSize()
Definition at line 72 of file descriptor_3d.h.
Abstract constructor.
Definition at line 42 of file descriptor_3d.cpp.
Descriptor3D::~Descriptor3D | ( | ) | [pure virtual] |
Definition at line 52 of file descriptor_3d.cpp.
virtual void Descriptor3D::clearShared | ( | ) | [pure virtual] |
Clears the shared information this Descriptor3D is using so the information is computed from scratch on the next compute() call.
Implemented in SpinImageCustom, SpinImageNormal, SpinImageTangent, BoundingBoxSpectral, BoundingBoxRaw, OrientationNormal, OrientationTangent, ShapeSpectral, Channel, Position, and Curvature.
void Descriptor3D::compute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts, | ||
std::vector< std::vector< float > > & | results | ||
) |
Computes feature values for each specified interest point.
See the inherited class constructor for the type of features computed and necessary parameters
data | Point cloud of the data |
data_kdtree | K-D tree representation of data |
interest_pts | List of interest points to compute features for |
results | Vector to hold computed vector of features for each interest point. If the features could not be computed for an interest point i, then results[i].size() == 0 |
Definition at line 60 of file descriptor_3d.cpp.
void Descriptor3D::compute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices, | ||
std::vector< std::vector< float > > & | results | ||
) |
Computes feature values for each interest region of points.
See the inherited class constructor for the type of features computed and necessary parameters
data | Point cloud of the data |
data_kdtree | K-D tree representation of data |
interest_region_indices | List of groups of indices into data that represent an interest region |
results | Vector to hold computed vector of features for each interest region. If the features could not be computed for an interest region i, then results[i].size() == 0 |
static unsigned int Descriptor3D::computeAndConcatFeatures | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts, | ||
std::vector< Descriptor3D * > & | descriptors_3d, | ||
std::vector< boost::shared_array< const float > > & | concatenated_features | ||
) | [static] |
Utility function to compute multiple descriptor feature around interest points and concatenate the results into a single vector.
This method clears out any pre-computed shared information among the descriptors before calculating the new features.
data | See Descriptor3D::compute |
data_kdtree | See Descriptor3D::compute |
interest_pts | See Descriptor3D::compute |
descriptors_3d | List of various feature descriptors to compute on each interest point |
concatenated_features | List containing the concatenated features from the descriptors if they were ALL successful for the interest point. If one descriptor failed for interest point i, then concatenated_features[i].get() == NULL |
static unsigned int Descriptor3D::computeAndConcatFeatures | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices, | ||
std::vector< Descriptor3D * > & | descriptors_3d, | ||
std::vector< boost::shared_array< const float > > & | concatenated_features | ||
) | [static] |
Utility function to compute multiple descriptor feature around interest regions and concatenate the results into a single vector.
This method clears out any pre-computed shared information among the descriptors before calculating the new features.
data | See Descriptor3D::compute |
data_kdtree | See Descriptor3D::compute |
interest_region_indices | See Descriptor3D::compute |
descriptors_3d | List of various feature descriptors to compute on each interest point |
concatenated_features | List containing the concatenated features from the descriptors if they were ALL successful for the interest region. If one descriptor failed for interest region i, then concatenated_features[i].get() == NULL |
void Descriptor3D::concatenateFeatures | ( | const std::vector< std::vector< std::vector< float > > > & | all_descriptor_results, |
const unsigned int | nbr_samples, | ||
const unsigned int | nbr_concatenated_vals, | ||
std::vector< boost::shared_array< const float > > & | concatenated_features | ||
) | [static, private] |
Concatenates the resulting feature descriptor values.
all_descriptor_results | The results for each descriptor |
nbr_samples | The number of interest points/regions |
nbr_concatenated_vals | The total length of all concatenated features from each descriptor |
concatenated_features | The concatenated features. NULL indicates could not successfully compute descriptor for sample |
Definition at line 116 of file descriptor_3d.cpp.
virtual void Descriptor3D::doComputation | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts, | ||
std::vector< std::vector< float > > & | results | ||
) | [protected, pure virtual] |
Does the actual computation after any pre-computations.
Implemented in Position, ShapeSpectral, Channel, Curvature, NeighborhoodFeature, and OrientationGeneric.
virtual void Descriptor3D::doComputation | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices, | ||
std::vector< std::vector< float > > & | results | ||
) | [protected, pure virtual] |
Does the actual computation after any pre-computations.
Implemented in Position, ShapeSpectral, Channel, Curvature, NeighborhoodFeature, and OrientationGeneric.
virtual std::string Descriptor3D::getName | ( | ) | const [pure virtual] |
Returns a string that is unique for the current param settings.
Implemented in SpinImageCustom, SpinImageNormal, SpinImageTangent, BoundingBoxSpectral, BoundingBoxRaw, OrientationNormal, OrientationTangent, Position, ShapeSpectral, Channel, and Curvature.
unsigned int Descriptor3D::getResultSize | ( | ) | const [inline] |
Returns the number of feature values this descriptor computes on success.
Definition at line 140 of file descriptor_3d.h.
virtual int Descriptor3D::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts | ||
) | [protected, pure virtual] |
Method to do any setup pre-computation necessary for the inheriting descriptor.
Example: estimating normals for each interest point.
data | Point cloud of the data |
data_kdtree | K-D tree representation of data |
interest_pts | List of interest points for feature computation |
Implemented in SpinImageCustom, SpinImageNormal, SpinImageTangent, BoundingBoxSpectral, BoundingBoxRaw, Position, OrientationNormal, OrientationTangent, ShapeSpectral, Channel, and Curvature.
virtual int Descriptor3D::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices | ||
) | [protected, pure virtual] |
Method to do any setup pre-computation necessary for the inheriting descriptor.
Example: estimating normals for each interest point.
data | Point cloud of the data |
data_kdtree | K-D tree representation of data |
interest_region_indices | List of groups of indices into data that represent an interest region for feature computation |
Implemented in SpinImageCustom, SpinImageNormal, SpinImageTangent, BoundingBoxSpectral, BoundingBoxRaw, Position, ShapeSpectral, OrientationNormal, OrientationTangent, Curvature, and Channel.
Whether to display the features as they are computed.
Definition at line 211 of file descriptor_3d.h.
unsigned int Descriptor3D::result_size_ [protected] |
The number of feature values the inheriting descriptor computes on success.
Definition at line 272 of file descriptor_3d.h.
bool Descriptor3D::result_size_defined_ [protected] |
Flag if the inheriting descriptor has defined the result size.
Definition at line 275 of file descriptor_3d.h.