voxel_grid.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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: voxel_grid.cpp 35876 2011-02-09 01:04:36Z rusu $
35  *
36  */
37 
40 
42 bool
44 {
45  // Enable the dynamic reconfigure service
46  has_service = true;
47  srv_ = boost::make_shared <dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig> > (nh);
48  dynamic_reconfigure::Server<pcl_ros::VoxelGridConfig>::CallbackType f = boost::bind (&VoxelGrid::config_callback, this, _1, _2);
49  srv_->setCallback (f);
50 
51  return (true);
52 }
53 
55 void
56 pcl_ros::VoxelGrid::filter (const PointCloud2::ConstPtr &input,
57  const IndicesPtr &indices,
58  PointCloud2 &output)
59 {
60  boost::mutex::scoped_lock lock (mutex_);
61  pcl::PCLPointCloud2::Ptr pcl_input(new pcl::PCLPointCloud2);
62  pcl_conversions::toPCL (*(input), *(pcl_input));
63  impl_.setInputCloud (pcl_input);
64  impl_.setIndices (indices);
65  pcl::PCLPointCloud2 pcl_output;
66  impl_.filter (pcl_output);
67  pcl_conversions::moveFromPCL(pcl_output, output);
68 }
69 
71 void
72 pcl_ros::VoxelGrid::config_callback (pcl_ros::VoxelGridConfig &config, uint32_t /*level*/)
73 {
74  boost::mutex::scoped_lock lock (mutex_);
75 
76  Eigen::Vector3f leaf_size = impl_.getLeafSize ();
77  Eigen::Vector3f config_leaf_size;
78 
79  config_leaf_size[0] = (config.leaf_size_x >= 0.0 ? config.leaf_size_x : config.leaf_size);
80  config_leaf_size[1] = (config.leaf_size_y >= 0.0 ? config.leaf_size_y : config.leaf_size);
81  config_leaf_size[2] = (config.leaf_size_z >= 0.0 ? config.leaf_size_z : config.leaf_size);
82 
83  if (leaf_size != config_leaf_size) {
84  NODELET_DEBUG("[config_callback] Setting the downsampling leaf size to: (%f, %f, %f).",
85  config_leaf_size[0], config_leaf_size[1], config_leaf_size[2]);
86  impl_.setLeafSize(config_leaf_size[0], config_leaf_size[1], config_leaf_size[2]);
87  }
88  unsigned int minPointsPerVoxel = impl_.getMinimumPointsNumberPerVoxel ();
89  if (minPointsPerVoxel != ((unsigned int) config.min_points_per_voxel))
90  {
91  minPointsPerVoxel = config.min_points_per_voxel;
92  NODELET_DEBUG ("[config_callback] Setting the minimum points per voxel to: %u.", minPointsPerVoxel);
93  impl_.setMinimumPointsNumberPerVoxel (minPointsPerVoxel);
94  }
95 
96  double filter_min, filter_max;
97  impl_.getFilterLimits (filter_min, filter_max);
98  if (filter_min != config.filter_limit_min)
99  {
100  filter_min = config.filter_limit_min;
101  NODELET_DEBUG ("[config_callback] Setting the minimum filtering value a point will be considered from to: %f.", filter_min);
102  }
103  if (filter_max != config.filter_limit_max)
104  {
105  filter_max = config.filter_limit_max;
106  NODELET_DEBUG ("[config_callback] Setting the maximum filtering value a point will be considered from to: %f.", filter_max);
107  }
108  impl_.setFilterLimits (filter_min, filter_max);
109 
110  if (impl_.getFilterLimitsNegative () != config.filter_limit_negative)
111  {
112  impl_.setFilterLimitsNegative (config.filter_limit_negative);
113  NODELET_DEBUG ("[%s::config_callback] Setting the filter negative flag to: %s.", getName ().c_str (), config.filter_limit_negative ? "true" : "false");
114  }
115 
116  if (impl_.getFilterFieldName () != config.filter_field_name)
117  {
118  impl_.setFilterFieldName (config.filter_field_name);
119  NODELET_DEBUG ("[config_callback] Setting the filter field name to: %s.", config.filter_field_name.c_str ());
120  }
121 
122  // ---[ These really shouldn't be here, and as soon as dynamic_reconfigure improves, we'll remove them and inherit from Filter
123  if (tf_input_frame_ != config.input_frame)
124  {
125  tf_input_frame_ = config.input_frame;
126  NODELET_DEBUG ("[config_callback] Setting the input TF frame to: %s.", tf_input_frame_.c_str ());
127  }
128  if (tf_output_frame_ != config.output_frame)
129  {
130  tf_output_frame_ = config.output_frame;
131  NODELET_DEBUG ("[config_callback] Setting the output TF frame to: %s.", tf_output_frame_.c_str ());
132  }
133  // ]---
134 }
135 
138 
virtual void filter(const PointCloud2::ConstPtr &input, const IndicesPtr &indices, PointCloud2 &output)
Call the actual filter.
Definition: voxel_grid.cpp:56
f
pcl_ros::VoxelGrid VoxelGrid
Definition: voxel_grid.cpp:136
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
Definition: filter.h:85
bool child_init(ros::NodeHandle &nh, bool &has_service)
Child initialization routine.
Definition: voxel_grid.cpp:43
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
Definition: filter.h:91
pcl::IndicesPtr IndicesPtr
Definition: filter.h:61
boost::shared_ptr< dynamic_reconfigure::Server< pcl_ros::VoxelGridConfig > > srv_
Pointer to a dynamic reconfigure service.
Definition: voxel_grid.h:57
sensor_msgs::PointCloud2 PointCloud2
Definition: filter.h:59
VoxelGrid assembles a local 3D grid over a given PointCloud, and downsamples + filters the data...
Definition: voxel_grid.h:53
void config_callback(pcl_ros::VoxelGridConfig &config, uint32_t level)
Dynamic reconfigure callback.
Definition: voxel_grid.cpp:72
const std::string & getName() const
boost::mutex mutex_
Internal mutex.
Definition: filter.h:94
void toPCL(const ros::Time &stamp, std::uint64_t &pcl_stamp)
pcl::VoxelGrid< pcl::PCLPointCloud2 > impl_
The PCL filter implementation used.
Definition: voxel_grid.h:60
void moveFromPCL(pcl::PCLImage &pcl_image, sensor_msgs::Image &image)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
#define NODELET_DEBUG(...)


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Thu Feb 16 2023 03:08:03