35 #define BOOST_PARAMETER_MAX_ARITY 7 
   38 #include <jsk_topic_tools/rosparam_utils.h> 
   39 #include <pcl/sample_consensus/method_types.h> 
   40 #include <pcl/sample_consensus/model_types.h> 
   41 #include <pcl/segmentation/sac_segmentation.h> 
   42 #include <pcl/filters/voxel_grid.h> 
   48     DiagnosticNodelet::onInit();
 
   49     pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
 
   50     pnh_->param(
"use_hint", 
use_hint_, 
false);
 
   52       if (pnh_->hasParam(
"initial_axis_hint")) {
 
   53         std::vector<double> axis;
 
   54         jsk_topic_tools::readVectorParameter(*pnh_, 
"initial_axis_hint", axis);
 
   55         if (axis.size() == 3) {
 
   68     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   69     typename dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   71     srv_->setCallback (
f);
 
   73     pub_torus_ = advertise<jsk_recognition_msgs::Torus>(*pnh_, 
"output", 1);
 
   74     pub_torus_array_ = advertise<jsk_recognition_msgs::TorusArray>(*pnh_, 
"output/array", 1);
 
   77     pub_inliers_ = advertise<PCLIndicesMsg>(*pnh_, 
"output/inliers", 1);
 
   78     pub_pose_stamped_ = advertise<geometry_msgs::PoseStamped>(*pnh_, 
"output/pose", 1);
 
   80       *pnh_, 
"output/coefficients", 1);
 
   82       *pnh_, 
"output/latest_time", 1);
 
   84       *pnh_, 
"output/average_time", 1);
 
  117     const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg)
 
  124     pcl::PointCloud<pcl::PointNormal>::Ptr 
cloud 
  125       (
new pcl::PointCloud<pcl::PointNormal>);
 
  128       pcl::PointNormal pcl_point;
 
  132       cloud->points.push_back(pcl_point);
 
  134     sensor_msgs::PointCloud2 ros_cloud;
 
  137     segment(boost::make_shared<sensor_msgs::PointCloud2>(ros_cloud));
 
  141     const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
 
  147     vital_checker_->poke();
 
  148     pcl::PointCloud<pcl::PointNormal>::Ptr 
cloud 
  149       (
new pcl::PointCloud<pcl::PointNormal>);
 
  154       pcl::PointCloud<pcl::PointNormal>::Ptr downsampled_cloud
 
  155       (
new pcl::PointCloud<pcl::PointNormal>);
 
  156       pcl::VoxelGrid<pcl::PointNormal> sor;
 
  157       sor.setInputCloud (
cloud);
 
  159       sor.filter (*downsampled_cloud);
 
  160       cloud = downsampled_cloud;
 
  163     pcl::SACSegmentation<pcl::PointNormal> seg;
 
  165       pcl::SACSegmentationFromNormals<pcl::PointNormal, pcl::PointNormal> seg_normal;
 
  166       seg_normal.setInputNormals(
cloud);
 
  171     seg.setOptimizeCoefficients (
true);
 
  172     seg.setInputCloud(
cloud);
 
  175       seg.setMethodType(pcl::SAC_RANSAC);
 
  178       seg.setMethodType(pcl::SAC_LMEDS);
 
  181       seg.setMethodType(pcl::SAC_MSAC);
 
  184       seg.setMethodType(pcl::SAC_RRANSAC);
 
  187       seg.setMethodType(pcl::SAC_RMSAC);
 
  190       seg.setMethodType(pcl::SAC_MLESAC);
 
  193       seg.setMethodType(pcl::SAC_PROSAC);
 
  198     seg.setModelType(pcl::SACMODEL_CIRCLE3D);
 
  203     pcl::PointIndices::Ptr inliers (
new pcl::PointIndices);
 
  204     pcl::ModelCoefficients::Ptr 
coefficients (
new pcl::ModelCoefficients);
 
  207     if (inliers->indices.size() > 
min_size_) {
 
  213       if (dir.dot(Eigen::Vector3f::UnitZ()) < 0) {
 
  217       Eigen::Affine3f 
pose = Eigen::Affine3f::Identity();
 
  221       Eigen::Quaternionf 
rot;
 
  222       rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), dir);
 
  225       ros_inliers.indices = inliers->indices;
 
  226       ros_inliers.header = cloud_msg->header;
 
  230       ros_coefficients.header = cloud_msg->header;
 
  232       jsk_recognition_msgs::Torus torus_msg;
 
  233       torus_msg.header = cloud_msg->header;
 
  235       torus_msg.small_radius = 0.01;
 
  238       jsk_recognition_msgs::TorusArray torus_array_msg;
 
  239       torus_array_msg.header = cloud_msg->header;
 
  240       torus_array_msg.toruses.push_back(torus_msg);
 
  243       geometry_msgs::PoseStamped pose_stamped;
 
  244       pose_stamped.header = torus_msg.header;
 
  245       pose_stamped.pose = torus_msg.pose;
 
  251       jsk_recognition_msgs::Torus torus_msg;
 
  252       torus_msg.header = cloud_msg->header;
 
  253       torus_msg.failure = 
true;
 
  255       jsk_recognition_msgs::TorusArray torus_array_msg;
 
  256       torus_array_msg.header = cloud_msg->header;
 
  257       torus_array_msg.toruses.push_back(torus_msg);