polygon_points_sampler_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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
39 
40 namespace jsk_pcl_ros_utils
41 {
43  {
44  DiagnosticNodelet::onInit();
45  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
46  typename dynamic_reconfigure::Server<Config>::CallbackType f =
47  boost::bind (&PolygonPointsSampler::configCallback, this, _1, _2);
48  srv_->setCallback (f);
49 
50  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
51  pub_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_xyz", 1);
52 
54  }
55 
57  {
58  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
59  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
60  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
61  sync_->connectInput(sub_polygons_, sub_coefficients_);
62  sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, _1, _2));
63  }
64 
66  {
69  }
70 
72  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
73  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
74  {
75  if (polygon_msg->polygons.size() == 0) {
76  NODELET_DEBUG("empty polygons");
77  return false;
78  }
79  if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
80  NODELET_ERROR("The size of coefficients and polygons are not same");
81  return false;
82  }
83 
84  std::string frame_id = polygon_msg->header.frame_id;
85  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
86  if (frame_id != polygon_msg->polygons[i].header.frame_id) {
87  NODELET_ERROR("Frame id of polygon is not same: %s, %s",
88  frame_id.c_str(),
89  polygon_msg->polygons[i].header.frame_id.c_str());
90  return false;
91  }
92  }
93  for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
94  if (frame_id != coefficients_msg->coefficients[i].header.frame_id) {
95  NODELET_ERROR("Frame id of coefficient is not same: %s, %s",
96  frame_id.c_str(),
97  coefficients_msg->coefficients[i].header.frame_id.c_str());
98  return false;
99  }
100  }
101  return true;
102  }
103 
105  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
106  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
107  {
108  boost::mutex::scoped_lock lock(mutex_);
109  vital_checker_->poke();
110  // check frame_ids
111  if (!isValidMessage(polygon_msg, coefficients_msg)) {
112  return;
113  }
114  // Sample points...
115  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
116  pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (new pcl::PointCloud<pcl::PointXYZ>);
117  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
119  = jsk_recognition_utils::Polygon::fromROSMsg(polygon_msg->polygons[i].polygon);
120  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
121  = polygon.samplePoints<pcl::PointXYZRGBNormal>(grid_size_);
122  pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
123  one_xyz_cloud.points.resize(one_cloud->points.size());
124  for (size_t i = 0; i < one_cloud->points.size(); i++) {
125  pcl::PointXYZ p;
126  p.getVector3fMap() = one_cloud->points[i].getVector3fMap();
127  one_xyz_cloud.points[i] = p;
128  }
129  *xyz_cloud = *xyz_cloud + one_xyz_cloud;
130  *cloud = *cloud + *one_cloud;
131  }
132  sensor_msgs::PointCloud2 ros_cloud;
133  pcl::toROSMsg(*cloud, ros_cloud);
134  ros_cloud.header = polygon_msg->header;
135  pub_.publish(ros_cloud);
136  sensor_msgs::PointCloud2 ros_xyz_cloud;
137  pcl::toROSMsg(*xyz_cloud, ros_xyz_cloud);
138  ros_xyz_cloud.header = polygon_msg->header;
139  pub_xyz_.publish(ros_xyz_cloud);
140  }
141 
142 
143  void PolygonPointsSampler::configCallback(Config& config, uint32_t level)
144  {
145  boost::mutex::scoped_lock lock(mutex_);
146  grid_size_ = config.grid_size;
147  }
148 }
149 
f
virtual void configCallback(Config &config, uint32_t level)
lock
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
virtual void sample(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
static Polygon fromROSMsg(const geometry_msgs::Polygon &polygon)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonPointsSampler, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
virtual bool isValidMessage(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
pcl::PointCloud< PointT >::Ptr samplePoints(double grid_size)
p
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
#define NODELET_DEBUG(...)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:15