Namespaces | Functions
common.h File Reference
#include <pcl/pcl_base.h>
#include <cfloat>
#include <pcl/common/impl/common.hpp>
Include dependency graph for common/include/pcl/common/common.h:

Go to the source code of this file.

Namespaces

namespace  pcl

Functions

template<typename PointT >
float pcl::calculatePolygonArea (const pcl::PointCloud< PointT > &polygon)
 Calculate the area of a polygon given a point cloud that defines the polygon.
double pcl::getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2)
 Compute the smallest angle between two vectors in the [ 0, PI ) interval in 3D.
template<typename PointT >
double pcl::getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc)
 Compute the radius of a circumscribed circle for a triangle formed of three points pa, pb, and pc.
template<typename PointT >
void pcl::getMaxDistance (const pcl::PointCloud< PointT > &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt)
 Get the point at maximum distance from a given point and a given pointcloud.
template<typename PointT >
void pcl::getMaxDistance (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt)
 Get the point at maximum distance from a given point and a given pointcloud.
void pcl::getMeanStd (const std::vector< float > &values, double &mean, double &stddev)
 Compute both the mean and the standard deviation of an array of values.
PCL_EXPORTS void pcl::getMeanStdDev (const std::vector< float > &values, double &mean, double &stddev)
 Compute both the mean and the standard deviation of an array of values.
template<typename PointT >
void pcl::getMinMax (const PointT &histogram, int len, float &min_p, float &max_p)
 Get the minimum and maximum values on a point histogram.
PCL_EXPORTS void pcl::getMinMax (const pcl::PCLPointCloud2 &cloud, int idx, const std::string &field_name, float &min_p, float &max_p)
 Get the minimum and maximum values on a point histogram.
template<typename PointT >
void pcl::getMinMax3D (const pcl::PointCloud< PointT > &cloud, PointT &min_pt, PointT &max_pt)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
template<typename PointT >
void pcl::getMinMax3D (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
template<typename PointT >
void pcl::getMinMax3D (const pcl::PointCloud< PointT > &cloud, const std::vector< int > &indices, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
template<typename PointT >
void pcl::getMinMax3D (const pcl::PointCloud< PointT > &cloud, const pcl::PointIndices &indices, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt)
 Get the minimum and maximum values on each of the 3 (x-y-z) dimensions in a given pointcloud.
template<typename PointT >
void pcl::getPointsInBox (const pcl::PointCloud< PointT > &cloud, Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt, std::vector< int > &indices)
 Get a set of points residing in a box given its bounds.

Detailed Description

Define standard C methods and C++ classes that are common to all methods

Definition in file common/include/pcl/common/common.h.



pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:38:44