Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_COMMON_H_
00039 #define PCL_COMMON_H_
00040
00041 #include <pcl/pcl_base.h>
00042 #include <cfloat>
00043
00051 namespace pcl
00052 {
00059 inline double
00060 getAngle3D (const Eigen::Vector4f &v1, const Eigen::Vector4f &v2);
00061
00068 inline void
00069 getMeanStd (const std::vector<float> &values, double &mean, double &stddev);
00070
00078 template <typename PointT> inline void
00079 getPointsInBox (const pcl::PointCloud<PointT> &cloud, Eigen::Vector4f &min_pt,
00080 Eigen::Vector4f &max_pt, std::vector<int> &indices);
00081
00088 template<typename PointT> inline void
00089 getMaxDistance (const pcl::PointCloud<PointT> &cloud, const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt);
00090
00098 template<typename PointT> inline void
00099 getMaxDistance (const pcl::PointCloud<PointT> &cloud, const std::vector<int> &indices,
00100 const Eigen::Vector4f &pivot_pt, Eigen::Vector4f &max_pt);
00101
00108 template <typename PointT> inline void
00109 getMinMax3D (const pcl::PointCloud<PointT> &cloud, PointT &min_pt, PointT &max_pt);
00110
00117 template <typename PointT> inline void
00118 getMinMax3D (const pcl::PointCloud<PointT> &cloud,
00119 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
00120
00128 template <typename PointT> inline void
00129 getMinMax3D (const pcl::PointCloud<PointT> &cloud, const std::vector<int> &indices,
00130 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
00131
00139 template <typename PointT> inline void
00140 getMinMax3D (const pcl::PointCloud<PointT> &cloud, const pcl::PointIndices &indices,
00141 Eigen::Vector4f &min_pt, Eigen::Vector4f &max_pt);
00142
00150 template <typename PointT> inline double
00151 getCircumcircleRadius (const PointT &pa, const PointT &pb, const PointT &pc);
00152
00160 template <typename PointT> inline void
00161 getMinMax (const PointT &histogram, int len, float &min_p, float &max_p);
00162
00171 PCL_EXPORTS void
00172 getMinMax (const sensor_msgs::PointCloud2 &cloud, int idx, const std::string &field_name,
00173 float &min_p, float &max_p);
00174
00181 PCL_EXPORTS void
00182 getMeanStdDev (const std::vector<float> &values, double &mean, double &stddev);
00183
00184 }
00186 #include <pcl/common/impl/common.hpp>
00187
00188 #endif //#ifndef PCL_COMMON_H_