organized_pass_through_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_pcl_ros/organized_pass_through.h"
00037 #include <jsk_topic_tools/diagnostic_utils.h>
00038 #include <pcl/filters/extract_indices.h>
00039 #include <jsk_recognition_utils/pcl_util.h>
00040 
00041 namespace jsk_pcl_ros
00042 {
00043   OrganizedPassThrough::OrganizedPassThrough():
00044     DiagnosticNodelet("OrganizedPassThrough")
00045   {
00046     
00047   }
00048   
00049   void OrganizedPassThrough::onInit()
00050   {
00051     DiagnosticNodelet::onInit();
00053     // Publisher
00055     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00056 
00058     // Dynamic Reconfigure
00060     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00061     dynamic_reconfigure::Server<Config>::CallbackType f =
00062       boost::bind (
00063         &OrganizedPassThrough::configCallback, this, _1, _2);
00064     srv_->setCallback (f);
00065     onInitPostProcess();
00066   }
00067 
00068   void OrganizedPassThrough::subscribe()
00069   {
00071     // Subscriber
00073     sub_ = pnh_->subscribe("input", 1, &OrganizedPassThrough::filter, this);
00074   }
00075 
00076   void OrganizedPassThrough::unsubscribe()
00077   {
00078     sub_.shutdown();
00079   }
00080 
00081   void OrganizedPassThrough::configCallback(Config &config, uint32_t level)
00082   {
00083     boost::mutex::scoped_lock lock(mutex_);
00084     if (config.filter_field == 0) {
00085       filter_field_ = FIELD_X;
00086     }
00087     else {
00088       filter_field_ = FIELD_Y;
00089     }
00090     min_index_ = config.min_index;
00091     max_index_ = config.max_index;
00092     filter_limit_negative_ = config.filter_limit_negative;
00093     keep_organized_ = config.keep_organized;
00094   }
00095 
00096   pcl::PointIndices::Ptr OrganizedPassThrough::filterIndices(const sensor_msgs::PointCloud2::ConstPtr& msg)
00097   {
00098     pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00099 
00100     if (filter_field_ == FIELD_X) {
00101       for (size_t j = 0; j < msg->height; j++) {
00102         for (size_t i = min_index_; i < max_index_ && i < msg->width; i++) {
00103           indices->indices.push_back(i + j * msg->width);
00104         }
00105       }
00106     }
00107     else if (filter_field_ == FIELD_Y) {
00108       for (size_t i = 0; i < msg->width; i++) {
00109         for (size_t j = min_index_; j < max_index_ && j < msg->height; j++) {
00110           indices->indices.push_back(i + j * msg->width);
00111         }
00112       }
00113     }
00114     return indices;
00115   }
00116   
00117   void OrganizedPassThrough::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
00118   {
00119     boost::mutex::scoped_lock lock(mutex_);
00120     vital_checker_->poke();
00121     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00122     pcl::fromROSMsg(*msg, *cloud);
00123     pcl::PointIndices::Ptr indices = filterIndices(msg);
00124     filtered_points_counter_.add(indices->indices.size());
00125     pcl::ExtractIndices<PointT> ex;
00126     ex.setInputCloud(cloud);
00127     ex.setIndices(indices);
00128     ex.setNegative(filter_limit_negative_);
00129     ex.setKeepOrganized(keep_organized_);
00130     pcl::PointCloud<PointT> output;
00131     ex.filter(output);
00132     sensor_msgs::PointCloud2 ros_output;
00133     pcl::toROSMsg(output, ros_output);
00134     ros_output.header = msg->header;
00135     pub_.publish(ros_output);
00136     diagnostic_updater_->update();
00137   }
00138 
00139   void OrganizedPassThrough::updateDiagnostic(
00140     diagnostic_updater::DiagnosticStatusWrapper &stat)
00141   {
00142     if (vital_checker_->isAlive()) {
00143       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00144                    name_ + " running");
00145       stat.add("Filtered points (Avg.)", filtered_points_counter_.mean());
00146       if (filter_field_ == FIELD_X) {
00147         stat.add("filter field", "x");
00148       }
00149       else if (filter_field_ == FIELD_Y) {
00150         stat.add("filter field", "y");
00151       }
00152       stat.add("min index", min_index_);
00153       stat.add("max index", max_index_);
00154       jsk_topic_tools::addDiagnosticBooleanStat("keep organized",
00155                                                 keep_organized_,
00156                                                 stat);
00157       jsk_topic_tools::addDiagnosticBooleanStat("filter_limit_negative",
00158                                                 filter_limit_negative_,
00159                                                 stat);
00160     }
00161     else {
00162       jsk_recognition_utils::addDiagnosticErrorSummary(
00163         "ClusterPointIndicesDecomposer", vital_checker_, stat);
00164     }
00165   }
00166 }
00167 
00168 #include <pluginlib/class_list_macros.h>
00169 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OrganizedPassThrough, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Sun Oct 8 2017 02:43:50