extract_polygonal_prism_data.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: extract_polygonal_prism_data.hpp 32996 2010-09-30 23:42:11Z rusu $
35  *
36  */
37 
39 #include "pcl_ros/transforms.h"
41 #include <pcl/io/io.h>
42 
44 
47 
49 void
51 {
52  // Call the super onInit ()
54 
55  // Enable the dynamic reconfigure service
56  srv_ = boost::make_shared <dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > (*pnh_);
57  dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig>::CallbackType f = boost::bind (&ExtractPolygonalPrismData::config_callback, this, _1, _2);
58  srv_->setCallback (f);
59 
60  // Advertise the output topics
61  pub_output_ = advertise<PointIndices> (*pnh_, "output", max_queue_size_);
62 
64 }
65 
67 void
69 {
72 
73  // Create the objects here
75  sync_input_hull_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
76  else
77  sync_input_hull_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > (max_queue_size_);
78 
79  if (use_indices_)
80  {
84  else
85  sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, sub_indices_filter_);
86  }
87  else
88  {
90 
93  else
94  sync_input_hull_indices_e_->connectInput (sub_input_filter_, sub_hull_filter_, nf_);
95  }
96  // Register callbacks
98  sync_input_hull_indices_a_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
99  else
100  sync_input_hull_indices_e_->registerCallback (bind (&ExtractPolygonalPrismData::input_hull_indices_callback, this, _1, _2, _3));
101 }
102 
104 void
106 {
109 
110  if (use_indices_)
112 }
113 
115 void
116 pcl_ros::ExtractPolygonalPrismData::config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level)
117 {
118  double height_min, height_max;
119  impl_.getHeightLimits (height_min, height_max);
120  if (height_min != config.height_min)
121  {
122  height_min = config.height_min;
123  NODELET_DEBUG ("[%s::config_callback] Setting new minimum height to the planar model to: %f.", getName ().c_str (), height_min);
124  impl_.setHeightLimits (height_min, height_max);
125  }
126  if (height_max != config.height_max)
127  {
128  height_max = config.height_max;
129  NODELET_DEBUG ("[%s::config_callback] Setting new maximum height to the planar model to: %f.", getName ().c_str (), height_max);
130  impl_.setHeightLimits (height_min, height_max);
131  }
132 }
133 
135 void
137  const PointCloudConstPtr &cloud,
138  const PointCloudConstPtr &hull,
139  const PointIndicesConstPtr &indices)
140 {
141  // No subscribers, no work
142  if (pub_output_.getNumSubscribers () <= 0)
143  return;
144 
145  // Copy the header (stamp + frame_id)
146  pcl_msgs::PointIndices inliers;
147  inliers.header = fromPCL(cloud->header);
148 
149  // If cloud is given, check if it's valid
150  if (!isValid (cloud) || !isValid (hull, "planar_hull"))
151  {
152  NODELET_ERROR ("[%s::input_hull_indices_callback] Invalid input!", getName ().c_str ());
153  pub_output_.publish (inliers);
154  return;
155  }
156  // If indices are given, check if they are valid
157  if (indices && !isValid (indices))
158  {
159  NODELET_ERROR ("[%s::input_hull_indices_callback] Invalid indices!", getName ().c_str ());
160  pub_output_.publish (inliers);
161  return;
162  }
163 
165  if (indices)
166  NODELET_DEBUG ("[%s::input_indices_hull_callback]\n"
167  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
168  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
169  " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
170  getName ().c_str (),
171  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
172  hull->width * hull->height, pcl::getFieldsList (*hull).c_str (), fromPCL(hull->header).stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName ("planar_hull").c_str (),
173  indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName ("indices").c_str ());
174  else
175  NODELET_DEBUG ("[%s::input_indices_hull_callback]\n"
176  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
177  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
178  getName ().c_str (),
179  cloud->width * cloud->height, pcl::getFieldsList (*cloud).c_str (), fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName ("input").c_str (),
180  hull->width * hull->height, pcl::getFieldsList (*hull).c_str (), fromPCL(hull->header).stamp.toSec (), hull->header.frame_id.c_str (), pnh_->resolveName ("planar_hull").c_str ());
182 
183  if (cloud->header.frame_id != hull->header.frame_id)
184  {
185  NODELET_DEBUG ("[%s::input_hull_callback] Planar hull has a different TF frame (%s) than the input point cloud (%s)! Using TF to transform.", getName ().c_str (), hull->header.frame_id.c_str (), cloud->header.frame_id.c_str ());
186  PointCloud planar_hull;
187  if (!pcl_ros::transformPointCloud (cloud->header.frame_id, *hull, planar_hull, tf_listener_))
188  {
189  // Publish empty before return
190  pub_output_.publish (inliers);
191  return;
192  }
193  impl_.setInputPlanarHull (planar_hull.makeShared ());
194  }
195  else
196  impl_.setInputPlanarHull (hull);
197 
198  IndicesPtr indices_ptr;
199  if (indices && !indices->header.frame_id.empty ())
200  indices_ptr.reset (new std::vector<int> (indices->indices));
201 
202  impl_.setInputCloud (cloud);
203  impl_.setIndices (indices_ptr);
204 
205  // Final check if the data is empty (remember that indices are set to the size of the data -- if indices* = NULL)
206  if (!cloud->points.empty ()) {
207  pcl::PointIndices pcl_inliers;
208  moveToPCL(inliers, pcl_inliers);
209  impl_.segment (pcl_inliers);
210  moveFromPCL(pcl_inliers, inliers);
211  }
212  // Enforce that the TF frame and the timestamp are copied
213  inliers.header = fromPCL(cloud->header);
214  pub_output_.publish (inliers);
215  NODELET_DEBUG ("[%s::input_hull_callback] Publishing %zu indices.", getName ().c_str (), inliers.indices.size ());
216 }
217 
220 
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
#define NODELET_ERROR(...)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
Definition: pcl_nodelet.h:203
void publish(const boost::shared_ptr< M > &message) const
f
const std::string & getName() const
void onInit()
Nodelet initialization routine.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_e_
Synchronized input, planar hull, and indices.
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
Definition: pcl_nodelet.h:121
ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it.
bool isValid(const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-ze...
Definition: pcl_nodelet.h:140
ros::Publisher pub_output_
The output PointIndices publisher.
void input_callback(const PointCloudConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
void input_hull_indices_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_a_
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: pcl_nodelet.h:77
message_filters::Subscriber< PointCloud > sub_hull_filter_
The message filter subscriber for PointCloud2.
tf::TransformListener tf_listener_
TF listener object.
Definition: pcl_nodelet.h:133
PLUGINLIB_EXPORT_CLASS(CropBox, nodelet::Nodelet)
PointCloud::ConstPtr PointCloudConstPtr
Definition: pcl_nodelet.h:79
uint32_t getNumSubscribers() const
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)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
Apply a rigid transform defined by a 3D offset and a quaternion.
Definition: transforms.hpp:71
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
Definition: pcl_nodelet.h:130
int max_queue_size_
The maximum queue size (default: 3).
Definition: pcl_nodelet.h:127
pcl::ExtractPolygonalPrismData< pcl::PointXYZ > impl_
The PCL implementation used.
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
void subscribe()
LazyNodelet connection routine.
message_filters::PassThrough< PointIndices > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
void config_callback(ExtractPolygonalPrismDataConfig &config, uint32_t level)
Dynamic reconfigure callback.
#define NODELET_DEBUG(...)
bool use_indices_
Set to true if point indices are used.
Definition: pcl_nodelet.h:94
boost::shared_ptr< dynamic_reconfigure::Server< ExtractPolygonalPrismDataConfig > > srv_
Pointer to a dynamic reconfigure service.
void moveToPCL(sensor_msgs::Image &image, pcl::PCLImage &pcl_image)
PointIndices::ConstPtr PointIndicesConstPtr
Definition: pcl_nodelet.h:83
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
Definition: pcl_nodelet.h:118
pcl_ros::ExtractPolygonalPrismData ExtractPolygonalPrismData
Connection registerCallback(const C &callback)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18