line_segment_collector_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, 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 #define BOOST_PARAMETER_MAX_ARITY 7 
00036 #include "jsk_pcl_ros/line_segment_collector.h"
00037 #include "jsk_recognition_utils/pcl_conversion_util.h"
00038 #include "jsk_recognition_utils/pcl_util.h"
00039 #include <pcl/sample_consensus/method_types.h>
00040 #include <pcl/sample_consensus/model_types.h>
00041 #include <pcl/segmentation/sac_segmentation.h>
00042 
00043 namespace jsk_pcl_ros
00044 {
00045   LineSegmentCluster::LineSegmentCluster():
00046     delta_(Eigen::Vector3f(0, 0, 0)),
00047     points_(new pcl::PointCloud<pcl::PointXYZ>),
00048     raw_points_(new pcl::PointCloud<pcl::PointXYZ>)
00049   {
00050 
00051   }
00052   
00053   void LineSegmentCluster::addLineSegmentEWMA(
00054     LineSegment::Ptr segment, const double tau)
00055   {
00056     segments_.push_back(segment);
00057     Eigen::Vector3f new_delta = segment->toSegment()->getDirection();
00058     if (new_delta.dot(delta_) < 0) {
00059       new_delta = - new_delta;
00060     }
00061     delta_ = ((1 - tau) * delta_ + tau * new_delta).normalized();
00062     
00063     // update points_
00064     pcl::PointCloud<pcl::PointXYZ>::Ptr new_cloud = segment->getPoints();
00065     for (size_t i = 0; i < new_cloud->points.size(); i++) {
00066       points_->points.push_back(new_cloud->points[i]);
00067     }
00068     // update raw_points_
00069     pcl::PointCloud<pcl::PointXYZ>::Ptr new_raw_cloud = segment->getRawPoints();
00070     for (size_t i = 0; i < new_raw_cloud->points.size(); i++) {
00071       raw_points_->points.push_back(new_raw_cloud->points[i]);
00072     }
00073   }
00074 
00075   pcl::PointCloud<pcl::PointXYZ>::Ptr LineSegmentCluster::getPoints()
00076   {
00077     return points_;
00078   }
00079 
00080   pcl::PointCloud<pcl::PointXYZ>::Ptr LineSegmentCluster::getRawPoints()
00081   {
00082     return raw_points_;
00083   }
00084 
00085   void LineSegmentCluster::removeBefore(const ros::Time& stamp)
00086   {
00087     bool removed = false;
00088     for (std::vector<LineSegment::Ptr>::iterator it = segments_.begin();
00089          it != segments_.end(); ) {
00090       if (((*it)->header.stamp - stamp).toSec() < 0) {
00091         it = segments_.erase(it);
00092         removed = true;
00093       }
00094       else {
00095         ++it;
00096       }
00097     }
00098     if (removed) {
00099       // reconstruct pointcloud
00100       points_.reset(new pcl::PointCloud<pcl::PointXYZ>);
00101 
00102       raw_points_.reset(new pcl::PointCloud<pcl::PointXYZ>);
00103       for (std::vector<LineSegment::Ptr>::iterator it = segments_.begin();
00104          it != segments_.end(); ++it) {
00105         {
00106           pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getPoints();
00107           for (size_t i = 0; i < segment_points->points.size(); i++) {
00108             points_->points.push_back(segment_points->points[i]);
00109           }
00110         }
00111         {
00112           pcl::PointCloud<pcl::PointXYZ>::Ptr segment_points = (*it)->getRawPoints();
00113           for (size_t i = 0; i < segment_points->points.size(); i++) {
00114             raw_points_->points.push_back(segment_points->points[i]);
00115           }
00116         }
00117       }
00118     }
00119   }
00120   
00121   bool LineSegmentCluster::isEmpty()
00122   {
00123     return segments_.size() == 0;
00124   }
00125   
00126   void LineSegmentCollector::onInit()
00127   {
00128     DiagnosticNodelet::onInit();
00129     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00130     dynamic_reconfigure::Server<Config>::CallbackType f =
00131       boost::bind (&LineSegmentCollector::configCallback, this, _1, _2);
00132     srv_->setCallback (f);
00133     
00134     if (!pnh_->getParam("fixed_frame_id", fixed_frame_id_)) {
00135       NODELET_ERROR("no ~fixed_frame_id is specified");
00136       return;
00137     }
00138 
00139     std::string rotate_type_str;
00140     pnh_->param("rotate_type", rotate_type_str, std::string("tilt_two_way"));
00141     if (rotate_type_str == "tilt") {
00142       rotate_type_ = ROTATION_TILT;
00143     }
00144     else if (rotate_type_str == "tilt_two_way") {
00145       rotate_type_ = ROTATION_TILT_TWO_WAY;
00146     }
00147     else if (rotate_type_str == "spindle") {
00148       rotate_type_ = ROTATION_SPINDLE;
00149     }
00150     else {
00151       NODELET_ERROR("unknown ~rotate_type: %s", rotate_type_str.c_str());
00152       return;
00153     }
00154     
00155     pub_point_cloud_
00156       = advertise<sensor_msgs::PointCloud2>(*pnh_, "output/cloud", 1);
00157     pub_inliers_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(*pnh_, "output/inliers", 1);
00158     pub_coefficients_
00159       = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(*pnh_, "output/coefficients", 1);
00160     pub_polygons_
00161       = advertise<jsk_recognition_msgs::PolygonArray>(*pnh_, "output/polygons", 1);
00162     debug_pub_inliers_before_plane_
00163       = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00164         *pnh_, "debug/connect_segments/inliers", 1);
00165 
00166     onInitPostProcess();
00167   }
00168 
00169   void LineSegmentCollector::configCallback(Config &config, uint32_t level)
00170   {
00171     boost::mutex::scoped_lock lock(mutex_);
00172     ewma_tau_ = config.ewma_tau;
00173     segment_connect_normal_threshold_ = config.segment_connect_normal_threshold;
00174     outlier_threshold_ = config.outlier_threshold;
00175   }
00176 
00177   void LineSegmentCollector::subscribe()
00178   {
00179     sub_input_.subscribe(*pnh_, "input", 1);
00180     sub_indices_.subscribe(*pnh_, "input_indices", 1);
00181     sub_coefficients_.subscribe(*pnh_, "input_coefficients", 1);
00182     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00183     sync_->connectInput(sub_input_, sub_indices_, sub_coefficients_);
00184     sync_->registerCallback(boost::bind(&LineSegmentCollector::collect,
00185                                         this, _1, _2, _3));
00186     sub_trigger_ = pnh_->subscribe("trigger", 1,
00187                                    &LineSegmentCollector::triggerCallback, this);
00188   }
00189 
00190   void LineSegmentCollector::unsubscribe()
00191   {
00192     sub_input_.unsubscribe();
00193     sub_indices_.unsubscribe();
00194     sub_coefficients_.unsubscribe();
00195     sub_trigger_.shutdown();
00196   }
00197 
00198   void LineSegmentCollector::cleanupBuffers(
00199       const ros::Time& stamp)
00200   {
00201     pointclouds_buffer_.removeBefore(stamp);
00202     indices_buffer_.removeBefore(stamp);
00203     coefficients_buffer_.removeBefore(stamp);
00204     segments_buffer_.removeBefore(stamp);
00205     for (std::vector<LineSegmentCluster::Ptr>::iterator it = segment_clusters_.begin();
00206          it != segment_clusters_.end();) {
00207       (*it)->removeBefore(stamp);
00208       if ((*it)->isEmpty()) {
00209         it = segment_clusters_.erase(it);
00210       }
00211       else {
00212         ++it;
00213       }
00214     }
00215   }
00216 
00217   void LineSegmentCollector::triggerCallback(
00218     const jsk_recognition_msgs::TimeRange::ConstPtr& trigger)
00219   {
00220     boost::mutex::scoped_lock lock(mutex_);
00221     time_range_ = trigger;
00222     cleanupBuffers(time_range_->start);
00223   }
00224   
00225   void LineSegmentCollector::publishBeforePlaneSegmentation(
00226     const std_msgs::Header& header,
00227     const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00228     const std::vector<pcl::PointIndices::Ptr>& connected_indices)
00229   {
00230     sensor_msgs::PointCloud2 ros_cloud;
00231     pcl::toROSMsg(*cloud, ros_cloud);
00232     ros_cloud.header = header;
00233     pub_point_cloud_.publish(ros_cloud);
00234     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00235     ros_indices.header = header;
00236     ros_indices.cluster_indices
00237       = pcl_conversions::convertToROSPointIndices(connected_indices, header);
00238     debug_pub_inliers_before_plane_.publish(ros_indices);
00239   }
00240 
00241   LineSegmentCluster::Ptr LineSegmentCollector::lookupNearestSegment(
00242     LineSegment::Ptr segment)
00243   {
00244     int max_index = -1;
00245     double max_dot = - DBL_MAX;
00246     for (size_t i = 0; i < segment_clusters_.size(); i++) {
00247       LineSegmentCluster::Ptr cluster = segment_clusters_[i];
00248       Eigen::Vector3f delta_cluster = cluster->getDelta();
00249       Eigen::Vector3f delta = segment->toSegment()->getDirection();
00250       double delta_dot = std::abs(delta_cluster.dot(delta));
00251       if (delta_dot > segment_connect_normal_threshold_) {
00252         if (max_dot < delta_dot) {
00253           max_dot = delta_dot;
00254           max_index = i;
00255         }
00256       }
00257       // else {
00258       //   if (segment_clusters_.size() != 0) {
00259       //     NODELET_INFO("dot: %f", delta_dot);
00260       //   }
00261       // }
00262     }
00263     if (max_index == -1) {
00264       
00265       return LineSegmentCluster::Ptr();
00266     }
00267     else {
00268       //ROS_INFO("max angle: %f", acos(max_dot) * 180.0 / M_PI);
00269       return segment_clusters_[max_index];
00270     }
00271   }
00272   
00273   void LineSegmentCollector::collectFromBuffers(
00274     const std_msgs::Header& header,
00275     std::vector<LineSegment::Ptr> new_segments)
00276   {
00277     for (size_t i = 0; i < new_segments.size(); i++) {
00278       LineSegment::Ptr segment = new_segments[i];
00279       LineSegmentCluster::Ptr cluster = lookupNearestSegment(segment);
00280       if (cluster) {
00281         cluster->addLineSegmentEWMA(segment, ewma_tau_);
00282       }
00283       else {
00284         cluster.reset(new LineSegmentCluster());
00285         cluster->addLineSegmentEWMA(segment, 1.0);
00286         segment_clusters_.push_back(cluster);
00287       }
00288     }
00289     
00290     pcl::PointCloud<pcl::PointXYZ>::Ptr
00291       connected_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00292     std::vector<pcl::PointIndices::Ptr> connected_indices;
00293     std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > clouds_list;
00294     for (size_t i = 0; i < segment_clusters_.size(); i++) {
00295       LineSegmentCluster::Ptr cluster = segment_clusters_[i];
00296       pcl::PointIndices::Ptr current_indices (new pcl::PointIndices);
00297       pcl::PointCloud<pcl::PointXYZ>::Ptr current_cloud
00298         = cluster->getRawPoints();
00299       for (size_t j = 0; j < current_cloud->points.size(); j++) {
00300         current_indices->indices.push_back(connected_cloud->points.size() + j);
00301       }
00302       connected_indices.push_back(current_indices);
00303       clouds_list.push_back(current_cloud);
00304       *connected_cloud = *connected_cloud + *current_cloud;
00305     }
00306     // publish debug information
00307     publishBeforePlaneSegmentation(
00308       header,
00309       connected_cloud,
00310       connected_indices);
00311   }
00312 
00313   void LineSegmentCollector::publishResult(
00314     const std_msgs::Header& header,
00315     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00316     std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
00317     std::vector<pcl::PointIndices::Ptr> all_indices)
00318   {
00319     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00320     ros_indices.header = header;
00321     ros_indices.cluster_indices
00322       = pcl_conversions::convertToROSPointIndices(all_indices,
00323                                                   header);
00324     pub_inliers_.publish(ros_indices);
00325     jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00326     ros_coefficients.header = header;
00327     ros_coefficients.coefficients
00328       = pcl_conversions::convertToROSModelCoefficients(
00329         all_coefficients,
00330         header);
00331     pub_coefficients_.publish(ros_coefficients);
00332     jsk_recognition_msgs::PolygonArray ros_polygon;
00333     ros_polygon.header = header;
00334     for (size_t i = 0; i < all_indices.size(); i++) {
00335       jsk_recognition_utils::ConvexPolygon::Ptr convex
00336         = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointXYZ>(
00337           cloud, all_indices[i], all_coefficients[i]);
00338       geometry_msgs::PolygonStamped polygon_stamped;
00339       polygon_stamped.header = header;
00340       polygon_stamped.polygon = convex->toROSMsg();
00341       ros_polygon.polygons.push_back(polygon_stamped);
00342     }
00343     pub_polygons_.publish(ros_polygon);
00344   }
00345   
00346   void LineSegmentCollector::collect(
00347       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00348       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00349       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00350   {
00351     boost::mutex::scoped_lock lock(mutex_);
00352     //NODELET_INFO("buffer length: %lu", pointclouds_buffer_.size());
00353     pointclouds_buffer_.push_back(cloud_msg);
00354     indices_buffer_.push_back(indices_msg);
00355     coefficients_buffer_.push_back(coefficients_msg);
00356     pcl::PointCloud<pcl::PointXYZ>::Ptr
00357       input_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00358     pcl::fromROSMsg(*cloud_msg, *input_cloud);
00359     // buildup segments
00360     std::vector<pcl::PointIndices::Ptr> input_indices
00361       = pcl_conversions::convertToPCLPointIndices(indices_msg->cluster_indices);
00362     std::vector<pcl::ModelCoefficients::Ptr> input_coefficients
00363       = pcl_conversions::convertToPCLModelCoefficients(
00364         coefficients_msg->coefficients);
00365     std::vector<LineSegment::Ptr> new_segments;
00366     for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
00367       LineSegment::Ptr segment (new LineSegment(cloud_msg->header,
00368                                                 input_indices[i],
00369                                                 input_coefficients[i],
00370                                                 input_cloud));
00371       segments_buffer_.push_back(segment);
00372       new_segments.push_back(segment);
00373     }
00374     collectFromBuffers(cloud_msg->header, new_segments);
00375   }
00376   
00377 }
00378 
00379 #include <pluginlib/class_list_macros.h>
00380 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::LineSegmentCollector, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jul 2 2019 19:41:43