40 #ifndef JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__ 
   41 #define JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__ 
   43 #include <boost/shared_ptr.hpp> 
   44 #include <dynamic_reconfigure/server.h> 
   45 #include <jsk_topic_tools/diagnostic_nodelet.h> 
   49 #include <sensor_msgs/PointCloud2.h> 
   50 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   51 #include <jsk_recognition_msgs/ClassificationResult.h> 
   52 #include <jsk_recognition_msgs/PolygonArray.h> 
   55 #include <jsk_pcl_ros/PrimitiveShapeClassifierConfig.h> 
   56 #include <pcl/point_types.h> 
   57 #include <pcl/point_cloud.h> 
   58 #include <pcl/ModelCoefficients.h> 
   62   class PrimitiveShapeClassifier : 
public jsk_topic_tools::DiagnosticNodelet
 
   66                                                       sensor_msgs::PointCloud2,
 
   67                                                       jsk_recognition_msgs::ClusterPointIndices,
 
   68                                                       jsk_recognition_msgs::PolygonArray> 
SyncPolicy;
 
   69     typedef PrimitiveShapeClassifierConfig 
Config;
 
   70     typedef pcl::PointXYZRGBA 
PointT;
 
   81     process(
const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
 
   82             const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
 
   83             const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
 
   84             const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
 
   87     estimate(
const pcl::PointCloud<PointT>::Ptr& cloud,
 
   88              const pcl::PointCloud<pcl::Normal>::Ptr& normal,
 
   89              const pcl::ModelCoefficients::Ptr& plane,
 
   90              pcl::PointIndices::Ptr& boundary_indices,
 
   91              pcl::PointCloud<PointT>::Ptr& projected_cloud,
 
   92              float& circle_likelihood,
 
   93              float& box_likelihood);
 
   97                     const std::vector<jsk_recognition_utils::Polygon::Ptr>& polygons,
 
   98                     pcl::ModelCoefficients::Ptr& coeff);
 
  101     checkFrameId(
const sensor_msgs::PointCloud2::ConstPtr& ros_cloud,
 
  102                  const sensor_msgs::PointCloud2::ConstPtr& ros_normal,
 
  103                  const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& ros_indices,
 
  104                  const jsk_recognition_msgs::PolygonArray::ConstPtr& ros_polygons);
 
  128 #endif // JSK_PCL_ROS_PRIMITIVE_SHAPE_CLASSIFIER_H__