common.h File Reference

#include <pcl/pcl_base.h>
#include "Core"
#include <vector>
#include "src/StlSupport/StdVector.h"
#include <stdint.h>
#include <assert.h>
#include <stddef.h>
#include <string>
#include <cstdio>
#include <sstream>
#include <iostream>
#include <cmath>
#include <stdexcept>
#include "duration.h"
#include <sys/time.h>
#include <log4cxx/logger.h>
#include <boost/static_assert.hpp>
#include <cassert>
#include <map>
#include <set>
#include <list>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>
#include <ros/time.h>
#include "exceptions.h"
#include <boost/shared_array.hpp>
#include <boost/make_shared.hpp>
#include <ostream>
#include <ros/types.h>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include "ros/macros.h"
#include <boost/array.hpp>
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include "ros/builtin_message_traits.h"
#include "ros/assert.h"
#include <string.h>
#include "ros/serialization.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include <Eigen/StdVector>
#include "src/Core/util/DisableMSVCWarnings.h"
#include "SVD"
#include "LU"
#include <limits>
#include "src/Geometry/OrthoMethods.h"
#include "src/Geometry/EulerAngles.h"
#include "src/Core/util/EnableMSVCWarnings.h"
#include "pcl/ros_macros.h"
#include <std_msgs/Header.h>
#include <boost/fusion/sequence/intrinsic/at_key.hpp>
#include "pcl/pcl_base.h"
#include "pcl/PointIndices.h"
#include <sensor_msgs/PointField.h>
#include <sensor_msgs/PointCloud2.h>
#include "pcl/point_cloud.h"
#include <boost/type_traits/remove_all_extents.hpp>
#include <boost/type_traits/is_same.hpp>
#include <boost/mpl/assert.hpp>
#include <boost/mpl/is_sequence.hpp>
#include <boost/mpl/begin_end.hpp>
#include <boost/mpl/next_prior.hpp>
#include <boost/mpl/deref.hpp>
#include <boost/mpl/aux_/unwrap.hpp>
#include <boost/foreach.hpp>
#include <locale>
#include <cfloat>
#include "src/Core/util/Macros.h"
#include <cerrno>
#include <cstdlib>
#include <complex>
#include <functional>
#include <iosfwd>
#include <climits>
#include <algorithm>
#include "src/Core/util/Constants.h"
#include "src/Core/util/ForwardDeclarations.h"
#include "src/Core/util/Meta.h"
#include "src/Core/util/XprHelper.h"
#include "src/Core/util/StaticAssert.h"
#include "src/Core/util/Memory.h"
#include "src/Core/NumTraits.h"
#include "src/Core/MathFunctions.h"
#include "src/Core/GenericPacketMath.h"
#include "src/Core/arch/Default/Settings.h"
#include "src/Core/Functors.h"
#include "src/Core/DenseCoeffsBase.h"
#include "src/Core/DenseBase.h"
#include "src/Core/MatrixBase.h"
#include "src/Core/EigenBase.h"
#include "src/Core/Assign.h"
#include "src/Core/util/BlasUtil.h"
#include "src/Core/DenseStorage.h"
#include "src/Core/NestByValue.h"
#include "src/Core/ForceAlignedAccess.h"
#include "src/Core/ReturnByValue.h"
#include "src/Core/NoAlias.h"
#include "src/Core/PlainObjectBase.h"
#include "src/Core/Matrix.h"
#include "src/Core/Array.h"
#include "src/Core/CwiseBinaryOp.h"
#include "src/Core/CwiseUnaryOp.h"
#include "src/Core/CwiseNullaryOp.h"
#include "src/Core/CwiseUnaryView.h"
#include "src/Core/SelfCwiseBinaryOp.h"
#include "src/Core/Dot.h"
#include "src/Core/StableNorm.h"
#include "src/Core/MapBase.h"
#include "src/Core/Stride.h"
#include "src/Core/Map.h"
#include "src/Core/Block.h"
#include "src/Core/VectorBlock.h"
#include "src/Core/Transpose.h"
#include "src/Core/DiagonalMatrix.h"
#include "src/Core/Diagonal.h"
#include "src/Core/DiagonalProduct.h"
#include "src/Core/PermutationMatrix.h"
#include "src/Core/Transpositions.h"
#include "src/Core/Redux.h"
#include "src/Core/Visitor.h"
#include "src/Core/Fuzzy.h"
#include "src/Core/IO.h"
#include "src/Core/Swap.h"
#include "src/Core/CommaInitializer.h"
#include "src/Core/Flagged.h"
#include "src/Core/ProductBase.h"
#include "src/Core/Product.h"
#include "src/Core/TriangularMatrix.h"
#include "src/Core/SelfAdjointView.h"
#include "src/Core/SolveTriangular.h"
#include "src/Core/products/Parallelizer.h"
#include "src/Core/products/CoeffBasedProduct.h"
#include "src/Core/products/GeneralBlockPanelKernel.h"
#include "src/Core/products/GeneralMatrixVector.h"
#include "src/Core/products/GeneralMatrixMatrix.h"
#include "src/Core/products/GeneralMatrixMatrixTriangular.h"
#include "src/Core/products/SelfadjointMatrixVector.h"
#include "src/Core/products/SelfadjointMatrixMatrix.h"
#include "src/Core/products/SelfadjointProduct.h"
#include "src/Core/products/SelfadjointRank2Update.h"
#include "src/Core/products/TriangularMatrixVector.h"
#include "src/Core/products/TriangularMatrixMatrix.h"
#include "src/Core/products/TriangularSolverMatrix.h"
#include "src/Core/products/TriangularSolverVector.h"
#include "src/Core/BandMatrix.h"
#include "src/Core/BooleanRedux.h"
#include "src/Core/Select.h"
#include "src/Core/VectorwiseOp.h"
#include "src/Core/Random.h"
#include "src/Core/Replicate.h"
#include "src/Core/Reverse.h"
#include "src/Core/ArrayBase.h"
#include "src/Core/ArrayWrapper.h"
#include "src/Core/GlobalFunctions.h"
#include <bitset>
#include "pcl/ros/point_traits.h"
#include <boost/mpl/vector.hpp>
#include <boost/mpl/for_each.hpp>
#include <boost/preprocessor/seq/enum.hpp>
#include <boost/preprocessor/seq/for_each.hpp>
#include <boost/preprocessor/seq/transform.hpp>
#include <boost/preprocessor/cat.hpp>
#include <boost/preprocessor/repetition/repeat_from_to.hpp>
#include <boost/type_traits/is_pod.hpp>
#include "pcl/win32_macros.h"
#include <math.h>
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

namespace  pcl

Functions

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 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.
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.
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.
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.
void pcl::getMinMax (const sensor_msgs::PointCloud2 &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::getMinMax (const PointT &histogram, int len, 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, 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::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, 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, 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::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.
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines


pcl
Author(s): See http://pcl.ros.org/authors for the complete list of authors.
autogenerated on Fri Jan 11 09:55:27 2013