organized_pass_through_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, 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 
38 #include <pcl/filters/extract_indices.h>
40 
41 namespace jsk_pcl_ros
42 {
44  DiagnosticNodelet("OrganizedPassThrough")
45  {
46 
47  }
48 
50  {
51  DiagnosticNodelet::onInit();
53  // Publisher
55  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
56 
58  // Dynamic Reconfigure
60  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
61  dynamic_reconfigure::Server<Config>::CallbackType f =
62  boost::bind (
64  srv_->setCallback (f);
66  }
67 
69  {
71  // Subscriber
73  sub_ = pnh_->subscribe("input", 1, &OrganizedPassThrough::filter, this);
74  }
75 
77  {
78  sub_.shutdown();
79  }
80 
81  void OrganizedPassThrough::configCallback(Config &config, uint32_t level)
82  {
83  boost::mutex::scoped_lock lock(mutex_);
84  if (config.filter_field == 0) {
86  }
87  else {
89  }
90  min_index_ = config.min_index;
91  max_index_ = config.max_index;
92  filter_limit_negative_ = config.filter_limit_negative;
93  keep_organized_ = config.keep_organized;
94  remove_nan_ = config.remove_nan;
95  }
96 
97  pcl::PointIndices::Ptr OrganizedPassThrough::filterIndices(const pcl::PointCloud<PointT>::Ptr& pc)
98  {
99  pcl::PointIndices::Ptr indices (new pcl::PointIndices);
100 
101  if (filter_field_ == FIELD_X) {
102  for (size_t j = 0; j < pc->height; j++) {
103  for (size_t i = min_index_; i < max_index_ && i < pc->width; i++) {
104  size_t idx = i + j * pc->width;
105  if (!remove_nan_ || (remove_nan_ && !isPointNaN(pc->points[idx])))
106  indices->indices.push_back(idx);
107  }
108  }
109  }
110  else if (filter_field_ == FIELD_Y) {
111  for (size_t i = 0; i < pc->width; i++) {
112  for (size_t j = min_index_; j < max_index_ && j < pc->height; j++) {
113  size_t idx = i + j * pc->width;
114  if (!remove_nan_ || (remove_nan_ && !isPointNaN(pc->points[idx])))
115  indices->indices.push_back(idx);
116  }
117  }
118  }
119  return indices;
120  }
121 
122  void OrganizedPassThrough::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
123  {
124  boost::mutex::scoped_lock lock(mutex_);
125  vital_checker_->poke();
126  pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
127  pcl::fromROSMsg(*msg, *cloud);
128  pcl::PointIndices::Ptr indices = filterIndices(cloud);
129  filtered_points_counter_.add(indices->indices.size());
130  pcl::ExtractIndices<PointT> ex;
131  ex.setInputCloud(cloud);
132  ex.setIndices(indices);
133  ex.setNegative(filter_limit_negative_);
134  ex.setKeepOrganized(keep_organized_);
135  pcl::PointCloud<PointT> output;
136  ex.filter(output);
137  sensor_msgs::PointCloud2 ros_output;
138  pcl::toROSMsg(output, ros_output);
139  ros_output.header = msg->header;
140  pub_.publish(ros_output);
141  diagnostic_updater_->update();
142  }
143 
146  {
147  if (vital_checker_->isAlive()) {
148  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
149  name_ + " running");
150  stat.add("Filtered points (Avg.)", filtered_points_counter_.mean());
151  if (filter_field_ == FIELD_X) {
152  stat.add("filter field", "x");
153  }
154  else if (filter_field_ == FIELD_Y) {
155  stat.add("filter field", "y");
156  }
157  stat.add("min index", min_index_);
158  stat.add("max index", max_index_);
161  stat);
163  remove_nan_,
164  stat);
165  jsk_topic_tools::addDiagnosticBooleanStat("filter_limit_negative",
167  stat);
168  }
169  DiagnosticNodelet::updateDiagnostic(stat);
170  }
171 }
172 
jsk_topic_tools::Counter filtered_points_counter_
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
jsk_pcl_ros::OrganizedPassThroughConfig Config
void addDiagnosticBooleanStat(const std::string &string_prefix, const bool value, diagnostic_updater::DiagnosticStatusWrapper &stat)
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void add(double v)
virtual double mean()
void output(int index, double value)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OrganizedPassThrough, nodelet::Nodelet)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< ros::NodeHandle > pnh_
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
virtual pcl::PointIndices::Ptr filterIndices(const pcl::PointCloud< PointT >::Ptr &pc)
void add(const std::string &key, const T &val)
cloud
virtual void configCallback(Config &config, uint32_t level)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47