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::updateDiagnostic(
00199     diagnostic_updater::DiagnosticStatusWrapper &stat)
00200   {
00201 
00202   }
00203 
00204   void LineSegmentCollector::cleanupBuffers(
00205       const ros::Time& stamp)
00206   {
00207     pointclouds_buffer_.removeBefore(stamp);
00208     indices_buffer_.removeBefore(stamp);
00209     coefficients_buffer_.removeBefore(stamp);
00210     segments_buffer_.removeBefore(stamp);
00211     for (std::vector<LineSegmentCluster::Ptr>::iterator it = segment_clusters_.begin();
00212          it != segment_clusters_.end();) {
00213       (*it)->removeBefore(stamp);
00214       if ((*it)->isEmpty()) {
00215         it = segment_clusters_.erase(it);
00216       }
00217       else {
00218         ++it;
00219       }
00220     }
00221   }
00222 
00223   void LineSegmentCollector::triggerCallback(
00224     const jsk_recognition_msgs::TimeRange::ConstPtr& trigger)
00225   {
00226     boost::mutex::scoped_lock lock(mutex_);
00227     time_range_ = trigger;
00228     cleanupBuffers(time_range_->start);
00229   }
00230   
00231   void LineSegmentCollector::publishBeforePlaneSegmentation(
00232     const std_msgs::Header& header,
00233     const pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00234     const std::vector<pcl::PointIndices::Ptr>& connected_indices)
00235   {
00236     sensor_msgs::PointCloud2 ros_cloud;
00237     pcl::toROSMsg(*cloud, ros_cloud);
00238     ros_cloud.header = header;
00239     pub_point_cloud_.publish(ros_cloud);
00240     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00241     ros_indices.header = header;
00242     ros_indices.cluster_indices
00243       = pcl_conversions::convertToROSPointIndices(connected_indices, header);
00244     debug_pub_inliers_before_plane_.publish(ros_indices);
00245   }
00246 
00247   LineSegmentCluster::Ptr LineSegmentCollector::lookupNearestSegment(
00248     LineSegment::Ptr segment)
00249   {
00250     int max_index = -1;
00251     double max_dot = - DBL_MAX;
00252     for (size_t i = 0; i < segment_clusters_.size(); i++) {
00253       LineSegmentCluster::Ptr cluster = segment_clusters_[i];
00254       Eigen::Vector3f delta_cluster = cluster->getDelta();
00255       Eigen::Vector3f delta = segment->toSegment()->getDirection();
00256       double delta_dot = std::abs(delta_cluster.dot(delta));
00257       if (delta_dot > segment_connect_normal_threshold_) {
00258         if (max_dot < delta_dot) {
00259           max_dot = delta_dot;
00260           max_index = i;
00261         }
00262       }
00263       // else {
00264       //   if (segment_clusters_.size() != 0) {
00265       //     NODELET_INFO("dot: %f", delta_dot);
00266       //   }
00267       // }
00268     }
00269     if (max_index == -1) {
00270       
00271       return LineSegmentCluster::Ptr();
00272     }
00273     else {
00274       //ROS_INFO("max angle: %f", acos(max_dot) * 180.0 / M_PI);
00275       return segment_clusters_[max_index];
00276     }
00277   }
00278   
00279   void LineSegmentCollector::collectFromBuffers(
00280     const std_msgs::Header& header,
00281     std::vector<LineSegment::Ptr> new_segments)
00282   {
00283     for (size_t i = 0; i < new_segments.size(); i++) {
00284       LineSegment::Ptr segment = new_segments[i];
00285       LineSegmentCluster::Ptr cluster = lookupNearestSegment(segment);
00286       if (cluster) {
00287         cluster->addLineSegmentEWMA(segment, ewma_tau_);
00288       }
00289       else {
00290         cluster.reset(new LineSegmentCluster());
00291         cluster->addLineSegmentEWMA(segment, 1.0);
00292         segment_clusters_.push_back(cluster);
00293       }
00294     }
00295     
00296     pcl::PointCloud<pcl::PointXYZ>::Ptr
00297       connected_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00298     std::vector<pcl::PointIndices::Ptr> connected_indices;
00299     std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr > clouds_list;
00300     for (size_t i = 0; i < segment_clusters_.size(); i++) {
00301       LineSegmentCluster::Ptr cluster = segment_clusters_[i];
00302       pcl::PointIndices::Ptr current_indices (new pcl::PointIndices);
00303       pcl::PointCloud<pcl::PointXYZ>::Ptr current_cloud
00304         = cluster->getRawPoints();
00305       for (size_t j = 0; j < current_cloud->points.size(); j++) {
00306         current_indices->indices.push_back(connected_cloud->points.size() + j);
00307       }
00308       connected_indices.push_back(current_indices);
00309       clouds_list.push_back(current_cloud);
00310       *connected_cloud = *connected_cloud + *current_cloud;
00311     }
00312     // publish debug information
00313     publishBeforePlaneSegmentation(
00314       header,
00315       connected_cloud,
00316       connected_indices);
00317   }
00318 
00319   void LineSegmentCollector::publishResult(
00320     const std_msgs::Header& header,
00321     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud,
00322     std::vector<pcl::ModelCoefficients::Ptr> all_coefficients,
00323     std::vector<pcl::PointIndices::Ptr> all_indices)
00324   {
00325     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00326     ros_indices.header = header;
00327     ros_indices.cluster_indices
00328       = pcl_conversions::convertToROSPointIndices(all_indices,
00329                                                   header);
00330     pub_inliers_.publish(ros_indices);
00331     jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00332     ros_coefficients.header = header;
00333     ros_coefficients.coefficients
00334       = pcl_conversions::convertToROSModelCoefficients(
00335         all_coefficients,
00336         header);
00337     pub_coefficients_.publish(ros_coefficients);
00338     jsk_recognition_msgs::PolygonArray ros_polygon;
00339     ros_polygon.header = header;
00340     for (size_t i = 0; i < all_indices.size(); i++) {
00341       jsk_recognition_utils::ConvexPolygon::Ptr convex
00342         = jsk_recognition_utils::convexFromCoefficientsAndInliers<pcl::PointXYZ>(
00343           cloud, all_indices[i], all_coefficients[i]);
00344       geometry_msgs::PolygonStamped polygon_stamped;
00345       polygon_stamped.header = header;
00346       polygon_stamped.polygon = convex->toROSMsg();
00347       ros_polygon.polygons.push_back(polygon_stamped);
00348     }
00349     pub_polygons_.publish(ros_polygon);
00350   }
00351   
00352   void LineSegmentCollector::collect(
00353       const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00354       const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& indices_msg,
00355       const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00356   {
00357     boost::mutex::scoped_lock lock(mutex_);
00358     //NODELET_INFO("buffer length: %lu", pointclouds_buffer_.size());
00359     pointclouds_buffer_.push_back(cloud_msg);
00360     indices_buffer_.push_back(indices_msg);
00361     coefficients_buffer_.push_back(coefficients_msg);
00362     pcl::PointCloud<pcl::PointXYZ>::Ptr
00363       input_cloud(new pcl::PointCloud<pcl::PointXYZ>);
00364     pcl::fromROSMsg(*cloud_msg, *input_cloud);
00365     // buildup segments
00366     std::vector<pcl::PointIndices::Ptr> input_indices
00367       = pcl_conversions::convertToPCLPointIndices(indices_msg->cluster_indices);
00368     std::vector<pcl::ModelCoefficients::Ptr> input_coefficients
00369       = pcl_conversions::convertToPCLModelCoefficients(
00370         coefficients_msg->coefficients);
00371     std::vector<LineSegment::Ptr> new_segments;
00372     for (size_t i = 0; i < indices_msg->cluster_indices.size(); i++) {
00373       LineSegment::Ptr segment (new LineSegment(cloud_msg->header,
00374                                                 input_indices[i],
00375                                                 input_coefficients[i],
00376                                                 input_cloud));
00377       segments_buffer_.push_back(segment);
00378       new_segments.push_back(segment);
00379     }
00380     collectFromBuffers(cloud_msg->header, new_segments);
00381   }
00382   
00383 }
00384 
00385 #include <pluginlib/class_list_macros.h>
00386 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::LineSegmentCollector, nodelet::Nodelet);


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