39 #include <pcl/filters/extract_indices.h> 
   40 #include <pcl/common/centroid.h> 
   41 #include <pcl/common/common.h> 
   42 #include <boost/format.hpp> 
   43 #include <boost/range/adaptors.hpp> 
   44 #include <boost/range/algorithm.hpp> 
   45 #include <boost/range/irange.hpp> 
   46 #include <pcl/registration/ia_ransac.h> 
   47 #include <pcl/filters/project_inliers.h> 
   48 #include <pcl/common/pca.h> 
   50 #include <jsk_topic_tools/color_utils.h> 
   51 #include <Eigen/Geometry>  
   52 #include <geometry_msgs/PoseArray.h> 
   82     DiagnosticNodelet::onInit();
 
   96     pnh_->param(
"approximate_sync", 
use_async_, 
false);
 
  100       NODELET_WARN(
"~output%%02d are not published before subscribed, you should subscribe ~debug_output in debuging.");
 
  105     } 
else if (pnh_->hasParam(
"align_boxes_with_plane")) {
 
  106       NODELET_WARN(
"Rosparam ~align_boxes_with_plane is used only with ~align_boxes:=true, so ignoring it.");
 
  115     } 
else if (pnh_->hasParam(
"target_frame_id")) {
 
  116       NODELET_WARN(
"Rosparam ~target_frame_id is used only with ~align_boxes:=true and ~align_boxes_with_plane:=true, so ignoring it.");
 
  119     pnh_->param<std::string>(
"sort_by", 
sort_by_, 
"input_indices");
 
  121     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> >(*pnh_);
 
  122     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  124     srv_->setCallback(
f);
 
  127     pc_pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, 
"debug_output", 1);
 
  128     box_pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, 
"boxes", 1);
 
  129     mask_pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"mask", 1);
 
  130     label_pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"label", 1);
 
  131     centers_pub_ = advertise<geometry_msgs::PoseArray>(*pnh_, 
"centroid_pose_array", 1);
 
  132     indices_pub_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, 
"cluster_indices", 1);
 
  139     boost::mutex::scoped_lock(
mutex_);
 
  166         async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
 
  171         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
 
  189     const pcl::PointCloud<pcl::PointXYZ>::Ptr 
input,
 
  190     const std::vector<pcl::IndicesPtr> indices_array,
 
  191     std::vector<size_t>* argsort)
 
  194     bool reverse = 
false;
 
  195     if (sort_by.compare(0, 1, 
"-") == 0)
 
  198       sort_by = sort_by.substr(1, sort_by.size() - 1);
 
  200     if (sort_by == 
"input_indices")
 
  204     else if (sort_by == 
"z_axis")
 
  208     else if (sort_by == 
"cloud_size")
 
  215                         "so using the default: 'input_indices'", 
sort_by_.c_str());
 
  221       std::reverse((*argsort).begin(), (*argsort).end());
 
  226     const pcl::PointCloud<pcl::PointXYZ>::Ptr 
input,
 
  227     const std::vector<pcl::IndicesPtr> indices_array,
 
  228     std::vector<size_t>* argsort)
 
  230     (*argsort).resize(indices_array.size());
 
  231     for (
size_t i = 0; 
i < indices_array.size(); 
i++)
 
  238     const pcl::PointCloud<pcl::PointXYZ>::Ptr 
input,
 
  239     const std::vector<pcl::IndicesPtr> indices_array,
 
  240     std::vector<size_t>* argsort)
 
  242     std::vector<double> z_values;
 
  243     pcl::ExtractIndices<pcl::PointXYZ> 
ex;
 
  245     for (
size_t i = 0; 
i < indices_array.size(); 
i++)
 
  247       Eigen::Vector4f center;
 
  248       ex.setIndices(indices_array[i]);
 
  249       pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  252       std::vector<int> nan_indices;
 
  253       pcl::removeNaNFromPointCloud(*cloud, *cloud, nan_indices);
 
  255       pcl::compute3DCentroid(*cloud, center);
 
  256       z_values.push_back(center[2]); 
 
  261     (*argsort).resize(indices_array.size());
 
  262     std::iota(argsort->begin(), argsort->end(), 0);
 
  263     std::sort(argsort->begin(), argsort->end(),
 
  264               [&z_values](
size_t i1, 
size_t i2) {return z_values[i1] < z_values[i2];});
 
  268     const pcl::PointCloud<pcl::PointXYZ>::Ptr 
input,
 
  269     const std::vector<pcl::IndicesPtr> indices_array,
 
  270     std::vector<size_t>* argsort)
 
  272     std::vector<double> cloud_sizes;
 
  273     pcl::ExtractIndices<pcl::PointXYZ> 
ex;
 
  275     for (
size_t i = 0; 
i < indices_array.size(); 
i++)
 
  277       Eigen::Vector4f center;
 
  278       ex.setIndices(indices_array[
i]);
 
  279       pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud(
new pcl::PointCloud<pcl::PointXYZ>);
 
  282       std::vector<int> nan_indices;
 
  283       pcl::removeNaNFromPointCloud(*
cloud, *
cloud, nan_indices);
 
  285       double cloud_size = 
static_cast<double>(
cloud->points.size());
 
  286       cloud_sizes.push_back(cloud_size);
 
  290     (*argsort).resize(indices_array.size());
 
  291     std::iota(argsort->begin(), argsort->end(), 0);
 
  292     std::sort(argsort->begin(), argsort->end(),
 
  293               [&cloud_sizes](
size_t i1, 
size_t i2) {return cloud_sizes[i1] < cloud_sizes[i2];});
 
  299     if (vital_checker_->isAlive()) {
 
  300       stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
 
  301                    "ClusterPointIndicesDecomposer running");
 
  302       jsk_topic_tools::addDiagnosticBooleanStat(
 
  304       jsk_topic_tools::addDiagnosticBooleanStat(
 
  306       jsk_topic_tools::addDiagnosticBooleanStat(
 
  308       jsk_topic_tools::addDiagnosticBooleanStat(
 
  313     DiagnosticNodelet::updateDiagnostic(stat);
 
  317     const Eigen::Vector4f& center,
 
  318     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  319     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
 
  321     double min_distance = DBL_MAX;
 
  322     int nearest_index = -1;
 
  324       geometry_msgs::PolygonStamped 
polygon_msg = planes->polygons[
i];
 
  326       for (
size_t j = 0; j < 
polygon_msg.polygon.points.size(); j++) {
 
  331         vertices.push_back(v);
 
  334       double distance = 
p.distanceToPoint(center);
 
  335       if (distance < min_distance) {
 
  340     return nearest_index;
 
  344     const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  345     pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud_transformed,
 
  346     const Eigen::Vector4f center,
 
  347     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  348     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
 
  350     Eigen::Quaternionf& q,
 
  351     int& nearest_plane_index)
 
  354     if (nearest_plane_index == -1) {
 
  355       segmented_cloud_transformed = segmented_cloud;
 
  359       Eigen::Vector3f normal, 
z_axis;
 
  361         normal[0] = - 
coefficients->coefficients[nearest_plane_index].values[0];
 
  362         normal[1] = - 
coefficients->coefficients[nearest_plane_index].values[1];
 
  363         normal[2] = - 
coefficients->coefficients[nearest_plane_index].values[2];
 
  366         normal[0] = 
coefficients->coefficients[nearest_plane_index].values[0];
 
  367         normal[1] = 
coefficients->coefficients[nearest_plane_index].values[1];
 
  368         normal[2] = 
coefficients->coefficients[nearest_plane_index].values[2];
 
  370       normal = normal.normalized();
 
  371       Eigen::Quaternionf 
rot;
 
  372       rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), normal);
 
  373       Eigen::AngleAxisf rotation_angle_axis(
rot);
 
  374       Eigen::Vector3f rotation_axis = rotation_angle_axis.axis();
 
  375       double theta = rotation_angle_axis.angle();
 
  376       if (std::isnan(theta) ||
 
  377           std::isnan(rotation_axis[0]) ||
 
  378           std::isnan(rotation_axis[1]) ||
 
  379           std::isnan(rotation_axis[2])) {
 
  380         segmented_cloud_transformed = segmented_cloud;
 
  381         NODELET_ERROR(
"cannot compute angle to align the point cloud: [%f, %f, %f], [%f, %f, %f]",
 
  383                       normal[0], normal[1], normal[2]);
 
  386         Eigen::Matrix3f 
m = Eigen::Matrix3f::Identity() * 
rot;
 
  389           pcl::PointCloud<pcl::PointXYZ>::Ptr projected_cloud
 
  390             (
new pcl::PointCloud<pcl::PointXYZ>);
 
  391           pcl::ProjectInliers<pcl::PointXYZ> proj;
 
  392           proj.setModelType (pcl::SACMODEL_PLANE);
 
  393           pcl::ModelCoefficients::Ptr
 
  394             plane_coefficients (
new pcl::ModelCoefficients);
 
  395           plane_coefficients->values
 
  396             = 
coefficients->coefficients[nearest_plane_index].values;
 
  397           proj.setModelCoefficients(plane_coefficients);
 
  398           proj.setInputCloud(segmented_cloud);
 
  399           proj.filter(*projected_cloud);
 
  400           if (projected_cloud->points.size() >= 3) {
 
  401             pcl::PCA<pcl::PointXYZ> pca;
 
  402             pca.setInputCloud(projected_cloud);
 
  403             Eigen::Matrix3f 
eigen = pca.getEigenVectors();
 
  407             if (
m.col(0).cross(
m.col(1)).dot(
m.col(2)) < 0) {
 
  408               m.col(0) = - 
m.col(0);
 
  410             if (
m.col(0).dot(Eigen::Vector3f::UnitX()) < 0) {
 
  412               m = 
m * Eigen::AngleAxisf(M_PI, Eigen::Vector3f::UnitZ());
 
  421         for (
size_t row = 0; row < 3; row++) {
 
  422           for (
size_t column = 0; column < 3; column++) {
 
  423             m4(row, column) = 
m(row, column);
 
  428         Eigen::Matrix4f inv_m = m4.inverse();
 
  429         pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, inv_m);
 
  436 #if __cplusplus >= 201103L 
  437 #define pcl_isfinite(x) std::isfinite(x) 
  441   (
const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  442    const std_msgs::Header 
header,
 
  443    const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  444    const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
 
  445    geometry_msgs::Pose& center_pose_msg,
 
  446    jsk_recognition_msgs::BoundingBox& bounding_box,
 
  449     bounding_box.header = 
header;
 
  450     if (segmented_cloud->points.size() == 0) {
 
  456     bool is_center_valid = 
false;
 
  457     Eigen::Vector4f center;
 
  458     pcl::PointCloud<pcl::PointXYZ>::Ptr
 
  459       segmented_cloud_transformed (
new pcl::PointCloud<pcl::PointXYZ>);
 
  460     segmented_cloud_transformed->is_dense = segmented_cloud->is_dense;
 
  462     Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();
 
  463     Eigen::Quaternionf 
q = Eigen::Quaternionf::Identity();
 
  464     int nearest_plane_index = 0;
 
  467         is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
 
  469                                                            center, planes, coefficients, m4, q,
 
  470                                                            nearest_plane_index);
 
  492         pcl::transformPointCloud(*segmented_cloud, *segmented_cloud, transform);
 
  494         is_center_valid = pcl::compute3DCentroid(*segmented_cloud, center) != 0;
 
  497         pcl::PointXYZ min_pt, max_pt;
 
  498         pcl::getMinMax3D(*segmented_cloud, min_pt, max_pt);
 
  500         pcl_msgs::ModelCoefficients coef_by_frame;
 
  501         coef_by_frame.values.push_back(0);
 
  502         coef_by_frame.values.push_back(0);
 
  503         coef_by_frame.values.push_back(1);
 
  504         coef_by_frame.values.push_back(- min_pt.z);
 
  505         jsk_recognition_msgs::ModelCoefficientsArray::Ptr coefficients_by_frame(
 
  506           new jsk_recognition_msgs::ModelCoefficientsArray);
 
  508         coefficients_by_frame->coefficients.push_back(coef_by_frame);
 
  510         geometry_msgs::PolygonStamped plane_by_frame;
 
  512         geometry_msgs::Point32 
point;
 
  516         plane_by_frame.polygon.points.push_back(
point);
 
  519         plane_by_frame.polygon.points.push_back(
point);
 
  522         plane_by_frame.polygon.points.push_back(
point);
 
  525         plane_by_frame.polygon.points.push_back(
point);
 
  526         jsk_recognition_msgs::PolygonArray::Ptr planes_by_frame(
 
  527           new jsk_recognition_msgs::PolygonArray);
 
  529         planes_by_frame->polygons.push_back(plane_by_frame);
 
  532                                                            center, planes_by_frame, coefficients_by_frame, m4, q,
 
  533                                                            nearest_plane_index);
 
  541         if (segmented_cloud->points.size() >= 3) {
 
  542           Eigen::Vector4f pca_centroid;
 
  543           pcl::compute3DCentroid(*segmented_cloud, pca_centroid);
 
  544           Eigen::Matrix3f covariance;
 
  545           pcl::computeCovarianceMatrixNormalized(*segmented_cloud, pca_centroid, covariance);
 
  546           Eigen::SelfAdjointEigenSolver<Eigen::Matrix3f> eigen_solver(covariance, Eigen::ComputeEigenvectors);
 
  547           Eigen::Matrix3f eigen_vectors_pca = eigen_solver.eigenvectors();
 
  550           eigen_vectors_pca.col(2) = eigen_vectors_pca.col(0).cross(eigen_vectors_pca.col(1));
 
  552           eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(M_PI / 2.0, Eigen::Vector3f::UnitY());
 
  554           if (eigen_vectors_pca.col(2).dot(Eigen::Vector3f::UnitZ()) < 0) {
 
  555             eigen_vectors_pca = eigen_vectors_pca * Eigen::AngleAxisf(M_PI, Eigen::Vector3f::UnitX());
 
  558           Eigen::Matrix4f projection_transform(Eigen::Matrix4f::Identity());
 
  559           projection_transform.block<3,3>(0,0) = eigen_vectors_pca.transpose();
 
  560           pcl::transformPointCloud(*segmented_cloud, *segmented_cloud_transformed, projection_transform);
 
  561           m4.block<3, 3>(0, 0) = eigen_vectors_pca;
 
  562           q = eigen_vectors_pca;
 
  564           is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
 
  565           center = m4 * center;
 
  568           segmented_cloud_transformed = segmented_cloud;
 
  571         segmented_cloud_transformed = segmented_cloud;
 
  572         is_center_valid = pcl::compute3DCentroid(*segmented_cloud_transformed, center) != 0;
 
  577     Eigen::Vector4f minpt, maxpt;
 
  578     pcl::getMinMax3D<pcl::PointXYZ>(*segmented_cloud_transformed, minpt, maxpt);
 
  580     double xwidth = maxpt[0] - minpt[0];
 
  581     double ywidth = maxpt[1] - minpt[1];
 
  582     double zwidth = maxpt[2] - minpt[2];
 
  583     if (!pcl_isfinite(xwidth) || !pcl_isfinite(ywidth) || !pcl_isfinite(zwidth))
 
  586       xwidth = ywidth = zwidth = 0;
 
  589     Eigen::Vector4f center2((maxpt[0] + minpt[0]) / 2.0, (maxpt[1] + minpt[1]) / 2.0, (maxpt[2] + minpt[2]) / 2.0, 1.0);
 
  590     Eigen::Vector4f center_transformed = m4 * center2;
 
  593     if (is_center_valid) {
 
  594       center_pose_msg.position.x = center[0];
 
  595       center_pose_msg.position.y = center[1];
 
  596       center_pose_msg.position.z = center[2];
 
  597       center_pose_msg.orientation.x = 
q.x();
 
  598       center_pose_msg.orientation.y = 
q.y();
 
  599       center_pose_msg.orientation.z = 
q.z();
 
  600       center_pose_msg.orientation.w = 
q.w();
 
  604       center_pose_msg = geometry_msgs::Pose();
 
  608     bounding_box.pose.position.x = center_transformed[0];
 
  609     bounding_box.pose.position.y = center_transformed[1];
 
  610     bounding_box.pose.position.z = center_transformed[2];
 
  611     bounding_box.pose.orientation.x = 
q.x();
 
  612     bounding_box.pose.orientation.y = 
q.y();
 
  613     bounding_box.pose.orientation.z = 
q.z();
 
  614     bounding_box.pose.orientation.w = 
q.w();
 
  615     bounding_box.dimensions.x = xwidth;
 
  616     bounding_box.dimensions.y = ywidth;
 
  617     bounding_box.dimensions.z = zwidth;
 
  621       bounding_box.label = nearest_plane_index;
 
  627   (
const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
 
  629    pcl::PointCloud<pcl::PointXYZRGB>& debug_output)
 
  632     for (
size_t j = 0; j < segmented_cloud->points.size(); j++) {
 
  634       p.x= segmented_cloud->points[j].x;
 
  635       p.y= segmented_cloud->points[j].y;
 
  636       p.z= segmented_cloud->points[j].z;
 
  637       p.rgb = *
reinterpret_cast<float*
>(&
rgb);
 
  638       debug_output.points.push_back(p);
 
  643     const sensor_msgs::PointCloud2ConstPtr &
input,
 
  644     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
 
  649     std::vector<int> all_indices;
 
  652       boost::irange(0, (
int)(
input->width * 
input->height)),
 
  653       std::inserter(all_indices, all_indices.begin()));
 
  655     for (
size_t i = 0; 
i < indices_input->cluster_indices.size(); 
i++) {
 
  656       for (
size_t j = 0; j < indices_input->cluster_indices[
i].indices.size(); ++j) {
 
  657         all_indices[indices_input->cluster_indices[
i].indices[j]] = -1;
 
  660     all_indices.erase(std::remove(all_indices.begin(), all_indices.end(), -1), all_indices.end());
 
  663     pcl_msgs::PointIndices ros_indices;
 
  664     ros_indices.indices = std::vector<int>(all_indices.begin(), all_indices.end());
 
  665     ros_indices.header = 
input->header;
 
  670     const sensor_msgs::PointCloud2ConstPtr &
input,
 
  671     const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input,
 
  672     const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
 
  673     const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients)
 
  675     vital_checker_->poke();
 
  680     pcl::ExtractIndices<pcl::PointXYZ> 
extract;
 
  681     pcl::PointCloud<pcl::PointXYZ>::Ptr 
cloud (
new pcl::PointCloud<pcl::PointXYZ>);
 
  685     std::vector<pcl::IndicesPtr> converted_indices;
 
  687     for (
size_t i = 0; 
i < indices_input->cluster_indices.size(); 
i++)
 
  689       pcl::IndicesPtr vindices;
 
  692           indices_input->cluster_indices[
i].indices.size() < 
min_size_) {
 
  693         vindices.reset (
new std::vector<int> ());
 
  694         converted_indices.push_back(vindices);
 
  698           indices_input->cluster_indices[
i].indices.size() > 
max_size_) {
 
  699         vindices.reset (
new std::vector<int> ());
 
  700         converted_indices.push_back(vindices);
 
  703       vindices.reset (
new std::vector<int> (indices_input->cluster_indices[i].indices));
 
  704       converted_indices.push_back(vindices);
 
  707     std::vector<size_t> argsort;
 
  712     bool is_sensed_with_camera = (
input->height != 1);
 
  714     cv::Mat mask = cv::Mat::zeros(
input->height, 
input->width, CV_8UC1);
 
  716     pcl::PointCloud<pcl::PointXYZRGB> debug_output;
 
  717     jsk_recognition_msgs::BoundingBoxArray bounding_box_array;
 
  718     jsk_recognition_msgs::ClusterPointIndices out_cluster_indices;
 
  719     bounding_box_array.header = 
input->header;
 
  720     geometry_msgs::PoseArray center_pose_array;
 
  721     center_pose_array.header = 
input->header;
 
  722     out_cluster_indices.header = 
input->header;
 
  723     for (
size_t i = 0; 
i < argsort.size(); 
i++)
 
  725       pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud (
new pcl::PointCloud<pcl::PointXYZ>);
 
  726       segmented_cloud->is_dense = 
cloud->is_dense;
 
  728       pcl_msgs::PointIndices out_indices_msg;
 
  729       out_indices_msg.header = 
input->header;
 
  730       out_indices_msg.indices = *(converted_indices[argsort[
i]]);
 
  731       out_cluster_indices.cluster_indices.push_back(out_indices_msg);
 
  733       pcl::PointIndices::Ptr segmented_indices (
new pcl::PointIndices);
 
  734       extract.setIndices(converted_indices[argsort[i]]);
 
  735       extract.filter(*segmented_cloud);
 
  737         sensor_msgs::PointCloud2::Ptr out_cloud(
new sensor_msgs::PointCloud2);
 
  739         out_cloud->header = 
input->header;
 
  743       if (is_sensed_with_camera) {
 
  745         for (
size_t j = 0; j < converted_indices[argsort[
i]]->size(); j++) {
 
  746           int index = converted_indices[argsort[
i]]->data()[j];
 
  749           mask.at<uchar>(height_index, width_index) = 255;
 
  752           label.at<
int>(height_index, width_index) = (
int)
i + 1;
 
  759       geometry_msgs::Pose pose_msg;
 
  760       jsk_recognition_msgs::BoundingBox bounding_box;
 
  761       bounding_box.label = 
static_cast<int>(argsort[
i]);
 
  763       if (!segmented_cloud->is_dense) {
 
  764         std::vector<int> nan_indices;
 
  765         pcl::removeNaNFromPointCloud(*segmented_cloud, *segmented_cloud, nan_indices);
 
  770         segmented_cloud, 
input->header, planes, coefficients, pose_msg, bounding_box, publish_tf);
 
  781       center_pose_array.poses.push_back(pose_msg);
 
  783       bounding_box_array.boxes.push_back(bounding_box);
 
  786         transform.setOrigin(tf::Vector3(pose_msg.position.x, pose_msg.position.y, pose_msg.position.z));
 
  789                                                 tf_prefix_ + (boost::format(
"output%02u") % (i)).str()));
 
  799     if (is_sensed_with_camera) {
 
  812     sensor_msgs::PointCloud2 debug_ros_output;
 
  814     debug_ros_output.header = 
input->header;
 
  815     debug_ros_output.is_dense = 
false;
 
  823   (
const sensor_msgs::PointCloud2ConstPtr &
input,
 
  824    const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
 
  827             jsk_recognition_msgs::PolygonArrayConstPtr(),
 
  828             jsk_recognition_msgs::ModelCoefficientsArrayConstPtr());
 
  837             std::string topic_name = (boost::format(
"output%02u") % (
i)).str();
 
  839             ros::Publisher publisher = pnh_->advertise<sensor_msgs::PointCloud2>(topic_name, 1);