37 #include <pcl/kdtree/kdtree_flann.h> 
   38 #include <pcl/common/centroid.h> 
   40 #include <jsk_recognition_msgs/BoundingBoxArray.h> 
   41 #include <geometry_msgs/PoseArray.h> 
   42 #include <pcl/filters/extract_indices.h> 
   43 #include <visualization_msgs/Marker.h> 
   45 #include <pcl/sample_consensus/method_types.h> 
   46 #include <pcl/sample_consensus/model_types.h> 
   47 #include <pcl/segmentation/sac_segmentation.h> 
   48 #include <pcl/common/angles.h> 
   49 #include <jsk_recognition_msgs/PolygonArray.h> 
   50 #include <jsk_recognition_msgs/ClusterPointIndices.h> 
   51 #include <pcl/filters/project_inliers.h> 
   52 #include <pcl/surface/convex_hull.h> 
   59                                  const double outlier_threshold):
 
   60     value_(0.0), indices_pair_(pair), coefficients_pair_(coefficients_pair),
 
   61     outlier_threshold_(outlier_threshold_)
 
   71     const pcl::PointCloud<pcl::PointXYZRGB>::Ptr& cloud,
 
   72     const pcl::PointIndices::Ptr& indices,
 
   73     Eigen::Vector3f& output)
 
   75     Eigen::Vector4f centroid;
 
   77     pcl::PointCloud<pcl::PointXYZRGB>::Ptr target_cloud (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   78     pcl::ExtractIndices<pcl::PointXYZRGB> 
ex;
 
   79     ex.setInputCloud(cloud);
 
   80     ex.setIndices(indices);
 
   81     ex.filter(*target_cloud);
 
   82     pcl::compute3DCentroid(*target_cloud, centroid);
 
   83     jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(centroid, output);
 
   88     const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
 
   89     const pcl::PointIndices::Ptr indices,
 
   92     pcl::PointCloud<pcl::PointXYZRGB>::Ptr 
points 
   93       (
new pcl::PointCloud<pcl::PointXYZRGB>);
 
   94     pcl::ExtractIndices<pcl::PointXYZRGB> extract;
 
   95     extract.setInputCloud(
cloud.makeShared());
 
   96     extract.setIndices(indices);
 
   98     for (
size_t i = 0; 
i < 
points->points.size(); 
i++) {
 
   99       pcl::PointXYZRGB 
p = 
points->points[
i];
 
  100       Eigen::Vector3f p_eigen = 
p.getVector3fMap();
 
  101       Eigen::Vector3f foot_point;
 
  102       line.foot(p_eigen, foot_point);
 
  103       output.push_back(foot_point);
 
  111     vertices.push_back(a_edge_pair.get<0>());
 
  112     vertices.push_back(a_edge_pair.get<1>());
 
  113     vertices.push_back(b_edge_pair.get<1>());
 
  114     vertices.push_back(b_edge_pair.get<0>());
 
  120 #if __cplusplus >= 201103L 
  121 #define pcl_isfinite(x) std::isfinite(x) 
  125     const pcl::PointCloud<pcl::PointXYZRGB>& cloud,
 
  129     std::vector<int> a_indices, b_indices;
 
  130     for (
size_t i = 0; 
i < 
cloud.points.size(); 
i++) {
 
  131       pcl::PointXYZRGB pcl_point = 
cloud.points[
i];
 
  132       if (pcl_isfinite(pcl_point.x) &&
 
  133           pcl_isfinite(pcl_point.y) &&
 
  134           pcl_isfinite(pcl_point.z)) { 
 
  135         Eigen::Vector3f eigen_point = pcl_point.getVector3fMap();
 
  137           a_indices.push_back(
i);
 
  140           b_indices.push_back(
i);
 
  145     return a_indices.size() + b_indices.size();
 
  154     original_points.push_back(a_candidates.get<0>());
 
  155     original_points.push_back(a_candidates.get<1>());
 
  156     original_points.push_back(b_candidates.get<0>());
 
  157     original_points.push_back(b_candidates.get<1>());
 
  158     for (
size_t i = 0; 
i < original_points.size(); 
i++) {
 
  159       Eigen::Vector3f 
p = original_points[
i];
 
  160       ROS_INFO(
"[foot_point] [%f, %f, %f]", 
p[0], 
p[1], 
p[2]);
 
  164     for (
size_t i = 0; 
i < original_points.size(); 
i++) {
 
  165       Eigen::Vector3f foot_point;
 
  166       axis.
foot(original_points[i], foot_point);
 
  167       foot_points.push_back(foot_point);
 
  169     double max_alpha = -DBL_MAX;
 
  170     double min_alpha = DBL_MAX;
 
  171     Eigen::Vector3f max_alpha_point, min_alpha_point;
 
  173     for (
size_t i = 0; 
i < foot_points.size(); 
i++) {
 
  175       if (alpha > max_alpha) {
 
  177         max_alpha_point = foot_points[
i];
 
  179       if (alpha < min_alpha) {
 
  181         min_alpha_point = foot_points[
i];
 
  184     ROS_INFO(
"min_alpha_point: [%f, %f, %f]", min_alpha_point[0], min_alpha_point[1], min_alpha_point[2]);
 
  185     ROS_INFO(
"max_alpha_point: [%f, %f, %f]", max_alpha_point[0], max_alpha_point[1], max_alpha_point[2]);
 
  186     return boost::make_tuple(min_alpha_point, max_alpha_point);
 
  192     CubeHypothesis(pair, coefficients_pair, outlier_threshold)
 
  199     const double outlier_threshold):
 
  200     CubeHypothesis(pair, coefficients_pair, outlier_threshold), resolution_(10)
 
  206     const pcl::PointCloud<pcl::PointXYZRGB>& cloud)
 
  213     if (!line_a->isSameDirection(*line_b)) {
 
  214       line_b = line_b->flip();
 
  217     const double r2 = line_a->distance(*line_b);
 
  218     const double r = r2 / 2;
 
  220     Eigen::Vector3f center;
 
  221     axis->getOrigin(center);
 
  234     Eigen::Vector3f centroid_a, centroid_b;
 
  235     pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud_ptr = 
cloud.makeShared();
 
  238     ROS_INFO(
"centroid_a: [%f, %f, %f]", centroid_a[0], centroid_a[1], centroid_a[2]);
 
  239     ROS_INFO(
"centroid_b: [%f, %f, %f]", centroid_b[0], centroid_b[1], centroid_b[2]);
 
  243     line_a_aligned->print();
 
  245     line_b_aligned->print();
 
  254     double max_v = - DBL_MAX;
 
  261       Eigen::Vector3f point_on_x;
 
  262       line_a->foot(center, point_on_x);
 
  267       Eigen::Vector3f 
ex = (point_on_x - center).normalized();
 
  269       axis->getDirection(ez);
 
  270       Eigen::Vector3f ey = ez.cross(
ex).normalized();
 
  272       if (center.dot(ey) > 0) {
 
  274         ey = ez.cross(
ex).normalized();
 
  276       Eigen::Vector3f point_on_y = center + 
r * ey;
 
  291       Eigen::Vector3f line_c_a_min_point, line_c_a_max_point;
 
  292       Eigen::Vector3f line_c_b_min_point, line_c_b_max_point;
 
  293       line_c->foot(line_a_end_points.get<0>(), line_c_a_min_point);
 
  294       line_c->foot(line_a_end_points.get<1>(), line_c_a_max_point);
 
  295       line_c->foot(line_b_end_points.get<0>(), line_c_b_min_point);
 
  296       line_c->foot(line_b_end_points.get<1>(), line_c_b_max_point);
 
  302                                                       line_c_a_end_points);
 
  304                                                       line_c_b_end_points);
 
  310         max_line_c_a_points = line_c_a_end_points;
 
  311         max_line_c_b_points = line_c_b_end_points;
 
  319       max_line_c_b_points);
 
  320     ROS_INFO(
"end_point: [%f, %f, %f]", axis_end_points.get<0>()[0], axis_end_points.get<0>()[1], axis_end_points.get<0>()[2]);
 
  321     ROS_INFO(
"end_point: [%f, %f, %f]", axis_end_points.get<1>()[0], axis_end_points.get<1>()[1], axis_end_points.get<1>()[2]);
 
  322     Eigen::Vector3f midpoint
 
  323       = (axis_end_points.get<0>() + axis_end_points.get<1>()) / 2.0;
 
  324     double z_dimension = (axis_end_points.get<0>() - midpoint).norm() * 2;
 
  326     ROS_INFO(
"midpoint: [%f, %f, %f]", midpoint[0], midpoint[1], midpoint[2]);
 
  328     std::vector<double> dimensions = 
cube_->getDimensions();
 
  329     dimensions[2] = z_dimension;
 
  330     cube_->setDimensions(dimensions);
 
  334     const pcl::PointCloud<PointT>::Ptr cloud,
 
  338     for (
size_t i = 0; 
i < 
cloud->points.size(); 
i++) {
 
  340       if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  341         Eigen::Vector3f ep = 
p.getVector3fMap();
 
  351     const pcl::PointCloud<PointT>::Ptr cloud,
 
  352     const std::vector<jsk_recognition_utils::ConvexPolygon::Ptr>& convexes,
 
  353     std::vector<int>& output_indices)
 
  356     for (
size_t i = 0; 
i < convexes.size(); 
i++) {
 
  365           output_indices.push_back(i);
 
  384     ConnectionBasedNodelet::onInit();
 
  387     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
  388     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  390     srv_->setCallback (
f);
 
  396     pub_ = advertise<jsk_recognition_msgs::BoundingBoxArray>(*pnh_, 
"output", 1);
 
  398       = advertise<geometry_msgs::PoseArray>(*pnh_, 
"output_pose_array", 1);
 
  400       = advertise<visualization_msgs::Marker>(*pnh_, 
"debug_marker", 1);
 
  402       *pnh_, 
"debug_filtered_cloud", 1);
 
  404       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, 
"debug_polygons", 1);
 
  406       = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, 
"debug_clusters", 1);
 
  429     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
  431     sync_->registerCallback(boost::bind(
 
  444     pcl::ModelCoefficients::Ptr coefficients_a = pair.get<0>();
 
  445     pcl::ModelCoefficients::Ptr coefficients_b = pair.get<1>();
 
  448     return line_a->midLine(*line_b);
 
  452     const pcl::PointCloud<PointT>::Ptr cloud,
 
  453     const pcl::PointIndices::Ptr indices)
 
  455     pcl::PointCloud<PointT>::Ptr ret (
new pcl::PointCloud<PointT>);
 
  456     pcl::ExtractIndices<PointT> 
ex;
 
  458     ex.setIndices(indices);
 
  465     const pcl::PointCloud<PointT>::Ptr cloud)
 
  468     for (
size_t i = 0; 
i < 
cloud->points.size(); 
i++) {
 
  470       Eigen::Vector3f eigen_p = 
p.getVector3fMap();
 
  471       Eigen::Vector3f foot;
 
  472       line.foot(eigen_p, foot);
 
  479     const pcl::PointCloud<PointT>::Ptr cloud,
 
  483     pcl::ModelCoefficients::Ptr coefficients_a = coefficients_pair.get<0>();
 
  484     pcl::ModelCoefficients::Ptr coefficients_b = coefficients_pair.get<1>();
 
  485     pcl::PointIndices::Ptr indices_a = indices_pair.get<0>();
 
  486     pcl::PointIndices::Ptr indices_b = indices_pair.get<1>();
 
  496     vertices.push_back(a_min_max.get<0>());
 
  497     vertices.push_back(a_min_max.get<1>());
 
  498     vertices.push_back(b_min_max.get<1>());
 
  499     vertices.push_back(b_min_max.get<0>());
 
  505     const std::vector<IndicesPair>& pairs,
 
  506     const std::vector<CoefficientsPair>& coefficients_pair,
 
  507     std::vector<IndicesPair>& filtered_indices_pairs,
 
  508     std::vector<CoefficientsPair>& filtered_coefficients_pairs)
 
  510     for (
size_t i = 0; 
i < coefficients_pair.size(); 
i++) {
 
  512       pcl::ModelCoefficients::Ptr coefficients_a = coefficients_pair[
i].get<0>();
 
  513       pcl::ModelCoefficients::Ptr coefficients_b = coefficients_pair[
i].get<1>();
 
  519       Eigen::Vector3f origin_a, origin_b;
 
  520       line_a->getOrigin(origin_a);
 
  521       line_b->getOrigin(origin_b);
 
  524       Eigen::Vector3f distance_vector;
 
  525       line_a_aligned->parallelLineNormal(*line_b_aligned, distance_vector);
 
  526       double distance = distance_vector.norm();
 
  531         filtered_indices_pairs.push_back(pairs[
i]);
 
  538   pcl::PointIndices::Ptr
 
  542     const pcl::PointCloud<PointT>::Ptr cloud)
 
  545     pcl::PointIndices::Ptr indices(
new pcl::PointIndices);
 
  547     pcl::PointCloud<PointT>::Ptr ret (
new pcl::PointCloud<PointT>);
 
  548     for (
size_t i = 0; 
i < 
cloud->points.size(); 
i++) {
 
  550       if (!std::isnan(
p.x) && !std::isnan(
p.y) && !std::isnan(
p.z)) {
 
  551         Eigen::Vector3f ep = 
p.getVector3fMap();
 
  552         Eigen::Vector3f foot;
 
  553         magnified_convex->projectOnPlane(ep, foot);
 
  554         if (magnified_convex->isInside(foot) && convex->distanceSmallerThan(ep, 
outlier_threshold_)) {
 
  557           indices->indices.push_back(
i);
 
  566      const pcl::PointCloud<PointT>::Ptr filtered_cloud,
 
  567      pcl::PointIndices::Ptr output_inliers,
 
  568      pcl::ModelCoefficients::Ptr output_coefficients)
 
  570      Eigen::Vector3f normal = convex->getNormal();
 
  571      pcl::SACSegmentation<PointT> seg;
 
  572      seg.setOptimizeCoefficients (
true);
 
  573      seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
 
  574      seg.setMethodType (pcl::SAC_RANSAC);
 
  576      seg.setInputCloud(filtered_cloud);
 
  577      seg.setMaxIterations (10000);
 
  579      seg.setEpsAngle(pcl::deg2rad(10.0));
 
  580      seg.segment (*output_inliers, *output_coefficients);
 
  586      const pcl::PointCloud<PointT>::Ptr filtered_cloud,
 
  587      pcl::PointIndices::Ptr output_inliers,
 
  588      pcl::ModelCoefficients::Ptr output_coefficients)
 
  590      Eigen::Vector3f normal_a = convex->getNormal();
 
  592      Eigen::Vector3f normal_b;
 
  593      mid_line->getDirection(normal_b);
 
  594      Eigen::Vector3f normal = normal_a.cross(normal_b);
 
  595      pcl::SACSegmentation<PointT> seg;
 
  596      seg.setOptimizeCoefficients (
true);
 
  597      seg.setModelType (pcl::SACMODEL_PERPENDICULAR_PLANE);
 
  598      seg.setMethodType (pcl::SAC_RANSAC);
 
  600      seg.setInputCloud(filtered_cloud);
 
  601      seg.setMaxIterations (10000);
 
  603      seg.setEpsAngle(pcl::deg2rad(5.0));
 
  604      seg.segment (*output_inliers, *output_coefficients);
 
  608     const pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr cloud,
 
  610     pcl::PointCloud<EdgebasedCubeFinder::PointT>::Ptr points_on_edge)
 
  612     Eigen::Vector3f 
ex, ey, ez;
 
  614       = indices_coefficients_triple.get<1>();
 
  616       = indices_coefficients_triple.get<0>();
 
  625     if (!mid_line->isSameDirection(*line_a)) {
 
  626       line_a = line_a->flip();
 
  628     if (!mid_line->isSameDirection(*line_b)) {
 
  629       line_b = line_b->flip();
 
  633     pcl::PointCloud<PointT>::Ptr point_on_a
 
  635                           indices_triple.get<1>());
 
  636     pcl::PointCloud<PointT>::Ptr point_on_b
 
  638                           indices_triple.get<2>());
 
  639     pcl::PointCloud<PointT>::Ptr point_on_c
 
  641                           indices_triple.get<0>());
 
  642     Eigen::Vector4f a_centroid4, b_centroid4, c_centroid4;
 
  643     Eigen::Vector3f a_centroid, b_centroid, c_centroid;
 
  644     pcl::compute3DCentroid(*point_on_a, a_centroid4);
 
  645     pcl::compute3DCentroid(*point_on_b, b_centroid4);
 
  646     pcl::compute3DCentroid(*point_on_c, c_centroid4);
 
  647     jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
 
  648       a_centroid4, a_centroid);
 
  649     jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
 
  650       b_centroid4, b_centroid);
 
  651     jsk_recognition_utils::pointFromVectorToVector<Eigen::Vector4f, Eigen::Vector3f>(
 
  652       c_centroid4, c_centroid);
 
  658     pcl::PointCloud<PointT>::Ptr all_points(
new pcl::PointCloud<PointT>);
 
  659     *all_points = *point_on_a + *point_on_b;
 
  660     *all_points = *all_points + *point_on_c;
 
  661     *points_on_edge = *all_points;
 
  678     PointT min_point, max_point;
 
  687     Eigen::Vector3f center_point
 
  688       = (min_max_points.get<0>() + min_max_points.get<1>()) / 2.0;
 
  689     double z_width = (min_max_points.get<0>() - min_max_points.get<1>()).norm();
 
  690     mid_line_aligned->getDirection(ez);
 
  691     mid_line_aligned->parallelLineNormal(*line_a_aligned, 
ex);
 
  692     mid_line_aligned->parallelLineNormal(*line_b_aligned, ey);
 
  694     double x_width = 
ex.norm();
 
  695     double y_width = ey.norm();
 
  702     ROS_INFO(
"ey: [%f, %f, %f]", ey[0], ey[1], ey[2]);
 
  703     ROS_INFO(
"ez: [%f, %f, %f]", ez[0], ez[1], ez[2]);
 
  705     if (
ex.cross(ey).dot(ez) < 0) {
 
  710     std::vector<double> dimensions;
 
  711     dimensions.push_back(x_width);
 
  712     dimensions.push_back(y_width);
 
  713     dimensions.push_back(z_width);
 
  719     const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
  720     const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges)
 
  723      pcl::PointCloud<PointT>::Ptr 
cloud (
new pcl::PointCloud<PointT>);
 
  724      pcl::PointCloud<PointT>::Ptr all_filtered_cloud (
new pcl::PointCloud<PointT>);
 
  726      visualization_msgs::Marker 
marker;
 
  727      jsk_recognition_msgs::PolygonArray polygon_array;
 
  728      geometry_msgs::PoseArray pose_array;
 
  729      jsk_recognition_msgs::BoundingBoxArray box_array;
 
  730      box_array.header = input_cloud->header;
 
  731      pose_array.header = input_cloud->header;
 
  732      std::vector<jsk_recognition_utils::Cube::Ptr> cubes;
 
  733      std::vector<pcl::PointIndices::Ptr> candidate_cluster_indices;
 
  734      for (
size_t i = 0; 
i < input_edges->edge_groups.size(); 
i++) {
 
  735        jsk_recognition_msgs::ParallelEdge parallel_edge = input_edges->edge_groups[
i];
 
  736        std::vector<pcl::PointIndices::Ptr> edges
 
  738            parallel_edge.cluster_indices);
 
  741            parallel_edge.coefficients);
 
  742        std::vector<IndicesCoefficientsTriple> triples
 
  744        std::vector<IndicesCoefficientsTriple> perpendicular_triples
 
  746        if (perpendicular_triples.size() > 0) {
 
  748          pcl::PointCloud<PointT>::Ptr points_on_edges(
new pcl::PointCloud<PointT>);
 
  750          for (
size_t j = 0; j < perpendicular_triples.size(); j++) {
 
  751            pcl::PointCloud<PointT>::Ptr points_on_edge(
new pcl::PointCloud<PointT>);
 
  754              perpendicular_triples[j],
 
  756            *points_on_edges = *points_on_edges + *points_on_edge;
 
  757            cubes.push_back(
cube);
 
  759 #if ( PCL_MAJOR_VERSION >= 1 && PCL_MINOR_VERSION >= 12 ) 
  767      if (cubes.size() > 0) {
 
  768        for (
size_t i = 0; 
i < cubes.size(); 
i++) {
 
  770          jsk_recognition_msgs::BoundingBox ros_box = cubes[
i]->toROSMsg();
 
  771          ros_box.header = input_cloud->header;
 
  772          box_array.boxes.push_back(ros_box);
 
  773          pose_array.poses.push_back(ros_box.pose);
 
  781     const Eigen::Vector3f& a,
 
  782     const Eigen::Vector3f& b)
 
  784     double dot = 
a.normalized().dot(
b.normalized());
 
  785     if (fabs(dot) >= 1.0) {
 
  789       double theta = fabs(acos(dot));
 
  791       if (fabs(theta - M_PI / 2.0) < pcl::deg2rad(20.0)) {
 
  805     Eigen::Vector3f a_b_normal, a_c_normal;
 
  812       Eigen::Vector3f b_a_normal, b_c_normal;
 
  819         Eigen::Vector3f c_a_normal, c_b_normal;
 
  832   std::vector<IndicesCoefficientsTriple>
 
  834     const std::vector<IndicesCoefficientsTriple>& triples)
 
  836     std::vector<IndicesCoefficientsTriple> ret;
 
  837     for (
size_t i = 0; 
i < triples.size(); 
i++) {
 
  838       pcl::ModelCoefficients::Ptr a_coefficients
 
  839         = triples[
i].get<1>().get<0>();
 
  840       pcl::ModelCoefficients::Ptr b_coefficients
 
  841         = triples[
i].get<1>().get<1>();
 
  842       pcl::ModelCoefficients::Ptr c_coefficients
 
  843         = triples[
i].get<1>().get<2>();
 
  857           ret.push_back(triples[
i]);
 
  862               boost::make_tuple(triples[
i].get<0>().get<1>(),
 
  863                                 triples[
i].get<0>().get<0>(),
 
  864                                 triples[
i].get<0>().get<2>()),
 
  866                           triples[i].get<1>().get<1>(),
 
  867                           triples[i].get<1>().get<0>(),
 
  868                           triples[i].get<1>().get<2>()));
 
  869           ret.push_back(new_triple);
 
  874               boost::make_tuple(triples[i].get<0>().get<2>(),
 
  875                                 triples[i].get<0>().get<0>(),
 
  876                                 triples[i].get<0>().get<1>()),
 
  878                           triples[i].get<1>().get<2>(),
 
  879                           triples[i].get<1>().get<0>(),
 
  880                           triples[i].get<1>().get<1>()));
 
  881           ret.push_back(new_triple);
 
  889     const sensor_msgs::PointCloud2::ConstPtr& input_cloud,
 
  890     const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr& input_edges)
 
  893      pcl::PointCloud<PointT>::Ptr 
cloud (
new pcl::PointCloud<PointT>);
 
  894      pcl::PointCloud<PointT>::Ptr all_filtered_cloud (
new pcl::PointCloud<PointT>);
 
  896      visualization_msgs::Marker 
marker;
 
  897      jsk_recognition_msgs::PolygonArray polygon_array;
 
  898      std::vector<pcl::PointIndices::Ptr> candidate_cluster_indices;
 
  900      polygon_array.header = input_cloud->header;
 
  901      marker.pose.orientation.w = 1.0;
 
  904      marker.header = input_cloud->header;
 
  906      marker.type = visualization_msgs::Marker::LINE_LIST;
 
  907      NODELET_INFO(
"%lu parallel edge groups", input_edges->edge_groups.size());
 
  908      geometry_msgs::PoseArray pose_array;
 
  909      pose_array.header = input_cloud->header;
 
  910      jsk_recognition_msgs::BoundingBoxArray ros_output;
 
  911      ros_output.header = input_cloud->header;
 
  913      for (
size_t i = 0; 
i < input_edges->edge_groups.size(); 
i++) {
 
  914        jsk_recognition_msgs::ParallelEdge parallel_edge = input_edges->edge_groups[
i];
 
  916        if (parallel_edge.cluster_indices.size() <= 1) {
 
  918                        parallel_edge.cluster_indices.size());
 
  922                     i, parallel_edge.cluster_indices.size());
 
  926        std::vector<pcl::PointIndices::Ptr> edges
 
  928            parallel_edge.cluster_indices);
 
  931            parallel_edge.coefficients);
 
  934        std::vector<CoefficientsPair> coefficients_pair
 
  936        std::vector<IndicesPair> filtered_indices_pairs;
 
  937        std::vector<CoefficientsPair> filtered_coefficients_pairs;
 
  939        filtered_indices_pairs = pairs;
 
  940        filtered_coefficients_pairs = coefficients_pair;
 
  946        std::vector<jsk_recognition_utils::ConvexPolygon::Ptr> convexes;
 
  947        for (
size_t j = 0; j < filtered_coefficients_pairs.size(); j++) {
 
  951          convexes.push_back(convex);
 
  953        std::vector<int> filtered_indices;
 
  956        pcl::PointIndices::Ptr filtered_cube_candidate_indices(
new pcl::PointIndices);
 
  957        for (
size_t j = 0; j < filtered_indices.size(); j++) {
 
  958          int index = filtered_indices[j];
 
  961            = filtered_indices_pairs[
index];
 
  963            = filtered_coefficients_pairs[
index];
 
  966          pcl::PointIndices::Ptr filtered_indices
 
  968              target_convex, target_edge_coefficients_pair, cloud);
 
  971          filtered_cube_candidate_indices
 
 1072        candidate_cluster_indices.push_back(filtered_cube_candidate_indices);
 
 1075        pcl::PointIndices::Ptr first_inliers(
new pcl::PointIndices);
 
 1076        pcl::ModelCoefficients::Ptr first_coefficients(
new pcl::ModelCoefficients);
 
 1080            filtered_cube_candidate_indices,
 
 1083        if (first_polygon) {
 
 1084          geometry_msgs::PolygonStamped first_polygon_ros;
 
 1085          first_polygon_ros.polygon = first_polygon->toROSMsg();
 
 1086          first_polygon_ros.header = input_cloud->header;
 
 1087          polygon_array.polygons.push_back(first_polygon_ros);
 
 1128     sensor_msgs::PointCloud2 ros_cloud;
 
 1130     ros_cloud.header = input_cloud->header;
 
 1135     jsk_recognition_msgs::ClusterPointIndices ros_cluster_indices;
 
 1136     ros_cluster_indices.header = input_cloud->header;
 
 1137     for (
size_t i = 0; 
i < candidate_cluster_indices.size(); 
i++) {
 
 1139       indices_msg.header = input_cloud->header;
 
 1140       indices_msg.indices = candidate_cluster_indices[
i]->indices;
 
 1141       ros_cluster_indices.cluster_indices.push_back(indices_msg);
 
 1146   std::vector<IndicesCoefficientsTriple>
 
 1148     const std::vector<pcl::PointIndices::Ptr>& indices,
 
 1149     const std::vector<pcl::ModelCoefficients::Ptr>& coefficients)
 
 1152       NODELET_ERROR(
"size of indices and coefficients are not same");
 
 1153       return std::vector<IndicesCoefficientsTriple>();
 
 1157       NODELET_WARN(
"[EdgebasedCubeFinder::tripleIndicesAndCoefficients] no enough canddiates");
 
 1158       return std::vector<IndicesCoefficientsTriple>();
 
 1160     std::vector<IndicesCoefficientsTriple> ret;
 
 1161     for (
size_t i = 0; 
i < indices.size() - 2; 
i++) {
 
 1162       for (
size_t j = i + 1; j < indices.size() - 1; j++) {
 
 1163         for (
size_t k = j + 1; 
k < indices.size(); 
k++) {
 
 1165             = boost::make_tuple(indices[i],
 
 1169             = boost::make_tuple(coefficients[i],
 
 1173             = boost::make_tuple(indices_triple,
 
 1174                                 coefficients_triple);
 
 1175           ret.push_back(indices_coefficients_triple);
 
 1183     const pcl::PointCloud<PointT>::Ptr cloud,
 
 1184     const pcl::PointIndices::Ptr indices,
 
 1185     pcl::ModelCoefficients::Ptr coefficients,
 
 1186     pcl::PointIndices::Ptr inliers)
 
 1191     pcl::SACSegmentation<PointT> seg;
 
 1192     seg.setOptimizeCoefficients (
true);
 
 1193     seg.setModelType (pcl::SACMODEL_PLANE);
 
 1194     seg.setMethodType (pcl::SAC_RANSAC);
 
 1195     seg.setInputCloud(
cloud);
 
 1196     seg.setIndices(indices);
 
 1197     seg.setDistanceThreshold(0.003);
 
 1202     if (inliers->indices.size() > 0) {
 
 1203       return jsk_recognition_utils::convexFromCoefficientsAndInliers<PointT>(
 
 1212     const std::vector<pcl::PointIndices::Ptr>& indices)
 
 1214     std::vector<IndicesPair> ret;
 
 1215     for(
size_t i = 0; 
i < indices.size() - 1; 
i++) {
 
 1216       for (
size_t j = 
i + 1; j < indices.size(); j++) {
 
 1219         ret.push_back(pair);
 
 1226     const std::vector<pcl::ModelCoefficients::Ptr>& coefficients)
 
 1228     std::vector<CoefficientsPair> ret;
 
 1233         ret.push_back(pair);