segment_differences.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: segment_differences.cpp 35361 2011-01-20 04:34:49Z rusu $
35  *
36  */
37 
40 #include <pcl/io/io.h>
41 
43 void
45 {
46  // Call the super onInit ()
48 
49  pub_output_ = advertise<PointCloud> (*pnh_, "output", max_queue_size_);
50 
51  NODELET_DEBUG ("[%s::onInit] Nodelet successfully created with the following parameters:\n"
52  " - max_queue_size : %d",
53  getName ().c_str (),
55 
57 }
58 
60 void
62 {
63  // Subscribe to the input using a filter
66 
67  // Enable the dynamic reconfigure service
68  srv_ = boost::make_shared <dynamic_reconfigure::Server<SegmentDifferencesConfig> > (*pnh_);
69  dynamic_reconfigure::Server<SegmentDifferencesConfig>::CallbackType f = boost::bind (&SegmentDifferences::config_callback, this, _1, _2);
70  srv_->setCallback (f);
71 
73  {
74  sync_input_target_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud> > > (max_queue_size_);
76  sync_input_target_a_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, _1, _2));
77  }
78  else
79  {
80  sync_input_target_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud> > > (max_queue_size_);
82  sync_input_target_e_->registerCallback (bind (&SegmentDifferences::input_target_callback, this, _1, _2));
83  }
84 }
85 
87 void
89 {
92 }
93 
95 void
96 pcl_ros::SegmentDifferences::config_callback (SegmentDifferencesConfig &config, uint32_t level)
97 {
98  if (impl_.getDistanceThreshold () != config.distance_threshold)
99  {
100  impl_.setDistanceThreshold (config.distance_threshold);
101  NODELET_DEBUG ("[%s::config_callback] Setting new distance threshold to: %f.", getName ().c_str (), config.distance_threshold);
102  }
103 }
104 
105 
107 void
109  const PointCloudConstPtr &cloud_target)
110 {
111  if (pub_output_.getNumSubscribers () <= 0)
112  return;
113 
114  if (!isValid (cloud) || !isValid (cloud_target, "target"))
115  {
116  NODELET_ERROR ("[%s::input_indices_callback] Invalid input!", getName ().c_str ());
117  PointCloud output;
118  output.header = cloud->header;
119  pub_output_.publish (output.makeShared ());
120  return;
121  }
122 
123  NODELET_DEBUG ("[%s::input_indices_callback]\n"
124  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n"
125  " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
126  getName ().c_str (),
127  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 (),
128  cloud_target->width * cloud_target->height, pcl::getFieldsList (*cloud_target).c_str (), fromPCL(cloud_target->header).stamp.toSec (), cloud_target->header.frame_id.c_str (), pnh_->resolveName ("target").c_str ());
129 
130  impl_.setInputCloud (cloud);
131  impl_.setTargetCloud (cloud_target);
132 
133  PointCloud output;
134  impl_.segment (output);
135 
136  pub_output_.publish (output.makeShared ());
137  NODELET_DEBUG ("[%s::segmentAndPublish] Published PointCloud2 with %zu points and stamp %f on topic %s", getName ().c_str (),
138  output.points.size (), fromPCL(output.header).stamp.toSec (), pnh_->resolveName ("output").c_str ());
139 }
140 
143 
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
void config_callback(SegmentDifferencesConfig &config, uint32_t level)
Dynamic reconfigure callback.
f
const std::string & getName() const
SegmentDifferences()
Empty constructor.
void onInit()
Nodelet initialization routine.
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
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud > > > sync_input_target_a_
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
boost::shared_ptr< ros::NodeHandle > pnh_
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud > > > sync_input_target_e_
Synchronized input, and planar hull.
pcl::PointCloud< pcl::PointXYZ > PointCloud
Definition: pcl_nodelet.h:77
void input_target_callback(const PointCloudConstPtr &cloud, const PointCloudConstPtr &cloud_target)
Input point cloud callback.
pcl::SegmentDifferences< pcl::PointXYZ > impl_
The PCL implementation used.
boost::shared_ptr< dynamic_reconfigure::Server< SegmentDifferencesConfig > > srv_
Pointer to a dynamic reconfigure service.
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)
message_filters::Subscriber< PointCloud > sub_target_filter_
The message filter subscriber for PointCloud2.
void subscribe()
LazyNodelet connection routine.
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
ros::Publisher pub_output_
The output PointCloud publisher.
Definition: pcl_nodelet.h:124
#define NODELET_DEBUG(...)
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the ...
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
Definition: pcl_nodelet.h:118


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:52