36 #ifndef JSK_RECOGNITION_UTILS_GEO_CYLINDER_H_ 37 #define JSK_RECOGNITION_UTILS_GEO_CYLINDER_H_ 39 #include <Eigen/Geometry> 40 #include <pcl/point_cloud.h> 41 #include <pcl/PointIndices.h> 42 #include <pcl/point_types.h> 43 #include <visualization_msgs/Marker.h> 51 Cylinder(Eigen::Vector3f point, Eigen::Vector3f direction,
double radius);
54 const double threshold,
55 pcl::PointIndices& output);
57 const pcl::PointIndices& indices,
58 Eigen::Vector3f& center,
60 virtual void toMarker(visualization_msgs::Marker& marker,
61 const Eigen::Vector3f& center,
62 const Eigen::Vector3f& uz,
Cylinder(Eigen::Vector3f point, Eigen::Vector3f direction, double radius)
virtual void toMarker(visualization_msgs::Marker &marker, const Eigen::Vector3f ¢er, const Eigen::Vector3f &uz, const double height)
virtual Eigen::Vector3f getDirection()
virtual double getRadius()
boost::shared_ptr< Cylinder > Ptr
virtual void filterPointCloud(const pcl::PointCloud< pcl::PointXYZ > &cloud, const double threshold, pcl::PointIndices &output)
virtual void estimateCenterAndHeight(const pcl::PointCloud< pcl::PointXYZ > &cloud, const pcl::PointIndices &indices, Eigen::Vector3f ¢er, double &height)
Eigen::Vector3f direction_