A BoundingBoxSpectral descriptor to compute the dimensions of the bounding box in principle component space that encloses a neighborhood of points within a radius of the interest point/region. More...
#include <bounding_box_spectral.h>
Public Member Functions | |
BoundingBoxSpectral (double bbox_radius, SpectralAnalysis &spectral_information) | |
Instantiates the bounding box feature with the specified radius to define the neighborhood and spectral information. | |
virtual void | clearShared () |
Clears any already-computed spectral information. | |
std::string | getName () const |
Returns a name that is unique for any given setting of the parameters. | |
Protected Member Functions | |
virtual void | computeNeighborhoodFeature (const sensor_msgs::PointCloud &data, const std::vector< int > &neighbor_indices, const unsigned int interest_sample_idx, std::vector< float > &result) const |
Projects the given neighborhood in principle component space and then computes its bounding box. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts) |
Computes the spectral information (eigenvectors), necessary to project the points into principle component space. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices) |
Computes the spectral information (eigenvectors), necessary to project the points into principle component space. | |
Private Attributes | |
const std::vector< const Eigen3::Vector3d * > * | eig_vecs_max_ |
The biggest eigenvector for each interest point/region. | |
const std::vector< const Eigen3::Vector3d * > * | eig_vecs_mid_ |
The middle eigenvector for each interest point/region. | |
const std::vector< const Eigen3::Vector3d * > * | eig_vecs_min_ |
The smallest eigenvector for each interest point/region. | |
SpectralAnalysis * | spectral_information_ |
The container the holds spectral information for the point cloud. |
A BoundingBoxSpectral descriptor to compute the dimensions of the bounding box in principle component space that encloses a neighborhood of points within a radius of the interest point/region.
The compute features are in order: [a,b,c] where a is the length along the principle eigenvector, b is the length along the middle eigenvector, and c is the length along the smallest eigenvector.
Definition at line 70 of file bounding_box_spectral.h.
BoundingBoxSpectral::BoundingBoxSpectral | ( | double | bbox_radius, |
SpectralAnalysis & | spectral_information | ||
) |
Instantiates the bounding box feature with the specified radius to define the neighborhood and spectral information.
When computing the feature for an interest region of points, the bounding box can either be the box that encloses the given region of points (indicated by -negative value), or from the neighboring points within the specified radius from the region's centroid (indicated by positive value).
bbox_radius | The radius from the interest point/region to define the neighborhood that defines the bounding box |
spectral_information | Class to retrieve spectral information for the point cloud during Descriptor3D::compute() |
Definition at line 42 of file bounding_box_spectral.cpp.
void BoundingBoxSpectral::clearShared | ( | ) | [virtual] |
Clears any already-computed spectral information.
Implements Descriptor3D.
Definition at line 59 of file bounding_box_spectral.cpp.
void BoundingBoxSpectral::computeNeighborhoodFeature | ( | const sensor_msgs::PointCloud & | data, |
const std::vector< int > & | neighbor_indices, | ||
const unsigned int | interest_sample_idx, | ||
std::vector< float > & | result | ||
) | const [protected, virtual] |
Projects the given neighborhood in principle component space and then computes its bounding box.
data | The point cloud to process from Descriptor3D::compute() |
neighbor_indices | The list of indices in data that constitute the neighborhood |
interest_sample_idx | The index of the interest point/region that is being processed from Descriptor3D::compute() |
result | The vector to hold the computed bounding box dimensions |
Implements NeighborhoodFeature.
Definition at line 148 of file bounding_box_spectral.cpp.
std::string BoundingBoxSpectral::getName | ( | void | ) | const [virtual] |
Returns a name that is unique for any given setting of the parameters.
Implements Descriptor3D.
Definition at line 67 of file bounding_box_spectral.cpp.
int BoundingBoxSpectral::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts | ||
) | [protected, virtual] |
Computes the spectral information (eigenvectors), necessary to project the points into principle component space.
data | The point cloud to process from Descriptor3D::compute() |
data_kdtree | The efficient neighborhood data structure |
interest_pts | The list of interest points to be processed |
Implements Descriptor3D.
Definition at line 78 of file bounding_box_spectral.cpp.
int BoundingBoxSpectral::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices | ||
) | [protected, virtual] |
Computes the spectral information (eigenvectors), necessary to project the points into principle component space.
data | The point cloud to process from Descriptor3D::compute() |
data_kdtree | The efficient neighborhood data structure |
interest_pts | The list of interest regions to be processed |
Implements Descriptor3D.
Definition at line 112 of file bounding_box_spectral.cpp.
const std::vector<const Eigen3::Vector3d*>* BoundingBoxSpectral::eig_vecs_max_ [private] |
The biggest eigenvector for each interest point/region.
Definition at line 166 of file bounding_box_spectral.h.
const std::vector<const Eigen3::Vector3d*>* BoundingBoxSpectral::eig_vecs_mid_ [private] |
The middle eigenvector for each interest point/region.
Definition at line 163 of file bounding_box_spectral.h.
const std::vector<const Eigen3::Vector3d*>* BoundingBoxSpectral::eig_vecs_min_ [private] |
The smallest eigenvector for each interest point/region.
Definition at line 160 of file bounding_box_spectral.h.
The container the holds spectral information for the point cloud.
Definition at line 169 of file bounding_box_spectral.h.