37 #ifndef JSK_PCL_ROS_UTILS_PLANE_REASONER_H_
38 #define JSK_PCL_ROS_UTILS_PLANE_REASONER_H_
40 #include <jsk_topic_tools/diagnostic_nodelet.h>
41 #include "jsk_recognition_msgs/ClusterPointIndices.h"
42 #include "jsk_recognition_msgs/PolygonArray.h"
43 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
50 #include <dynamic_reconfigure/server.h>
51 #include "jsk_pcl_ros_utils/PlaneReasonerConfig.h"
57 typedef boost::tuple<pcl::PointIndices::Ptr,
58 pcl::ModelCoefficients::Ptr,
60 geometry_msgs::PolygonStamped>
63 class PlaneReasoner:
public jsk_topic_tools::DiagnosticNodelet
70 sensor_msgs::PointCloud2,
71 jsk_recognition_msgs::ClusterPointIndices,
72 jsk_recognition_msgs::ModelCoefficientsArray,
73 jsk_recognition_msgs::PolygonArray>
SyncPolicy;
74 typedef jsk_pcl_ros_utils::PlaneReasonerConfig
Config;
75 typedef pcl::PointXYZRGB
PointT;
92 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
93 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& inliers_msg,
94 const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg,
95 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons_msg);
99 virtual std::vector<PlaneInfoContainer>
100 packInfo(std::vector<pcl::PointIndices::Ptr>& inliers,
101 std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
102 std::vector<jsk_recognition_utils::Plane::Ptr>& planes,
103 std::vector<geometry_msgs::PolygonStamped>& polygons);
105 virtual std::vector<PlaneInfoContainer>
107 std::vector<PlaneInfoContainer>& infos);
109 virtual std::vector<PlaneInfoContainer>
111 std::vector<PlaneInfoContainer>& infos);
113 virtual std::vector<PlaneInfoContainer>
115 double reference_angle,
117 std::vector<PlaneInfoContainer>& infos);
120 std::vector<PlaneInfoContainer>& containers,
121 const std_msgs::Header& header,
122 pcl::PointCloud<PointT>::Ptr
cloud,