torus_finder_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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/torus_finder.h"
00037 #include "jsk_pcl_ros/pcl_conversion_util.h"
00038 #include <jsk_topic_tools/rosparam_utils.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 #include <pcl/filters/voxel_grid.h>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046   void TorusFinder::onInit()
00047   {
00048     DiagnosticNodelet::onInit();
00049     pnh_->param("use_hint", use_hint_, false);
00050     if (use_hint_) {
00051       if (pnh_->hasParam("initial_axis_hint")) {
00052         std::vector<double> axis;
00053         jsk_topic_tools::readVectorParameter(*pnh_, "initial_axis_hint", axis);
00054         if (axis.size() == 3) {
00055           hint_axis_[0] = axis[0];
00056           hint_axis_[1] = axis[1];
00057           hint_axis_[2] = axis[2];
00058         }
00059         else {
00060           hint_axis_[0] = 0;
00061           hint_axis_[1] = 0;
00062           hint_axis_[2] = 1;
00063         }
00064       }
00065     }
00066     pnh_->param("use_normal", use_normal_, false);
00067     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00068     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00069       boost::bind (&TorusFinder::configCallback, this, _1, _2);
00070     srv_->setCallback (f);
00071 
00072     pub_torus_ = advertise<jsk_recognition_msgs::Torus>(*pnh_, "output", 1);
00073     pub_torus_array_ = advertise<jsk_recognition_msgs::TorusArray>(*pnh_, "output/array", 1);
00074     pub_inliers_ = advertise<PCLIndicesMsg>(*pnh_, "output/inliers", 1);
00075     pub_pose_stamped_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose", 1);
00076     pub_coefficients_ = advertise<PCLModelCoefficientMsg>(
00077       *pnh_, "output/coefficients", 1);
00078   }
00079 
00080   void TorusFinder::configCallback(Config &config, uint32_t level)
00081   {
00082     boost::mutex::scoped_lock lock(mutex_);
00083     min_radius_ = config.min_radius;
00084     max_radius_ = config.max_radius;
00085     outlier_threshold_ = config.outlier_threshold;
00086     max_iterations_ = config.max_iterations;
00087     min_size_ = config.min_size;
00088     eps_hint_angle_ = config.eps_hint_angle;
00089     algorithm_ = config.algorithm;
00090     voxel_grid_sampling_ = config.voxel_grid_sampling;
00091     voxel_size_ = config.voxel_size;
00092   }
00093 
00094   void TorusFinder::subscribe()
00095   {
00096     sub_ = pnh_->subscribe("input", 1, &TorusFinder::segment, this);
00097     sub_points_ = pnh_->subscribe("input/polygon", 1, &TorusFinder::segmentFromPoints, this);
00098   }
00099 
00100   void TorusFinder::unsubscribe()
00101   {
00102     sub_.shutdown();
00103     sub_points_.shutdown();
00104   }
00105 
00106   void TorusFinder::segmentFromPoints(
00107     const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg)
00108   {
00109     // Convert to pointcloud and call it
00110     // No normal
00111     pcl::PointCloud<pcl::PointNormal>::Ptr cloud
00112       (new pcl::PointCloud<pcl::PointNormal>);
00113     for (size_t i = 0; i < polygon_msg->polygon.points.size(); i++) {
00114       geometry_msgs::Point32 p = polygon_msg->polygon.points[i];
00115       pcl::PointNormal pcl_point;
00116       pcl_point.x = p.x;
00117       pcl_point.y = p.y;
00118       pcl_point.z = p.z;
00119       cloud->points.push_back(pcl_point);
00120     }
00121     sensor_msgs::PointCloud2 ros_cloud;
00122     pcl::toROSMsg(*cloud, ros_cloud);
00123     ros_cloud.header = polygon_msg->header;
00124     segment(boost::make_shared<sensor_msgs::PointCloud2>(ros_cloud));
00125   }
00126   
00127   void TorusFinder::segment(
00128     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
00129   {
00130     boost::mutex::scoped_lock lock(mutex_);
00131     vital_checker_->poke();
00132     pcl::PointCloud<pcl::PointNormal>::Ptr cloud
00133       (new pcl::PointCloud<pcl::PointNormal>);
00134     pcl::fromROSMsg(*cloud_msg, *cloud);
00135 
00136     if (voxel_grid_sampling_) {
00137       pcl::PointCloud<pcl::PointNormal>::Ptr downsampled_cloud
00138       (new pcl::PointCloud<pcl::PointNormal>);
00139       pcl::VoxelGrid<pcl::PointNormal> sor;
00140       sor.setInputCloud (cloud);
00141       sor.setLeafSize (voxel_size_, voxel_size_, voxel_size_);
00142       sor.filter (*downsampled_cloud);
00143       cloud = downsampled_cloud;
00144     }
00145     
00146     pcl::SACSegmentation<pcl::PointNormal> seg;
00147     if (use_normal_) {
00148       pcl::SACSegmentationFromNormals<pcl::PointNormal, pcl::PointNormal> seg_normal;
00149       seg_normal.setInputNormals(cloud);
00150       seg = seg_normal;
00151     }
00152 
00153     
00154     seg.setOptimizeCoefficients (true);
00155     seg.setInputCloud(cloud);
00156     seg.setRadiusLimits(min_radius_, max_radius_);
00157     if (algorithm_ == "RANSAC") {
00158       seg.setMethodType(pcl::SAC_RANSAC);
00159     }
00160     else if (algorithm_ == "LMEDS") {
00161       seg.setMethodType(pcl::SAC_LMEDS);
00162     }
00163     else if (algorithm_ == "MSAC") {
00164       seg.setMethodType(pcl::SAC_MSAC);
00165     }
00166     else if (algorithm_ == "RRANSAC") {
00167       seg.setMethodType(pcl::SAC_RRANSAC);
00168     }
00169     else if (algorithm_ == "RMSAC") {
00170       seg.setMethodType(pcl::SAC_RMSAC);
00171     }
00172     else if (algorithm_ == "MLESAC") {
00173       seg.setMethodType(pcl::SAC_MLESAC);
00174     }
00175     else if (algorithm_ == "PROSAC") {
00176       seg.setMethodType(pcl::SAC_PROSAC);
00177     }
00178     
00179     seg.setDistanceThreshold (outlier_threshold_);
00180     seg.setMaxIterations (max_iterations_);
00181     seg.setModelType(pcl::SACMODEL_CIRCLE3D);
00182     if (use_hint_) {
00183       seg.setAxis(hint_axis_);
00184       seg.setEpsAngle(eps_hint_angle_);
00185     }
00186     pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00187     pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00188     seg.segment(*inliers, *coefficients);
00189     JSK_NODELET_INFO("input points: %lu", cloud->points.size());
00190     if (inliers->indices.size() > min_size_) {
00191       // check direction. Torus should direct to origin of pointcloud
00192       // always.
00193       Eigen::Vector3f dir(coefficients->values[4],
00194                           coefficients->values[5],
00195                           coefficients->values[6]);
00196       if (dir.dot(Eigen::Vector3f::UnitZ()) < 0) {
00197         dir = - dir;
00198       }
00199       
00200       Eigen::Affine3f pose = Eigen::Affine3f::Identity();
00201       Eigen::Vector3f pos = Eigen::Vector3f(coefficients->values[0],
00202                                             coefficients->values[1],
00203                                             coefficients->values[2]);
00204       Eigen::Quaternionf rot;
00205       rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), dir);
00206       pose = pose * Eigen::Translation3f(pos) * Eigen::AngleAxisf(rot);
00207       PCLIndicesMsg ros_inliers;
00208       ros_inliers.indices = inliers->indices;
00209       ros_inliers.header = cloud_msg->header;
00210       pub_inliers_.publish(ros_inliers);
00211       PCLModelCoefficientMsg ros_coefficients;
00212       ros_coefficients.values = coefficients->values;
00213       ros_coefficients.header = cloud_msg->header;
00214       pub_coefficients_.publish(ros_coefficients);
00215       jsk_recognition_msgs::Torus torus_msg;
00216       torus_msg.header = cloud_msg->header;
00217       tf::poseEigenToMsg(pose, torus_msg.pose);
00218       torus_msg.small_radius = 0.01;
00219       torus_msg.large_radius = coefficients->values[3];
00220       pub_torus_.publish(torus_msg);
00221       jsk_recognition_msgs::TorusArray torus_array_msg;
00222       torus_array_msg.header = cloud_msg->header;
00223       torus_array_msg.toruses.push_back(torus_msg);
00224       pub_torus_array_.publish(torus_array_msg);
00225       // publish pose stamped
00226       geometry_msgs::PoseStamped pose_stamped;
00227       pose_stamped.header = torus_msg.header;
00228       pose_stamped.pose = torus_msg.pose;
00229       pub_pose_stamped_.publish(pose_stamped);
00230     }
00231     else {
00232       
00233       JSK_NODELET_INFO("failed to find torus");
00234     }
00235   }
00236 }
00237 
00238 #include <pluginlib/class_list_macros.h>
00239 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::TorusFinder, nodelet::Nodelet);


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