38 #include <pcl/filters/extract_indices.h> 
   39 #include <pcl/segmentation/extract_polygonal_prism_data.h> 
   41 #include <jsk_topic_tools/log_utils.h> 
   42 #include <pcl/filters/project_inliers.h> 
   51     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
 
   52     DiagnosticNodelet::onInit();
 
   58     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"output", 1);
 
   59     nonplane_pub_ = advertise<pcl::PointCloud<pcl::PointXYZRGB> >(*pnh_, 
"output_nonplane_cloud", 1);
 
   60     pub_indices_ = advertise<PCLIndicesMsg>(*pnh_, 
"output/indices", 1);
 
   66       pnh_->param(
"sensor_frame", 
sensor_frame_, std::string(
"head_root"));
 
   69         NODELET_WARN(
"'~use_sensor_frame' and '~use_coefficients' cannot be enabled at the same time." 
   70                      " disabled '~use_coefficients'");
 
   74       NODELET_WARN(
"'~use_coefficients' and '~use_sensor_frame' are both disabled." 
   75                    " Normal axes of planes are estimated with PCA" 
   76                    " and they may be flipped unintentionally.");
 
   82     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   83     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   85     srv_->setCallback (
f);
 
  194     if (vital_checker_->isAlive()) {
 
  195       stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
 
  196                    "MultiPlaneExtraction running");
 
  201     DiagnosticNodelet::updateDiagnostic(stat);
 
  205     const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
 
  207     jsk_recognition_msgs::ClusterPointIndices indices;
 
  209     indices.cluster_indices.resize(
polygons->polygons.size());
 
  211       boost::make_shared<jsk_recognition_msgs::ClusterPointIndices>(indices));
 
  215     const jsk_recognition_msgs::PolygonArray::ConstPtr &polygons)
 
  217     jsk_recognition_msgs::ModelCoefficientsArray coeffs;
 
  219     coeffs.coefficients.resize(
polygons->polygons.size());
 
  221       boost::make_shared<jsk_recognition_msgs::ModelCoefficientsArray>(coeffs));
 
  225                                      const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices,
 
  226                                      const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients,
 
  227                                      const jsk_recognition_msgs::PolygonArray::ConstPtr& polygons)
 
  230     vital_checker_->poke();
 
  233                                              indices->header.frame_id) ||
 
  238       std::ostringstream oss;
 
  239       oss << 
"frame id does not match. cloud: " << 
input->header.frame_id
 
  240           << 
", polygons: " << 
polygons->header.frame_id;
 
  242         oss << 
", indices: " << indices->header.frame_id;
 
  245         oss << 
", coefficients: " << 
coefficients->header.frame_id;
 
  252     Eigen::Vector3f viewpoint = Eigen::Vector3f::Zero();
 
  257                                         input->header.frame_id,
 
  261         Eigen::Affine3f sensor_pose;
 
  263         viewpoint = Eigen::Vector3f(sensor_pose.translation());
 
  280     pcl::PointCloud<pcl::PointXYZRGB>::Ptr input_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>());
 
  281     pcl::PointCloud<pcl::PointXYZRGB>::Ptr nonplane_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>());
 
  285       pcl::PointIndices::Ptr all_indices (
new pcl::PointIndices);
 
  286       for (
size_t i = 0; 
i < indices->cluster_indices.size(); 
i++) {
 
  287         std::vector<int> one_indices = indices->cluster_indices[
i].indices;
 
  288         for (
size_t j = 0; j < one_indices.size(); j++) {
 
  289           all_indices->indices.push_back(one_indices[j]);
 
  294       pcl::ExtractIndices<pcl::PointXYZRGB> extract_nonplane;
 
  295       extract_nonplane.setNegative(
true);
 
  297       extract_nonplane.setInputCloud(input_cloud);
 
  298       extract_nonplane.setIndices(all_indices);
 
  299       extract_nonplane.filter(*nonplane_cloud);
 
  300       sensor_msgs::PointCloud2 ros_result;
 
  302       ros_result.header = 
input->header;
 
  306       nonplane_cloud = input_cloud;
 
  311     std::set<int> result_set;
 
  313     for (
size_t plane_i = 0; plane_i < 
polygons->polygons.size(); plane_i++) {
 
  316         for (
size_t vec_i = 0; vec_i < 3; ++vec_i)
 
  317           viewpoint[vec_i] = 
coefficients->coefficients[plane_i].values[vec_i];
 
  319       pcl::ExtractPolygonalPrismData<pcl::PointXYZRGB> prism_extract;
 
  320       prism_extract.setViewPoint(viewpoint[0], viewpoint[1], viewpoint[2]);
 
  321       pcl::PointCloud<pcl::PointXYZRGB>::Ptr hull_cloud(
new pcl::PointCloud<pcl::PointXYZRGB>());
 
  322       geometry_msgs::Polygon the_polygon = 
polygons->polygons[plane_i].polygon;
 
  323       if (the_polygon.points.size() <= 2) {
 
  328       Eigen::Vector3f centroid(0, 0, 0);
 
  329       for (
size_t i = 0; 
i < the_polygon.points.size(); 
i++) {
 
  331         jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
 
  332           the_polygon.points[i], p);
 
  333         centroid = centroid + 
p.getVector3fMap();
 
  335       centroid = centroid / the_polygon.points.size();
 
  337       for (
size_t i = 0; 
i < the_polygon.points.size(); 
i++) {
 
  339         jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
 
  340           the_polygon.points[i], p);
 
  341         Eigen::Vector3f dir = (
p.getVector3fMap() - centroid).normalized();
 
  342         p.getVector3fMap() = dir * 
magnify_ + 
p.getVector3fMap();
 
  343         hull_cloud->points.push_back(p);
 
  346       pcl::PointXYZRGB p_last;
 
  347         jsk_recognition_utils::pointFromXYZToXYZ<geometry_msgs::Point32, pcl::PointXYZRGB>(
 
  348           the_polygon.points[0], p_last);
 
  349       hull_cloud->points.push_back(p_last);
 
  351       prism_extract.setInputCloud(nonplane_cloud);
 
  353       prism_extract.setInputPlanarHull(hull_cloud);
 
  354       pcl::PointIndices output_indices;
 
  355       prism_extract.segment(output_indices);
 
  357       for (
size_t i = 0; 
i < output_indices.indices.size(); 
i++) {
 
  358         result_set.insert(output_indices.indices[i]);
 
  364     pcl::PointCloud<pcl::PointXYZRGB> result_cloud;
 
  365     pcl::PointIndices::Ptr all_result_indices (
new pcl::PointIndices());
 
  366     for (std::set<int>::iterator it = result_set.begin();
 
  367          it != result_set.end();
 
  369       all_result_indices->indices.push_back(*it);
 
  372     pcl::ExtractIndices<pcl::PointXYZRGB> extract_all_indices;
 
  374     extract_all_indices.setInputCloud(nonplane_cloud);
 
  375     extract_all_indices.setIndices(all_result_indices);
 
  376     extract_all_indices.filter(result_cloud);
 
  378     sensor_msgs::PointCloud2 ros_result;
 
  380     ros_result.header = 
input->header;
 
  384     ros_indices.header = 
input->header;
 
  386     diagnostic_updater_->update();