line_segment_detector_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 #include "jsk_pcl_ros/pcl_conversion_util.h"
00036 #include "jsk_pcl_ros/line_segment_detector.h"
00037 #include <visualization_msgs/Marker.h>
00038 #include <pcl/sample_consensus/method_types.h>
00039 #include <pcl/sample_consensus/model_types.h>
00040 #include <pcl/segmentation/sac_segmentation.h>
00041 #include <pcl/filters/extract_indices.h>
00042 #include <jsk_topic_tools/color_utils.h>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046 
00047   LineSegment::LineSegment(
00048     pcl::PointIndices::Ptr indices,
00049     pcl::ModelCoefficients::Ptr coefficients):
00050     indices_(indices), coefficients_(coefficients)
00051   {
00052   }
00053   
00054   LineSegment::LineSegment(
00055     const std_msgs::Header& input_header,
00056     pcl::PointIndices::Ptr indices,
00057     pcl::ModelCoefficients::Ptr coefficients,
00058     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud):
00059     header(input_header),
00060     indices_(indices), coefficients_(coefficients),
00061     points_(new pcl::PointCloud<pcl::PointXYZ>),
00062     raw_points_(new pcl::PointCloud<pcl::PointXYZ>)
00063   {
00064     pcl::ProjectInliers<pcl::PointXYZ> proj;
00065     proj.setInputCloud(cloud);
00066     proj.setIndices(indices);
00067     proj.setModelType(pcl::SACMODEL_LINE);
00068     proj.setModelCoefficients(coefficients);
00069     proj.filter(*points_);
00070     pcl::ExtractIndices<pcl::PointXYZ> ex;
00071     ex.setInputCloud(cloud);
00072     ex.setIndices(indices);
00073     ex.filter(*raw_points_);
00074   }
00075 
00076   LineSegment::~LineSegment()
00077   {
00078   }
00079 
00080   Line::Ptr LineSegment::toSegment()
00081   {
00082     // we suppose the first and the last point should be the end points
00083     // return Segment::Ptr(
00084     //   new Segment(
00085     //     points_->points[0].getVector3fMap(),
00086     //     points_->points[points_->points.size() - 1].getVector3fMap()));
00087     Eigen::Vector3f direction;
00088     direction[0] = coefficients_->values[3];
00089     direction[1] = coefficients_->values[4];
00090     direction[2] = coefficients_->values[5];
00091     return Line::Ptr(new Line(direction,
00092                               points_->points[0].getVector3fMap()));
00093     // return Segment::Ptr(
00094     //   new Segment(
00095     //     points_->points[0].getVector3fMap(),
00096     //     points_->points[points_->points.size() - 1].getVector3fMap()));
00097   }
00098   
00099   void LineSegment::addMarkerLine(
00100     visualization_msgs::Marker& marker,
00101     const pcl::PointCloud<pcl::PointXYZ>::Ptr& cloud)
00102   {
00103     // lookup minimum and max index
00104     int min_index = INT_MAX;
00105     int max_index = - INT_MAX;
00106     for (size_t i = 0; i < indices_->indices.size(); i++) {
00107       int index = indices_->indices[i];
00108       if (min_index > index) {
00109         min_index = index;
00110       }
00111       if (max_index < index) {
00112         max_index = index;
00113       }
00114     }
00115     geometry_msgs::Point a, b;
00116     pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
00117       cloud->points[min_index], a);
00118     pointFromXYZToXYZ<pcl::PointXYZ, geometry_msgs::Point>(
00119       cloud->points[max_index], b);
00120     marker.points.push_back(a);
00121     marker.points.push_back(b);
00122   }
00123   
00124   void LineSegmentDetector::onInit()
00125   {
00126     DiagnosticNodelet::onInit();
00127 
00128     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00129     dynamic_reconfigure::Server<Config>::CallbackType f =
00130       boost::bind (&LineSegmentDetector::configCallback, this, _1, _2);
00131     srv_->setCallback (f);
00132     
00134     // setup publishers
00136     pub_line_marker_ = advertise<visualization_msgs::Marker>(
00137       *pnh_, "debug/line_marker", 1);
00138     pub_indices_ = advertise<jsk_recognition_msgs::ClusterPointIndices>(
00139       *pnh_, "output/inliers", 1);
00140     pub_coefficients_ = advertise<jsk_recognition_msgs::ModelCoefficientsArray>(
00141       *pnh_, "output/coefficients", 1);
00142 
00143   }
00144 
00145   void LineSegmentDetector::configCallback(Config &config, uint32_t level)
00146   {
00147     boost::mutex::scoped_lock lock(mutex_);
00148     outlier_threshold_ = config.outlier_threshold;
00149     max_iterations_ = config.max_iterations;
00150     min_indices_ = config.min_indices;
00151     min_length_ = config.min_length;
00152   }
00153   
00154   void LineSegmentDetector::subscribe()
00155   {
00156     sub_input_.subscribe(*pnh_, "input", 1);
00157     sub_indices_.subscribe(*pnh_, "input_indices", 1);
00158     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00159     sync_->connectInput(sub_input_, sub_indices_);
00160     sync_->registerCallback(boost::bind(&LineSegmentDetector::segment,
00161                                         this, _1, _2));
00162   }
00163 
00164   void LineSegmentDetector::unsubscribe()
00165   {
00166     sub_input_.unsubscribe();
00167     sub_indices_.unsubscribe();
00168   }
00169 
00170   void LineSegmentDetector::updateDiagnostic(
00171     diagnostic_updater::DiagnosticStatusWrapper &stat)
00172   {
00173   }
00174 
00175   void LineSegmentDetector::publishResult(
00176     const std_msgs::Header& header,
00177     const pcl::PointCloud<PointT>::Ptr& cloud,
00178     const std::vector<LineSegment::Ptr>& segments)
00179   {
00180     std::vector<pcl::PointIndices::Ptr> indices;
00181     std::vector<pcl::ModelCoefficients::Ptr> coefficients;
00182     visualization_msgs::Marker marker;
00183     marker.header = header;
00184     marker.pose.orientation.w = 1.0;
00185     marker.scale.x = 0.01;
00186     marker.type = visualization_msgs::Marker::LINE_LIST;
00187     marker.color.a = 1.0;
00188     marker.color.r = 1.0;
00189     for (size_t i = 0; i < segments.size(); i++) {
00190       indices.push_back(segments[i]->getIndices());
00191       coefficients.push_back(segments[i]->getCoefficients());
00192       segments[i]->addMarkerLine(marker, cloud);
00193       std_msgs::ColorRGBA color = jsk_topic_tools::colorCategory20(i);
00194       color.a = 1.0;
00195       marker.colors.push_back(color);
00196     }
00197 
00198     jsk_recognition_msgs::ModelCoefficientsArray ros_coefficients;
00199     jsk_recognition_msgs::ClusterPointIndices ros_indices;
00200     ros_coefficients.header = header;
00201     ros_indices.header = header;
00202     ros_coefficients.coefficients
00203       = pcl_conversions::convertToROSModelCoefficients(
00204         coefficients, header);
00205     ros_indices.cluster_indices
00206       = pcl_conversions::convertToROSPointIndices(
00207         indices, header);
00208     pub_indices_.publish(ros_indices);
00209     pub_coefficients_.publish(ros_coefficients);
00210     pub_line_marker_.publish(marker);
00211   }
00212   
00213   void LineSegmentDetector::segmentLines(
00214     const pcl::PointCloud<PointT>::Ptr& cloud,
00215     const pcl::PointIndices::Ptr& indices,
00216     std::vector<pcl::PointIndices::Ptr>& line_indices,
00217     std::vector<pcl::ModelCoefficients::Ptr>& line_coefficients)
00218   {
00219     boost::mutex::scoped_lock lock(mutex_);
00220     pcl::PointIndices::Ptr rest_indices (new pcl::PointIndices);
00221     rest_indices->indices = indices->indices;
00222     // use RANSAC to segment lines
00223     pcl::SACSegmentation<PointT> seg;
00224     seg.setOptimizeCoefficients (true);
00225     seg.setModelType (pcl::SACMODEL_LINE);
00226     seg.setMethodType (pcl::SAC_RANSAC);
00227     seg.setDistanceThreshold (outlier_threshold_);
00228     seg.setMaxIterations (max_iterations_);
00229     seg.setInputCloud(cloud);
00230     while (true) {
00231       if (rest_indices->indices.size() > min_indices_) {
00232         pcl::PointIndices::Ptr
00233           result_indices (new pcl::PointIndices);
00234         pcl::ModelCoefficients::Ptr
00235           result_coefficients (new pcl::ModelCoefficients);
00236         seg.setIndices(rest_indices);
00237         seg.segment(*result_indices, *result_coefficients);
00238         if (result_indices->indices.size() > min_indices_) {
00239           line_indices.push_back(result_indices);
00240           line_coefficients.push_back(result_coefficients);
00241           rest_indices = subIndices(*rest_indices, *result_indices);
00242         }
00243         else {
00244           break;
00245         }
00246       }
00247       else {
00248         break;
00249       }
00250     }
00251     
00252   }
00253   
00254   void LineSegmentDetector::segment(
00255     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
00256     const jsk_recognition_msgs::ClusterPointIndices::ConstPtr& cluster_msg)
00257   {
00258     pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>);
00259     pcl::fromROSMsg(*cloud_msg, *cloud);
00260     std::vector<LineSegment::Ptr> segments;
00261     std::vector<pcl::PointIndices::Ptr> input_indices
00262       = pcl_conversions::convertToPCLPointIndices(cluster_msg->cluster_indices);
00263     // for each cluster
00264     for (size_t i = 0; i < cluster_msg->cluster_indices.size(); i++) {
00265       std::vector<pcl::PointIndices::Ptr> line_indices;
00266       std::vector<pcl::ModelCoefficients::Ptr> line_coefficients;
00267       segmentLines(cloud, input_indices[i],
00268                    line_indices, line_coefficients);
00269       if (line_indices.size() > 0) {
00270         // update lines
00271         for (size_t j = 0; j < line_indices.size(); j++) {
00272           segments.push_back(
00273             LineSegment::Ptr(new LineSegment(line_indices[j],
00274                                              line_coefficients[j])));
00275         }
00276       }
00277     }
00278     // publish result
00279     publishResult(cloud_msg->header, cloud, segments);
00280   }
00281   
00282 }
00283 
00284 #include <pluginlib/class_list_macros.h>
00285 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::LineSegmentDetector,
00286                         nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:47