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/or 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 
53  onInitPostProcess();
54  }
55 
57  // message_filters::Synchronizer needs to be called reset
58  // before message_filters::Subscriber is freed.
59  // Calling reset fixes the following error on shutdown of the nodelet:
60  // terminate called after throwing an instance of
61  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
62  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
63  // Also see https://github.com/ros/ros_comm/issues/720 .
64  sync_.reset();
65  }
66 
68  {
69  sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
70  sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
71  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
72  sync_->connectInput(sub_polygons_, sub_coefficients_);
73  sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, _1, _2));
74  }
75 
77  {
80  }
81 
83  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
84  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
85  {
86  if (polygon_msg->polygons.size() == 0) {
87  NODELET_DEBUG("empty polygons");
88  return false;
89  }
90  if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
91  NODELET_ERROR("The size of coefficients and polygons are not same");
92  return false;
93  }
94 
95  std::string frame_id = polygon_msg->header.frame_id;
96  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
97  if (frame_id != polygon_msg->polygons[i].header.frame_id) {
98  NODELET_ERROR("Frame id of polygon is not same: %s, %s",
99  frame_id.c_str(),
100  polygon_msg->polygons[i].header.frame_id.c_str());
101  return false;
102  }
103  }
104  for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
105  if (frame_id != coefficients_msg->coefficients[i].header.frame_id) {
106  NODELET_ERROR("Frame id of coefficient is not same: %s, %s",
107  frame_id.c_str(),
108  coefficients_msg->coefficients[i].header.frame_id.c_str());
109  return false;
110  }
111  }
112  return true;
113  }
114 
116  const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
117  const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
118  {
119  boost::mutex::scoped_lock lock(mutex_);
120  vital_checker_->poke();
121  // check frame_ids
122  if (!isValidMessage(polygon_msg, coefficients_msg)) {
123  return;
124  }
125  // Sample points...
126  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
127  pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (new pcl::PointCloud<pcl::PointXYZ>);
128  for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
130  = jsk_recognition_utils::Polygon::fromROSMsg(polygon_msg->polygons[i].polygon);
131  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
132  = polygon.samplePoints<pcl::PointXYZRGBNormal>(grid_size_);
133  pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
134  one_xyz_cloud.points.resize(one_cloud->points.size());
135  for (size_t i = 0; i < one_cloud->points.size(); i++) {
136  pcl::PointXYZ p;
137  p.getVector3fMap() = one_cloud->points[i].getVector3fMap();
138  one_xyz_cloud.points[i] = p;
139  }
140  *xyz_cloud = *xyz_cloud + one_xyz_cloud;
141  *cloud = *cloud + *one_cloud;
142  }
143  sensor_msgs::PointCloud2 ros_cloud;
144  pcl::toROSMsg(*cloud, ros_cloud);
145  ros_cloud.header = polygon_msg->header;
146  pub_.publish(ros_cloud);
147  sensor_msgs::PointCloud2 ros_xyz_cloud;
148  pcl::toROSMsg(*xyz_cloud, ros_xyz_cloud);
149  ros_xyz_cloud.header = polygon_msg->header;
150  pub_xyz_.publish(ros_xyz_cloud);
151  }
152 
153 
154  void PolygonPointsSampler::configCallback(Config& config, uint32_t level)
155  {
156  boost::mutex::scoped_lock lock(mutex_);
157  grid_size_ = config.grid_size;
158  }
159 }
160 
jsk_pcl_ros_utils
Definition: add_point_indices.h:51
sample_camera_info_and_pointcloud_publisher.frame_id
frame_id
Definition: sample_camera_info_and_pointcloud_publisher.py:14
jsk_pcl_ros_utils::PolygonPointsSampler
Definition: polygon_points_sampler.h:86
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros_utils::PolygonPointsSampler, nodelet::Nodelet)
NODELET_ERROR
#define NODELET_ERROR(...)
_2
boost::arg< 2 > _2
i
int i
p
p
lock
lock
jsk_pcl_ros_utils::PolygonPointsSampler::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: polygon_points_sampler_nodelet.cpp:154
jsk_recognition_utils::Polygon
jsk_pcl_ros_utils::PolygonPointsSampler::sample
virtual void sample(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: polygon_points_sampler_nodelet.cpp:115
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
sample_camera_info_and_pointcloud_publisher.cloud
cloud
Definition: sample_camera_info_and_pointcloud_publisher.py:30
jsk_pcl_ros_utils::PolygonPointsSampler::mutex_
boost::mutex mutex_
Definition: polygon_points_sampler.h:146
jsk_pcl_ros_utils::PolygonPointsSampler::unsubscribe
virtual void unsubscribe()
Definition: polygon_points_sampler_nodelet.cpp:76
jsk_pcl_ros_utils::PolygonPointsSampler::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: polygon_points_sampler.h:141
class_list_macros.h
jsk_recognition_utils::Polygon::fromROSMsg
static Polygon fromROSMsg(const geometry_msgs::Polygon &polygon)
jsk_pcl_ros_utils::PolygonPointsSampler::isValidMessage
virtual bool isValidMessage(const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg, const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr &coefficients_msg)
Definition: polygon_points_sampler_nodelet.cpp:82
jsk_recognition_utils::Polygon::samplePoints
pcl::PointCloud< PointT >::Ptr samplePoints(double grid_size)
polygon_points_sampler.h
jsk_pcl_ros_utils::PolygonPointsSampler::pub_
ros::Publisher pub_
Definition: polygon_points_sampler.h:147
_1
boost::arg< 1 > _1
jsk_pcl_ros_utils::PolygonPointsSampler::onInit
virtual void onInit()
Definition: polygon_points_sampler_nodelet.cpp:42
jsk_pcl_ros_utils::PolygonPointsSampler::subscribe
virtual void subscribe()
Definition: polygon_points_sampler_nodelet.cpp:67
pcl_conversion_util.h
jsk_pcl_ros_utils::PolygonPointsSampler::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: polygon_points_sampler.h:143
message_filters::Subscriber::subscribe
void subscribe()
f
f
nodelet::Nodelet
jsk_pcl_ros_utils::PolygonPointsSampler::Config
PolygonPointsSamplerConfig Config
Definition: polygon_points_sampler.h:122
jsk_pcl_ros_utils::PolygonPointsSampler::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: polygon_points_sampler.h:142
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
jsk_pcl_ros_utils::PolygonPointsSampler::~PolygonPointsSampler
virtual ~PolygonPointsSampler()
Definition: polygon_points_sampler_nodelet.cpp:56
jsk_pcl_ros_utils::PolygonPointsSampler::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: polygon_points_sampler.h:144
jsk_pcl_ros_utils::PolygonPointsSampler::pub_xyz_
ros::Publisher pub_xyz_
Definition: polygon_points_sampler.h:148
config
config
jsk_pcl_ros_utils::PolygonPointsSampler::grid_size_
double grid_size_
Definition: polygon_points_sampler.h:149
NODELET_DEBUG
#define NODELET_DEBUG(...)


jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43