torus_finder_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 #define BOOST_PARAMETER_MAX_ARITY 7
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>
43 
44 namespace jsk_pcl_ros
45 {
47  {
48  DiagnosticNodelet::onInit();
49  pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
50  pnh_->param("use_hint", use_hint_, false);
51  if (use_hint_) {
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) {
56  hint_axis_[0] = axis[0];
57  hint_axis_[1] = axis[1];
58  hint_axis_[2] = axis[2];
59  }
60  else {
61  hint_axis_[0] = 0;
62  hint_axis_[1] = 0;
63  hint_axis_[2] = 1;
64  }
65  }
66  }
67  pnh_->param("use_normal", use_normal_, false);
68  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
69  typename dynamic_reconfigure::Server<Config>::CallbackType f =
70  boost::bind (&TorusFinder::configCallback, this, _1, _2);
71  srv_->setCallback (f);
72 
73  pub_torus_ = advertise<jsk_recognition_msgs::Torus>(*pnh_, "output", 1);
74  pub_torus_array_ = advertise<jsk_recognition_msgs::TorusArray>(*pnh_, "output/array", 1);
75  pub_torus_with_failure_ = advertise<jsk_recognition_msgs::Torus>(*pnh_, "output/with_failure", 1);
76  pub_torus_array_with_failure_ = advertise<jsk_recognition_msgs::TorusArray>(*pnh_, "output/with_failure/array", 1);
77  pub_inliers_ = advertise<PCLIndicesMsg>(*pnh_, "output/inliers", 1);
78  pub_pose_stamped_ = advertise<geometry_msgs::PoseStamped>(*pnh_, "output/pose", 1);
79  pub_coefficients_ = advertise<PCLModelCoefficientMsg>(
80  *pnh_, "output/coefficients", 1);
81  pub_latest_time_ = advertise<std_msgs::Float32>(
82  *pnh_, "output/latest_time", 1);
83  pub_average_time_ = advertise<std_msgs::Float32>(
84  *pnh_, "output/average_time", 1);
85 
86  done_initialization_ = true;
88  }
89 
90  void TorusFinder::configCallback(Config &config, uint32_t level)
91  {
92  boost::mutex::scoped_lock lock(mutex_);
93  min_radius_ = config.min_radius;
94  max_radius_ = config.max_radius;
95  outlier_threshold_ = config.outlier_threshold;
96  max_iterations_ = config.max_iterations;
97  min_size_ = config.min_size;
98  eps_hint_angle_ = config.eps_hint_angle;
99  algorithm_ = config.algorithm;
100  voxel_grid_sampling_ = config.voxel_grid_sampling;
101  voxel_size_ = config.voxel_size;
102  }
103 
105  {
106  sub_ = pnh_->subscribe("input", 1, &TorusFinder::segment, this);
107  sub_points_ = pnh_->subscribe("input/polygon", 1, &TorusFinder::segmentFromPoints, this);
108  }
109 
111  {
112  sub_.shutdown();
114  }
115 
117  const geometry_msgs::PolygonStamped::ConstPtr& polygon_msg)
118  {
119  if (!done_initialization_) {
120  return;
121  }
122  // Convert to pointcloud and call it
123  // No normal
124  pcl::PointCloud<pcl::PointNormal>::Ptr cloud
125  (new pcl::PointCloud<pcl::PointNormal>);
126  for (size_t i = 0; i < polygon_msg->polygon.points.size(); i++) {
127  geometry_msgs::Point32 p = polygon_msg->polygon.points[i];
128  pcl::PointNormal pcl_point;
129  pcl_point.x = p.x;
130  pcl_point.y = p.y;
131  pcl_point.z = p.z;
132  cloud->points.push_back(pcl_point);
133  }
134  sensor_msgs::PointCloud2 ros_cloud;
135  pcl::toROSMsg(*cloud, ros_cloud);
136  ros_cloud.header = polygon_msg->header;
137  segment(boost::make_shared<sensor_msgs::PointCloud2>(ros_cloud));
138  }
139 
141  const sensor_msgs::PointCloud2::ConstPtr& cloud_msg)
142  {
143  if (!done_initialization_) {
144  return;
145  }
146  boost::mutex::scoped_lock lock(mutex_);
147  vital_checker_->poke();
148  pcl::PointCloud<pcl::PointNormal>::Ptr cloud
149  (new pcl::PointCloud<pcl::PointNormal>);
150  pcl::fromROSMsg(*cloud_msg, *cloud);
153  if (voxel_grid_sampling_) {
154  pcl::PointCloud<pcl::PointNormal>::Ptr downsampled_cloud
155  (new pcl::PointCloud<pcl::PointNormal>);
156  pcl::VoxelGrid<pcl::PointNormal> sor;
157  sor.setInputCloud (cloud);
158  sor.setLeafSize (voxel_size_, voxel_size_, voxel_size_);
159  sor.filter (*downsampled_cloud);
160  cloud = downsampled_cloud;
161  }
162 
163  pcl::SACSegmentation<pcl::PointNormal> seg;
164  if (use_normal_) {
165  pcl::SACSegmentationFromNormals<pcl::PointNormal, pcl::PointNormal> seg_normal;
166  seg_normal.setInputNormals(cloud);
167  seg = seg_normal;
168  }
169 
170 
171  seg.setOptimizeCoefficients (true);
172  seg.setInputCloud(cloud);
173  seg.setRadiusLimits(min_radius_, max_radius_);
174  if (algorithm_ == "RANSAC") {
175  seg.setMethodType(pcl::SAC_RANSAC);
176  }
177  else if (algorithm_ == "LMEDS") {
178  seg.setMethodType(pcl::SAC_LMEDS);
179  }
180  else if (algorithm_ == "MSAC") {
181  seg.setMethodType(pcl::SAC_MSAC);
182  }
183  else if (algorithm_ == "RRANSAC") {
184  seg.setMethodType(pcl::SAC_RRANSAC);
185  }
186  else if (algorithm_ == "RMSAC") {
187  seg.setMethodType(pcl::SAC_RMSAC);
188  }
189  else if (algorithm_ == "MLESAC") {
190  seg.setMethodType(pcl::SAC_MLESAC);
191  }
192  else if (algorithm_ == "PROSAC") {
193  seg.setMethodType(pcl::SAC_PROSAC);
194  }
195 
196  seg.setDistanceThreshold (outlier_threshold_);
197  seg.setMaxIterations (max_iterations_);
198  seg.setModelType(pcl::SACMODEL_CIRCLE3D);
199  if (use_hint_) {
200  seg.setAxis(hint_axis_);
201  seg.setEpsAngle(eps_hint_angle_);
202  }
203  pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
204  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
205  seg.segment(*inliers, *coefficients);
206  NODELET_INFO("input points: %lu", cloud->points.size());
207  if (inliers->indices.size() > min_size_) {
208  // check direction. Torus should direct to origin of pointcloud
209  // always.
210  Eigen::Vector3f dir(coefficients->values[4],
211  coefficients->values[5],
212  coefficients->values[6]);
213  if (dir.dot(Eigen::Vector3f::UnitZ()) < 0) {
214  dir = - dir;
215  }
216 
217  Eigen::Affine3f pose = Eigen::Affine3f::Identity();
218  Eigen::Vector3f pos = Eigen::Vector3f(coefficients->values[0],
219  coefficients->values[1],
220  coefficients->values[2]);
221  Eigen::Quaternionf rot;
222  rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), dir);
223  pose = pose * Eigen::Translation3f(pos) * Eigen::AngleAxisf(rot);
224  PCLIndicesMsg ros_inliers;
225  ros_inliers.indices = inliers->indices;
226  ros_inliers.header = cloud_msg->header;
227  pub_inliers_.publish(ros_inliers);
228  PCLModelCoefficientMsg ros_coefficients;
229  ros_coefficients.values = coefficients->values;
230  ros_coefficients.header = cloud_msg->header;
231  pub_coefficients_.publish(ros_coefficients);
232  jsk_recognition_msgs::Torus torus_msg;
233  torus_msg.header = cloud_msg->header;
234  tf::poseEigenToMsg(pose, torus_msg.pose);
235  torus_msg.small_radius = 0.01;
236  torus_msg.large_radius = coefficients->values[3];
237  pub_torus_.publish(torus_msg);
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);
241  pub_torus_array_.publish(torus_array_msg);
242  // publish pose stamped
243  geometry_msgs::PoseStamped pose_stamped;
244  pose_stamped.header = torus_msg.header;
245  pose_stamped.pose = torus_msg.pose;
246  pub_pose_stamped_.publish(pose_stamped);
247  pub_torus_array_with_failure_.publish(torus_array_msg);
248  pub_torus_with_failure_.publish(torus_msg);
249  }
250  else {
251  jsk_recognition_msgs::Torus torus_msg;
252  torus_msg.header = cloud_msg->header;
253  torus_msg.failure = true;
254  pub_torus_with_failure_.publish(torus_msg);
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);
258  pub_torus_array_with_failure_.publish(torus_array_msg);
259  NODELET_INFO("failed to find torus");
260  }
261  }
262 }
263 
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::TorusFinder, nodelet::Nodelet)
Eigen::Vector3f hint_axis_
Definition: torus_finder.h:83
pos
void publish(const boost::shared_ptr< M > &message) const
void poseEigenToMsg(const Eigen::Affine3d &e, geometry_msgs::Pose &m)
ros::Publisher pub_latest_time_
Definition: torus_finder.h:79
virtual ScopedWallDurationReporter reporter()
coefficients
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void configCallback(Config &config, uint32_t level)
TorusFinderConfig Config
Definition: torus_finder.h:56
pose
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
ros::Publisher pub_torus_
Definition: torus_finder.h:72
virtual void segmentFromPoints(const geometry_msgs::PolygonStamped::ConstPtr &polygon_msg)
ros::Publisher pub_average_time_
Definition: torus_finder.h:80
boost::shared_ptr< ros::NodeHandle > pnh_
ros::Publisher pub_torus_array_
Definition: torus_finder.h:73
rot
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
ros::Publisher pub_torus_with_failure_
Definition: torus_finder.h:74
ros::Publisher pub_torus_array_with_failure_
Definition: torus_finder.h:75
jsk_topic_tools::VitalChecker::Ptr vital_checker_
ros::Publisher pub_coefficients_
Definition: torus_finder.h:77
#define NODELET_INFO(...)
virtual void segment(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
ros::Publisher pub_inliers_
Definition: torus_finder.h:76
ros::Publisher pub_pose_stamped_
Definition: torus_finder.h:78
p
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: torus_finder.h:69
pcl::PointIndices PCLIndicesMsg
cloud
ros::Subscriber sub_
Definition: torus_finder.h:70
pcl::ModelCoefficients PCLModelCoefficientMsg
jsk_recognition_utils::WallDurationTimer timer_
Definition: torus_finder.h:81
ros::Subscriber sub_points_
Definition: torus_finder.h:71


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47