cluster_point_indices_decomposer_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: C++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_pcl_ros/cluster_point_indices_decomposer.h"
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <pluginlib/class_list_macros.h>
00039 #include <pcl/filters/extract_indices.h>
00040 #include <pcl/common/centroid.h>
00041 #include <pcl/common/common.h>
00042 #include <boost/format.hpp>
00043 #include <boost/range/adaptors.hpp>
00044 #include <boost/range/algorithm.hpp>
00045 #include <boost/range/irange.hpp>
00046 #include <pcl/registration/ia_ransac.h>
00047 #include <pcl/filters/project_inliers.h>
00048 #include <pcl/common/pca.h>
00049 #include <sensor_msgs/image_encodings.h>
00050 #include <jsk_topic_tools/color_utils.h>
00051 #include <Eigen/Geometry> 
00052 #include <geometry_msgs/PoseArray.h>
00053 
00054 #include "jsk_recognition_utils/geo_util.h"
00055 #include "jsk_recognition_utils/pcl_conversion_util.h"
00056 #include "jsk_recognition_utils/pcl_util.h"
00057 
00058 namespace jsk_pcl_ros
00059 {
00060   void ClusterPointIndicesDecomposerZAxis::onInit()
00061   {
00062     ClusterPointIndicesDecomposer::onInit();
00063     sort_by_ = "z_axis";
00064   }
00065 
00066   void ClusterPointIndicesDecomposer::onInit()
00067   {
00068     DiagnosticNodelet::onInit();
00069     pnh_->param("publish_tf", publish_tf_, false);
00070     if (publish_tf_) {
00071       br_.reset(new tf::TransformBroadcaster);
00072     }
00073     if (!pnh_->getParam("tf_prefix", tf_prefix_))
00074     {
00075       if (publish_tf_) {
00076         ROS_WARN("~tf_prefix is not specified, using %s", getName().c_str());
00077       }
00078       tf_prefix_ = getName();
00079     }
00080 
00081     // fixed parameters
00082     pnh_->param("approximate_sync", use_async_, false);
00083     pnh_->param("queue_size", queue_size_, 100);
00084     pnh_->param("publish_clouds", publish_clouds_, false);
00085     if (publish_clouds_) {
00086       ROS_WARN("~output%%02d are not published before subscribed, you should subscribe ~debug_output in debuging.");
00087     }
00088     pnh_->param("align_boxes", align_boxes_, false);
00089     if (align_boxes_) {
00090       pnh_->param("align_boxes_with_plane", align_boxes_with_plane_, true);
00091     }
00092     if (align_boxes_ && !align_boxes_with_plane_) {
00093       tf_listener_ = jsk_recognition_utils::TfListenerSingleton::getInstance();
00094       if (!pnh_->getParam("target_frame_id", target_frame_id_)) {
00095         ROS_FATAL("~target_frame_id is not specified");
00096         return;
00097       }
00098       ROS_INFO("Aligning bboxes with '%s' using tf transform.", target_frame_id_.c_str());
00099     }
00100     pnh_->param("use_pca", use_pca_, false);
00101     pnh_->param("force_to_flip_z_axis", force_to_flip_z_axis_, true);
00102     pnh_->param<std::string>("sort_by", sort_by_, "input_indices");
00103     // dynamic_reconfigure
00104     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
00105     dynamic_reconfigure::Server<Config>::CallbackType f =
00106       boost::bind(&ClusterPointIndicesDecomposer::configCallback, this, _1, _2);
00107     srv_->setCallback(f);
00108 
00109     negative_indices_pub_ = advertise<pcl_msgs::PointIndices>(*pnh_, "negative_indices", 1);
00110     pc_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "debug_output", 1);
00111     box_pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, "boxes", 1);
00112     mask_pub_ = advertise<sensor_msgs::Image>(*pnh_, "mask", 1);
00113     label_pub_ = advertise<sensor_msgs::Image>(*pnh_, "label", 1);
00114     centers_pub_ = advertise<geometry_msgs::PoseArray>(*pnh_, "centroid_pose_array", 1);
00115     indices_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "cluster_indices", 1);
00116 
00117     onInitPostProcess();
00118   }
00119 
00120   void ClusterPointIndicesDecomposer::configCallback(Config &config, uint32_t level)
00121   {
00122     boost::mutex::scoped_lock(mutex_);
00123     max_size_ = config.max_size;
00124     min_size_ = config.min_size;
00125   }
00126 
00127   void ClusterPointIndicesDecomposer::subscribe()
00128   {
00129     sub_input_.subscribe(*pnh_, "input", 1);
00130     sub_target_.subscribe(*pnh_, "target", 1);
00131     if (align_boxes_ && align_boxes_with_plane_) {
00132       sync_align_ = boost::make_shared<message_filters::Synchronizer<SyncAlignPolicy> >(queue_size_);
00133       sub_polygons_.subscribe(*pnh_, "align_planes", 1);
00134       sub_coefficients_.subscribe(*pnh_, "align_planes_coefficients", 1);
00135       sync_align_->connectInput(sub_input_, sub_target_, sub_polygons_, sub_coefficients_);
00136       sync_align_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2, _3, _4));
00137     }
00138     else if (use_async_) {
00139       async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00140       async_->connectInput(sub_input_, sub_target_);
00141       async_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
00142     }
00143     else {
00144       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00145       sync_->connectInput(sub_input_, sub_target_);
00146       sync_->registerCallback(boost::bind(&ClusterPointIndicesDecomposer::extract, this, _1, _2));
00147     }
00148   }
00149 
00150   void ClusterPointIndicesDecomposer::unsubscribe()
00151   {
00152     sub_input_.unsubscribe();
00153     sub_target_.unsubscribe();
00154     if (align_boxes_ && align_boxes_with_plane_) {
00155       sub_polygons_.unsubscribe();
00156       sub_coefficients_.unsubscribe();
00157     }
00158   }
00159 
00160   void ClusterPointIndicesDecomposer::sortIndicesOrder(
00161     const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00162     const std::vector<pcl::IndicesPtr> indices_array,
00163     std::vector<size_t>* argsort)
00164   {
00165     std::string sort_by = sort_by_;
00166     bool reverse = false;
00167     if (sort_by.compare(0, 1, "-") == 0)
00168     {
00169       reverse = true;
00170       sort_by = sort_by.substr(1, sort_by.size() - 1);
00171     }
00172     if (sort_by == "input_indices")
00173     {
00174       sortIndicesOrderByIndices(input, indices_array, argsort);
00175     }
00176     else if (sort_by == "z_axis")
00177     {
00178       sortIndicesOrderByZAxis(input, indices_array, argsort);
00179     }
00180     else if (sort_by == "cloud_size")
00181     {
00182       sortIndicesOrderByCloudSize(input, indices_array, argsort);
00183     }
00184     else
00185     {
00186       NODELET_WARN_ONCE("Unsupported ~sort_by param is specified '%s', "
00187                         "so using the default: 'input_indices'", sort_by_.c_str());
00188       sortIndicesOrderByIndices(input, indices_array, argsort);
00189       return;
00190     }
00191     if (reverse)
00192     {
00193       std::reverse((*argsort).begin(), (*argsort).end());
00194     }
00195   }
00196 
00197   void ClusterPointIndicesDecomposer::sortIndicesOrderByIndices(
00198     const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00199     const std::vector<pcl::IndicesPtr> indices_array,
00200     std::vector<size_t>* argsort)
00201   {
00202     (*argsort).resize(indices_array.size());
00203     for (size_t i = 0; i < indices_array.size(); i++)
00204     {
00205       (*argsort)[i] = i;
00206     }
00207   }
00208 
00209   void ClusterPointIndicesDecomposer::sortIndicesOrderByZAxis(
00210     const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00211     const std::vector<pcl::IndicesPtr> indices_array,
00212     std::vector<size_t>* argsort)
00213   {
00214     std::vector<double> z_values;
00215     pcl::ExtractIndices<pcl::PointXYZ> ex;
00216     ex.setInputCloud(input);
00217     for (size_t i = 0; i < indices_array.size(); i++)
00218     {
00219       Eigen::Vector4f center;
00220       ex.setIndices(indices_array[i]);
00221       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00222       ex.filter(*cloud);
00223       //
00224       std::vector<int> nan_indices;
00225       pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
00226       //
00227       pcl::compute3DCentroid(*cloud, center);
00228       z_values.push_back(center[2]); // only focus on z value
00229     }
00230 
00231     // sort centroids
00232     // https://stackoverflow.com/a/12399290
00233     (*argsort).resize(indices_array.size());
00234     std::iota(argsort->begin(), argsort->end(), 0);
00235     std::sort(argsort->begin(), argsort->end(),
00236               [&z_values](size_t i1, size_t i2) {return z_values[i1] < z_values[i2];});
00237   }
00238 
00239   void ClusterPointIndicesDecomposer::sortIndicesOrderByCloudSize(
00240     const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
00241     const std::vector<pcl::IndicesPtr> indices_array,
00242     std::vector<size_t>* argsort)
00243   {
00244     std::vector<double> cloud_sizes;
00245     pcl::ExtractIndices<pcl::PointXYZ> ex;
00246     ex.setInputCloud(input);
00247     for (size_t i = 0; i < indices_array.size(); i++)
00248     {
00249       Eigen::Vector4f center;
00250       ex.setIndices(indices_array[i]);
00251       pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
00252       ex.filter(*cloud);
00253       //
00254       std::vector<int> nan_indices;
00255       pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
00256       //
00257       double cloud_size = static_cast<double>(cloud->points.size());
00258       cloud_sizes.push_back(cloud_size);
00259     }
00260 
00261     // sort clouds
00262     (*argsort).resize(indices_array.size());
00263     std::iota(argsort->begin(), argsort->end(), 0);
00264     std::sort(argsort->begin(), argsort->end(),
00265               [&cloud_sizes](size_t i1, size_t i2) {return cloud_sizes[i1] < cloud_sizes[i2];});
00266   }
00267 
00268   void ClusterPointIndicesDecomposer::updateDiagnostic(
00269     diagnostic_updater::DiagnosticStatusWrapper &stat)
00270   {
00271     if (vital_checker_->isAlive()) {
00272       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00273                    "ClusterPointIndicesDecomposer running");
00274       jsk_topic_tools::addDiagnosticBooleanStat(
00275         "publish_clouds", publish_clouds_, stat);
00276       jsk_topic_tools::addDiagnosticBooleanStat(
00277         "publish_tf", publish_tf_, stat);
00278       jsk_topic_tools::addDiagnosticBooleanStat(
00279         "use_pca", use_pca_, stat);
00280       jsk_topic_tools::addDiagnosticBooleanStat(
00281         "align_boxes", align_boxes_, stat);
00282       stat.add("tf_prefix", tf_prefix_);
00283       stat.add("Clusters (Ave.)", cluster_counter_.mean());
00284     }
00285     else {
00286       jsk_topic_tools::addDiagnosticErrorSummary(
00287         "ClusterPointIndicesDecomposer", vital_checker_, stat);
00288     }
00289   }
00290   
00291   int ClusterPointIndicesDecomposer::findNearestPlane(
00292     const Eigen::Vector4f& center,
00293     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00294     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
00295   {
00296     double min_distance = DBL_MAX;
00297     int nearest_index = -1;
00298     for (size_t i = 0; i < coefficients->coefficients.size(); i++) {
00299       geometry_msgs::PolygonStamped polygon_msg = planes->polygons[i];
00300       jsk_recognition_utils::Vertices vertices;
00301       for (size_t j = 0; j < polygon_msg.polygon.points.size(); j++) {
00302         jsk_recognition_utils::Vertex v;
00303         v[0] = polygon_msg.polygon.points[j].x;
00304         v[1] = polygon_msg.polygon.points[j].y;
00305         v[2] = polygon_msg.polygon.points[j].z;
00306         vertices.push_back(v);
00307       }
00308       jsk_recognition_utils::ConvexPolygon p(vertices, coefficients->coefficients[i].values);
00309       double distance = p.distanceToPoint(center);
00310       if (distance < min_distance) {
00311         min_distance = distance;
00312         nearest_index = i;
00313       }
00314     }
00315     return nearest_index;
00316   }
00317 
00318   bool ClusterPointIndicesDecomposer::transformPointCloudToAlignWithPlane(
00319     const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00320     pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud_transformed,
00321     const Eigen::Vector4f center,
00322     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00323     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
00324     Eigen::Matrix4f& m4,
00325     Eigen::Quaternionf& q)
00326   {
00327     int nearest_plane_index = findNearestPlane(center, planes, coefficients);
00328     if (nearest_plane_index == -1) {
00329       segmented_cloud_transformed = segmented_cloud;
00330       NODELET_ERROR("no planes to align boxes are given");
00331     }
00332     else {
00333       Eigen::Vector3f normal, z_axis;
00334       if (force_to_flip_z_axis_) {
00335         normal[0] = - coefficients->coefficients[nearest_plane_index].values[0];
00336         normal[1] = - coefficients->coefficients[nearest_plane_index].values[1];
00337         normal[2] = - coefficients->coefficients[nearest_plane_index].values[2];
00338       }
00339       else {
00340         normal[0] = coefficients->coefficients[nearest_plane_index].values[0];
00341         normal[1] = coefficients->coefficients[nearest_plane_index].values[1];
00342         normal[2] = coefficients->coefficients[nearest_plane_index].values[2];
00343       }
00344       normal = normal.normalized();
00345       Eigen::Quaternionf rot;
00346       rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), normal);
00347       Eigen::AngleAxisf rotation_angle_axis(rot);
00348       Eigen::Vector3f rotation_axis = rotation_angle_axis.axis();
00349       double theta = rotation_angle_axis.angle();
00350       if (std::isnan(theta) ||
00351           std::isnan(rotation_axis[0]) ||
00352           std::isnan(rotation_axis[1]) ||
00353           std::isnan(rotation_axis[2])) {
00354         segmented_cloud_transformed = segmented_cloud;
00355         NODELET_ERROR("cannot compute angle to align the point cloud: [%f, %f, %f], [%f, %f, %f]",
00356                       z_axis[0], z_axis[1], z_axis[2],
00357                       normal[0], normal[1], normal[2]);
00358       }
00359       else {
00360         Eigen::Matrix3f m = Eigen::Matrix3f::Identity() * rot;
00361         if (use_pca_) {
00362           // first project points to the plane
00363           pcl::PointCloud<pcl::PointXYZRGB>::Ptr projected_cloud
00364             (new pcl::PointCloud<pcl::PointXYZRGB>);
00365           pcl::ProjectInliers<pcl::PointXYZRGB> proj;
00366           proj.setModelType (pcl::SACMODEL_PLANE);
00367           pcl::ModelCoefficients::Ptr
00368             plane_coefficients (new pcl::ModelCoefficients);
00369           plane_coefficients->values
00370             = coefficients->coefficients[nearest_plane_index].values;
00371           proj.setModelCoefficients(plane_coefficients);
00372           proj.setInputCloud(segmented_cloud);
00373           proj.filter(*projected_cloud);
00374           if (projected_cloud->points.size() >= 3) {
00375             pcl::PCA<pcl::PointXYZRGB> pca;
00376             pca.setInputCloud(projected_cloud);
00377             Eigen::Matrix3f eigen = pca.getEigenVectors();
00378             m.col(0) = eigen.col(0);
00379             m.col(1) = eigen.col(1);
00380             // flip axis to satisfy right-handed system
00381             if (m.col(0).cross(m.col(1)).dot(m.col(2)) < 0) {
00382               m.col(0) = - m.col(0);
00383             }
00384             if (m.col(0).dot(Eigen::Vector3f::UnitX()) < 0) {
00385               // rotate around z
00386               m = m * Eigen::AngleAxisf(M_PI, Eigen::Vector3f::UnitZ());
00387             }
00388           }
00389           else {
00390             NODELET_ERROR("Too small indices for PCA computation");
00391             return false;
00392           }
00393         }
00394         // m4 <- m
00395         for (size_t row = 0; row < 3; row++) {
00396           for (size_t column = 0; column < 3; column++) {
00397             m4(row, column) = m(row, column);
00398           }
00399         }
00400         q = m;
00401         q.normalize();
00402         Eigen::Matrix4f inv_m = m4.inverse();
00403         pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, inv_m);
00404       }
00405     }
00406     return true;
00407   }
00408 
00409   bool ClusterPointIndicesDecomposer::computeCenterAndBoundingBox
00410   (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00411    const std_msgs::Header header,
00412    const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00413    const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
00414    geometry_msgs::Pose& center_pose_msg,
00415    jsk_recognition_msgs::BoundingBox& bounding_box)
00416   {
00417     bounding_box.header = header;
00418 
00419     bool is_center_valid = false;
00420     Eigen::Vector4f center;
00421     pcl::PointCloud<pcl::PointXYZRGB>::Ptr
00422       segmented_cloud_transformed (new pcl::PointCloud<pcl::PointXYZRGB>);
00423     // align boxes if possible
00424     Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();
00425     Eigen::Quaternionf q = Eigen::Quaternionf::Identity();
00426     if (align_boxes_) {
00427       if (align_boxes_with_plane_) {
00428         is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
00429         bool success = transformPointCloudToAlignWithPlane(segmented_cloud, segmented_cloud_transformed,
00430                                                            center, planes, coefficients, m4, q);
00431         if (!success) {
00432           return false;
00433         }
00434       }
00435       else {
00436         // transform point cloud to target frame
00437         tf::StampedTransform tf_transform;
00438         try {
00439           tf_transform = jsk_recognition_utils::lookupTransformWithDuration(
00440             /*listener=*/tf_listener_,
00441             /*to_frame=*/header.frame_id,                // box origin
00442             /*from_frame=*/target_frame_id_,  // sensor origin
00443             /*time=*/header.stamp,
00444             /*duration=*/ros::Duration(1.0));
00445         }
00446         catch (tf2::TransformException &e) {
00447           NODELET_ERROR("Transform error: %s", e.what());
00448           return false;
00449         }
00450         Eigen::Affine3f transform;
00451         tf::transformTFToEigen(tf_transform, transform);
00452         pcl::transformPointCloud(*segmented_cloud, *segmented_cloud, transform);
00453 
00454         is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
00455 
00456         // compute planes from target frame
00457         pcl::PointXYZRGB min_pt, max_pt;
00458         pcl::getMinMax3D(*segmented_cloud, min_pt, max_pt);
00459         //
00460         pcl_msgs::ModelCoefficients coef_by_frame;
00461         coef_by_frame.values.push_back(0);
00462         coef_by_frame.values.push_back(0);
00463         coef_by_frame.values.push_back(1);
00464         coef_by_frame.values.push_back(- min_pt.z);
00465         jsk_recognition_msgs::ModelCoefficientsArray::Ptr coefficients_by_frame(
00466           new jsk_recognition_msgs::ModelCoefficientsArray);
00467         coefficients_by_frame->header.frame_id = target_frame_id_;
00468         coefficients_by_frame->coefficients.push_back(coef_by_frame);
00469         //
00470         geometry_msgs::PolygonStamped plane_by_frame;
00471         plane_by_frame.header.frame_id = target_frame_id_;
00472         geometry_msgs::Point32 point;
00473         point.z = min_pt.z;
00474         point.x = min_pt.x;
00475         point.y = min_pt.y;
00476         plane_by_frame.polygon.points.push_back(point);
00477         point.x = max_pt.x;
00478         point.y = min_pt.y;
00479         plane_by_frame.polygon.points.push_back(point);
00480         point.x = max_pt.x;
00481         point.y = max_pt.y;
00482         plane_by_frame.polygon.points.push_back(point);
00483         point.x = min_pt.x;
00484         point.y = max_pt.y;
00485         plane_by_frame.polygon.points.push_back(point);
00486         jsk_recognition_msgs::PolygonArray::Ptr planes_by_frame(
00487           new jsk_recognition_msgs::PolygonArray);
00488         planes_by_frame->header.frame_id = target_frame_id_;
00489         planes_by_frame->polygons.push_back(plane_by_frame);
00490         //
00491         bool success = transformPointCloudToAlignWithPlane(segmented_cloud, segmented_cloud_transformed,
00492                                                            center, planes_by_frame, coefficients_by_frame, m4, q);
00493         if (!success) {
00494           return false;
00495         }
00496       }
00497     }
00498     else {
00499       segmented_cloud_transformed = segmented_cloud;
00500       is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
00501     }
00502       
00503     // create a bounding box
00504     Eigen::Vector4f minpt, maxpt;
00505     pcl::getMinMax3D<pcl::PointXYZRGB>(*segmented_cloud_transformed, minpt, maxpt);
00506 
00507     double xwidth = maxpt[0] - minpt[0];
00508     double ywidth = maxpt[1] - minpt[1];
00509     double zwidth = maxpt[2] - minpt[2];
00510     if (!pcl_isfinite(xwidth) || !pcl_isfinite(ywidth) || !pcl_isfinite(zwidth))
00511     {
00512       // all points in cloud are nan or its size is 0
00513       xwidth = ywidth = zwidth = 0;
00514     }
00515     
00516     Eigen::Vector4f center2((maxpt[0] + minpt[0]) / 2.0, (maxpt[1] + minpt[1]) / 2.0, (maxpt[2] + minpt[2]) / 2.0, 1.0);
00517     Eigen::Vector4f center_transformed = m4 * center2;
00518       
00519     // set centroid pose msg
00520     if (is_center_valid) {
00521       center_pose_msg.position.x = center[0];
00522       center_pose_msg.position.y = center[1];
00523       center_pose_msg.position.z = center[2];
00524       center_pose_msg.orientation.x = 0;
00525       center_pose_msg.orientation.y = 0;
00526       center_pose_msg.orientation.z = 0;
00527       center_pose_msg.orientation.w = 1;
00528     }
00529     else {
00530       // set invalid pose for invalid center
00531       center_pose_msg = geometry_msgs::Pose();
00532     }
00533     
00534     // set bounding_box msg
00535     bounding_box.pose.position.x = center_transformed[0];
00536     bounding_box.pose.position.y = center_transformed[1];
00537     bounding_box.pose.position.z = center_transformed[2];
00538     bounding_box.pose.orientation.x = q.x();
00539     bounding_box.pose.orientation.y = q.y();
00540     bounding_box.pose.orientation.z = q.z();
00541     bounding_box.pose.orientation.w = q.w();
00542     bounding_box.dimensions.x = xwidth;
00543     bounding_box.dimensions.y = ywidth;
00544     bounding_box.dimensions.z = zwidth;
00545     return true;
00546   }
00547 
00548   void ClusterPointIndicesDecomposer::addToDebugPointCloud
00549   (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
00550    size_t i,
00551    pcl::PointCloud<pcl::PointXYZRGB>& debug_output)
00552   {
00553     uint32_t rgb = colorRGBAToUInt32(jsk_topic_tools::colorCategory20(i));
00554     for (size_t j = 0; j < segmented_cloud->points.size(); j++) {
00555       pcl::PointXYZRGB p;
00556       p.x= segmented_cloud->points[j].x;
00557       p.y= segmented_cloud->points[j].y;
00558       p.z= segmented_cloud->points[j].z;
00559       p.rgb = *reinterpret_cast<float*>(&rgb);
00560       debug_output.points.push_back(p);
00561     }
00562   }
00563 
00564   void ClusterPointIndicesDecomposer::publishNegativeIndices(
00565     const sensor_msgs::PointCloud2ConstPtr &input,
00566     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
00567   {
00568     std::set<int> all_indices;
00569     boost::copy(
00570       boost::irange(0, (int)(input->width * input->height)),
00571       std::inserter(all_indices, all_indices.begin()));
00572     for (size_t i = 0; i < indices_input->cluster_indices.size(); i++) {
00573       std::set<int> indices_set(indices_input->cluster_indices[i].indices.begin(),
00574                                 indices_input->cluster_indices[i].indices.end());
00575       std::set<int> diff_indices;
00576       std::set_difference(all_indices.begin(), all_indices.end(),
00577                           indices_set.begin(), indices_set.end(),
00578                           std::inserter(diff_indices, diff_indices.begin()));
00579       all_indices = diff_indices;
00580     }
00581     // publish all_indices
00582     pcl_msgs::PointIndices ros_indices;
00583     ros_indices.indices = std::vector<int>(all_indices.begin(), all_indices.end());
00584     ros_indices.header = input->header;
00585     negative_indices_pub_.publish(ros_indices);
00586   }
00587     
00588   void ClusterPointIndicesDecomposer::extract(
00589     const sensor_msgs::PointCloud2ConstPtr &input,
00590     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input,
00591     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
00592     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
00593   {
00594     vital_checker_->poke();
00595     if (publish_clouds_) {
00596       allocatePublishers(indices_input->cluster_indices.size());
00597     }
00598     publishNegativeIndices(input, indices_input);
00599     pcl::ExtractIndices<pcl::PointXYZRGB> extract;
00600     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00601     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_xyz (new pcl::PointCloud<pcl::PointXYZ>);
00602     pcl::fromROSMsg(*input, *cloud);
00603     pcl::fromROSMsg(*input, *cloud_xyz);
00604     cluster_counter_.add(indices_input->cluster_indices.size());
00605     
00606     std::vector<pcl::IndicesPtr> converted_indices;
00607     
00608     for (size_t i = 0; i < indices_input->cluster_indices.size(); i++)
00609     {
00610       pcl::IndicesPtr vindices;
00611       // skip indices with points size
00612       if (min_size_ > 0 &&
00613           indices_input->cluster_indices[i].indices.size() < min_size_) {
00614         vindices.reset (new std::vector<int> ());
00615         converted_indices.push_back(vindices);
00616         continue;
00617       }
00618       if (max_size_ > 0 &&
00619           indices_input->cluster_indices[i].indices.size() > max_size_) {
00620         vindices.reset (new std::vector<int> ());
00621         converted_indices.push_back(vindices);
00622         continue;
00623       }
00624       vindices.reset (new std::vector<int> (indices_input->cluster_indices[i].indices));
00625       converted_indices.push_back(vindices);
00626     }
00627 
00628     std::vector<size_t> argsort;
00629     sortIndicesOrder(cloud_xyz, converted_indices, &argsort);
00630     extract.setInputCloud(cloud);
00631 
00632     // point cloud from camera not laser
00633     bool is_sensed_with_camera = (input->height != 1);
00634 
00635     cv::Mat mask = cv::Mat::zeros(input->height, input->width, CV_8UC1);
00636     cv::Mat label = cv::Mat::zeros(input->height, input->width, CV_32SC1);
00637     pcl::PointCloud<pcl::PointXYZRGB> debug_output;
00638     jsk_recognition_msgs::BoundingBoxArray bounding_box_array;
00639     jsk_recognition_msgs::ClusterPointIndices out_cluster_indices;
00640     bounding_box_array.header = input->header;
00641     geometry_msgs::PoseArray center_pose_array;
00642     center_pose_array.header = input->header;
00643     out_cluster_indices.header = input->header;
00644     for (size_t i = 0; i < argsort.size(); i++)
00645     {
00646       pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud (new pcl::PointCloud<pcl::PointXYZRGB>);
00647       
00648       pcl_msgs::PointIndices out_indices_msg;
00649       out_indices_msg.header = input->header;
00650       out_indices_msg.indices = *(converted_indices[argsort[i]]);
00651       out_cluster_indices.cluster_indices.push_back(out_indices_msg);
00652 
00653       pcl::PointIndices::Ptr segmented_indices (new pcl::PointIndices);
00654       extract.setIndices(converted_indices[argsort[i]]);
00655       extract.filter(*segmented_cloud);
00656       if (publish_clouds_) {
00657         sensor_msgs::PointCloud2::Ptr out_cloud(new sensor_msgs::PointCloud2);
00658         pcl::toROSMsg(*segmented_cloud, *out_cloud);
00659         out_cloud->header = input->header;
00660         publishers_[i].publish(out_cloud);
00661       }
00662       // label
00663       if (is_sensed_with_camera) {
00664         // create mask & label image from cluster indices
00665         for (size_t j = 0; j < converted_indices[argsort[i]]->size(); j++) {
00666           int index = converted_indices[argsort[i]]->data()[j];
00667           int width_index = index % input->width;
00668           int height_index = index / input->width;
00669           mask.at<uchar>(height_index, width_index) = 255;
00670           // 0 should be skipped,
00671           // because it is to label image as the black region is to mask image
00672           label.at<int>(height_index, width_index) = (int)i + 1;
00673         }
00674       }
00675       // adding the pointcloud into debug_output
00676       addToDebugPointCloud(segmented_cloud, i, debug_output);
00677 
00678       // compute centoid and bounding box
00679       geometry_msgs::Pose pose_msg;
00680       jsk_recognition_msgs::BoundingBox bounding_box;
00681       bounding_box.label = static_cast<int>(argsort[i]);
00682       bool successp = computeCenterAndBoundingBox(
00683         segmented_cloud, input->header, planes, coefficients, pose_msg, bounding_box);
00684       if (!successp) {
00685         return;
00686       }
00687       std::string target_frame;
00688       if (align_boxes_ && !align_boxes_with_plane_) {
00689         target_frame = target_frame_id_;
00690       }
00691       else {
00692         target_frame = input->header.frame_id;
00693       }
00694       center_pose_array.poses.push_back(pose_msg);
00695       bounding_box.header.frame_id = target_frame;
00696       bounding_box_array.boxes.push_back(bounding_box);
00697       if (publish_tf_) {
00698         tf::Transform transform;
00699         transform.setOrigin(tf::Vector3(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z));
00700         transform.setRotation(tf::createIdentityQuaternion());
00701         br_->sendTransform(tf::StampedTransform(transform, input->header.stamp, target_frame,
00702                                                 tf_prefix_ + (boost::format("output%02u") % (i)).str()));
00703       }
00704     }
00705 
00706     // Both bounding box and centroid are computed with transformed point cloud for the target frame.
00707     if (align_boxes_ && !align_boxes_with_plane_) {
00708       bounding_box_array.header.frame_id = target_frame_id_;
00709       center_pose_array.header.frame_id = target_frame_id_;
00710     }
00711 
00712     if (is_sensed_with_camera) {
00713       // publish mask
00714       cv_bridge::CvImage mask_bridge(indices_input->header,
00715                                     sensor_msgs::image_encodings::MONO8,
00716                                     mask);
00717       mask_pub_.publish(mask_bridge.toImageMsg());
00718       // publish label
00719       cv_bridge::CvImage label_bridge(indices_input->header,
00720                                       sensor_msgs::image_encodings::TYPE_32SC1,
00721                                       label);
00722       label_pub_.publish(label_bridge.toImageMsg());
00723     }
00724     
00725     sensor_msgs::PointCloud2 debug_ros_output;
00726     pcl::toROSMsg(debug_output, debug_ros_output);
00727     debug_ros_output.header = input->header;
00728     debug_ros_output.is_dense = false;
00729     pc_pub_.publish(debug_ros_output);
00730     centers_pub_.publish(center_pose_array);
00731     box_pub_.publish(bounding_box_array);
00732     indices_pub_.publish(out_cluster_indices);
00733   }
00734   
00735   void ClusterPointIndicesDecomposer::extract
00736   (const sensor_msgs::PointCloud2ConstPtr &input,
00737    const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
00738   {
00739     extract(input, indices_input,
00740             jsk_recognition_msgs::PolygonArrayConstPtr(),
00741             jsk_recognition_msgs::ModelCoefficientsArrayConstPtr());
00742   }
00743 
00744   void ClusterPointIndicesDecomposer::allocatePublishers(size_t num)
00745   {
00746     if (num > publishers_.size())
00747     {
00748         for (size_t i = publishers_.size(); i < num; i++)
00749         {
00750             std::string topic_name = (boost::format("output%02u") % (i)).str();
00751             ROS_INFO("advertising %s", topic_name.c_str());
00752             ros::Publisher publisher = pnh_->advertise<sensor_msgs::PointCloud2>(topic_name, 1);
00753             publishers_.push_back(publisher);
00754         }
00755     }
00756   }
00757 
00758 }  // namespace jsk_pcl_ros
00759 
00760 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ClusterPointIndicesDecomposer, nodelet::Nodelet);
00761 // TODO: deprecate below export. because sorting by z_axis is achieved in parent class with sort_by_ = "z_axis"
00762 PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::ClusterPointIndicesDecomposerZAxis, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:49