A BoundingBoxRaw descriptor to compute the dimensions of the bounding box that encloses a neighborhood of points within a radius of the interest point/region. More...
#include <bounding_box_raw.h>
Public Member Functions | |
BoundingBoxRaw (double bbox_radius) | |
Instantiates the bounding box feature with the specified radius to define the neighborhood. | |
virtual void | clearShared () |
This descriptor uses no shared precomputation, so this method has no affect. | |
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 |
Computes the bounding box information of the given neighborhood. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const geometry_msgs::Point32 * > &interest_pts) |
This descriptor requires no pre-computation, so this method has no affect. | |
virtual int | precompute (const sensor_msgs::PointCloud &data, cloud_kdtree::KdTree &data_kdtree, const std::vector< const std::vector< int > * > &interest_region_indices) |
This descriptor requires no pre-computation, so this method has no affect. |
A BoundingBoxRaw descriptor to compute the dimensions of the bounding box that encloses a neighborhood of points within a radius of the interest point/region.
The compute features are in order: [dx,dy,dz] where dx is the length along the x dimension, dy is the length along the y dimension, dz is the length along the z dimension.
Definition at line 68 of file bounding_box_raw.h.
BoundingBoxRaw::BoundingBoxRaw | ( | double | bbox_radius | ) |
Instantiates the bounding box feature with the specified radius to define the neighborhood.
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 |
Definition at line 42 of file bounding_box_raw.cpp.
void BoundingBoxRaw::clearShared | ( | ) | [virtual] |
This descriptor uses no shared precomputation, so this method has no affect.
Implements Descriptor3D.
Definition at line 56 of file bounding_box_raw.cpp.
void BoundingBoxRaw::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] |
Computes the bounding box information of the given neighborhood.
data | The overall point cloud data |
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 94 of file bounding_box_raw.cpp.
std::string BoundingBoxRaw::getName | ( | void | ) | const [virtual] |
Returns a name that is unique for any given setting of the parameters.
Implements Descriptor3D.
Definition at line 63 of file bounding_box_raw.cpp.
int BoundingBoxRaw::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const geometry_msgs::Point32 * > & | interest_pts | ||
) | [protected, virtual] |
This descriptor requires no pre-computation, so this method has no affect.
Implements Descriptor3D.
Definition at line 74 of file bounding_box_raw.cpp.
int BoundingBoxRaw::precompute | ( | const sensor_msgs::PointCloud & | data, |
cloud_kdtree::KdTree & | data_kdtree, | ||
const std::vector< const std::vector< int > * > & | interest_region_indices | ||
) | [protected, virtual] |
This descriptor requires no pre-computation, so this method has no affect.
Implements Descriptor3D.
Definition at line 84 of file bounding_box_raw.cpp.