37 #ifndef JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
38 #define JSK_PCL_ROS_MULTI_PLANE_SEGMENTATION_H_
44 #include <dynamic_reconfigure/server.h>
50 #include <jsk_pcl_ros/MultiPlaneSACSegmentationConfig.h>
51 #include <jsk_topic_tools/connection_based_nodelet.h>
58 #include <sensor_msgs/PointCloud2.h>
59 #include <jsk_recognition_msgs/PolygonArray.h>
60 #include <jsk_recognition_msgs/ModelCoefficientsArray.h>
61 #include <jsk_recognition_msgs/ClusterPointIndices.h>
62 #include <sensor_msgs/Imu.h>
66 class MultiPlaneSACSegmentation:
public jsk_topic_tools::ConnectionBasedNodelet
69 typedef pcl::PointXYZRGB
PointT;
70 typedef jsk_pcl_ros::MultiPlaneSACSegmentationConfig
Config;
72 sensor_msgs::PointCloud2,
75 sensor_msgs::PointCloud2,
78 sensor_msgs::PointCloud2,
82 sensor_msgs::PointCloud2,
83 sensor_msgs::PointCloud2,
95 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg);
96 virtual void segment(
const sensor_msgs::PointCloud2::ConstPtr&
msg,
97 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal);
99 const sensor_msgs::Imu::ConstPtr& imu);
101 const sensor_msgs::PointCloud2::ConstPtr& msg_nromal,
102 const sensor_msgs::Imu::ConstPtr& imu);
104 const sensor_msgs::PointCloud2::ConstPtr&
msg,
105 const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& clusters);
107 const pcl::PointCloud<PointT>::Ptr&
input,
108 const pcl::PointCloud<pcl::Normal>::Ptr& normal,
109 const Eigen::Vector3f& imu_vector,
110 std::vector<pcl::PointIndices::Ptr>& output_inliers,
111 std::vector<pcl::ModelCoefficients::Ptr>& output_coefficients,
112 std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& output_polygons);
114 const std_msgs::Header&
header,
115 const std::vector<pcl::PointIndices::Ptr>& inliers,
116 const std::vector<pcl::ModelCoefficients::Ptr>& coefficients,
117 const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes);