20 #ifndef SPACESAMPLEPOINT_HPP_ 21 #define SPACESAMPLEPOINT_HPP_ 23 #define PCL_NO_PRECOMPILE 25 #include <geometry_msgs/Pose.h> 27 #include <pcl/point_types.h> 28 #include <pcl/impl/point_types.hpp> 29 #include <pcl/search/search.h> 30 #include <pcl/search/organized.h> 31 #include <pcl/search/impl/organized.hpp> 32 #include <pcl/search/kdtree.h> 33 #include <pcl/search/impl/kdtree.hpp> 34 #include <pcl/kdtree/kdtree_flann.h> 35 #include <pcl/kdtree/impl/kdtree_flann.hpp> 36 #include <pcl/segmentation/conditional_euclidean_clustering.h> 37 #include <pcl/segmentation/impl/conditional_euclidean_clustering.hpp> 38 #include <pcl/pcl_base.h> 39 #include <pcl/impl/pcl_base.hpp> 61 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
boost::shared_ptr< SpaceSamplePoint > SpaceSamplePointPtr
SimpleVector3 getSimpleVector3() const
Eigen::Matrix< Precision, 3, 1 > SimpleVector3
SpaceSamplePoint(const SimpleVector3 &vector)
TFSIMD_FORCE_INLINE const tfScalar & y() const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SpaceSamplePoint(const gm::Pose &pose=gm::Pose())
this namespace contains all generally usable classes.
TFSIMD_FORCE_INLINE const tfScalar & x() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
struct next_best_view::DefaultViewportPoint EIGEN_ALIGN16
std::ostream & operator<<(std::ostream &strm, const next_best_view::DefaultViewportPoint &p)
gm::Point getPoint() const