Point Cloud Library (PCL)
1.11.1-dev
|
39 #include <pcl/point_cloud.h>
57 template<
typename Po
intT>
112 radiusSearch (
const PointCloudConstPtr &cloud_arg,
int index_arg,
double radius_arg,
113 std::vector<int> &k_indices_arg, std::vector<float> &k_sqr_distances_arg,
114 int max_nn_arg = INT_MAX);
126 radiusSearch (
int index_arg,
const double radius_arg, std::vector<int> &k_indices_arg,
127 std::vector<float> &k_sqr_distances_arg,
int max_nn_arg = INT_MAX)
const;
138 radiusSearch (
const PointT &p_q_arg,
const double radius_arg, std::vector<int> &k_indices_arg,
139 std::vector<float> &k_sqr_distances_arg,
int max_nn_arg = INT_MAX)
const;
151 nearestKSearch (
const PointCloudConstPtr &cloud_arg,
int index_arg,
int k_arg, std::vector<int> &k_indices_arg,
152 std::vector<float> &k_sqr_distances_arg);
164 nearestKSearch (
int index_arg,
int k_arg, std::vector<int> &k_indices_arg,
165 std::vector<float> &k_sqr_distances_arg);
176 std::vector<float> &k_sqr_distances_arg);
315 return (
"Organized_Neighbor_Search");
OrganizedNeighborSearch()
OrganizedNeighborSearch constructor.
int radiusSearch(const PointCloudConstPtr &cloud_arg, int index_arg, double radius_arg, std::vector< int > &k_indices_arg, std::vector< float > &k_sqr_distances_arg, int max_nn_arg=INT_MAX)
Search for all neighbors of query point that are within a given radius.
void setMaxDistance(double max_dist)
Set the maximum allowed distance between the query point and its nearest neighbors.
radiusSearchLoopkupEntry entry for radius search lookup vector
~nearestNeighborCandidate()
Empty deconstructor
typename PointCloud::Ptr PointCloudPtr
double focalLength_
Global focal length parameter.
void getProjectedRadiusSearchBox(const PointT &point_arg, double squared_radius_arg, int &minX_arg, int &minY_arg, int &maxX_arg, int &maxY_arg) const
nearestNeighborCandidate entry for the nearest neighbor candidate queue
void estimateFocalLengthFromInputCloud()
Estimate focal length parameter that was used during point cloud generation.
nearestNeighborCandidate()
Empty constructor
PointCloud represents the base class in PCL for storing collections of 3D points.
bool operator<(const nearestNeighborCandidate &rhs_arg) const
Operator< for comparing nearestNeighborCandidate instances with each other.
A point structure representing Euclidean xyz coordinates, and the RGB color.
~radiusSearchLoopkupEntry()
Empty deconstructor
virtual std::string getName() const
Class getName method.
typename PointCloud::ConstPtr PointCloudConstPtr
void generateRadiusLookupTable(unsigned int width, unsigned int height)
Generate radius lookup table.
double getMaxDistance() const
Get the maximum allowed distance between the query point and its nearest neighbors.
int radiusLookupTableWidth_
OrganizedNeighborSearch class
virtual ~OrganizedNeighborSearch()
Empty deconstructor.
double max_distance_
Maximum allowed distance between the query point and its k-neighbors.
int radiusLookupTableHeight_
const PointT & getPointByIndex(const unsigned int index_arg) const
Get point at index from input pointcloud dataset.
void defineShiftedSearchPoint(int x_shift, int y_shift)
Define search point and calculate squared distance.
std::vector< radiusSearchLoopkupEntry > radiusSearchLookup_
Precalculated radius search lookup vector.
int nearestKSearch(const PointCloudConstPtr &cloud_arg, int index_arg, int k_arg, std::vector< int > &k_indices_arg, std::vector< float > &k_sqr_distances_arg)
Search for k-nearest neighbors at the query point.
__inline double pcl_round(double number)
Win32 doesn't seem to have rounding functions.
void setInputCloud(const PointCloudConstPtr &cloud_arg)
Provide a pointer to the input data set.
shared_ptr< PointCloud< PointT > > Ptr
void pointPlaneProjection(const PointT &point, int &xpos, int &ypos) const
PointCloudConstPtr input_
Pointer to input point cloud dataset.
shared_ptr< const PointCloud< PointT > > ConstPtr
radiusSearchLoopkupEntry()
Empty constructor
bool operator<(const radiusSearchLoopkupEntry &rhs_arg) const
Operator< for comparing radiusSearchLoopkupEntry instances with each other.