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 namespace jsk_pcl_ros
00040 {
00041   OrganizedPassThrough::OrganizedPassThrough():
00042     DiagnosticNodelet("OrganizedPassThrough")
00043   {
00044     
00045   }
00046   
00047   void OrganizedPassThrough::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00051     // Publisher
00053     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00054 
00056     // Dynamic Reconfigure
00058     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00059     dynamic_reconfigure::Server<Config>::CallbackType f =
00060       boost::bind (
00061         &OrganizedPassThrough::configCallback, this, _1, _2);
00062     srv_->setCallback (f);
00063   }
00064 
00065   void OrganizedPassThrough::subscribe()
00066   {
00068     // Subscriber
00070     sub_ = pnh_->subscribe("input", 1, &OrganizedPassThrough::filter, this);
00071   }
00072 
00073   void OrganizedPassThrough::unsubscribe()
00074   {
00075     sub_.shutdown();
00076   }
00077 
00078   void OrganizedPassThrough::configCallback(Config &config, uint32_t level)
00079   {
00080     boost::mutex::scoped_lock lock(mutex_);
00081     if (config.filter_field == 0) {
00082       filter_field_ = FIELD_X;
00083     }
00084     else {
00085       filter_field_ = FIELD_Y;
00086     }
00087     min_index_ = config.min_index;
00088     max_index_ = config.max_index;
00089     filter_limit_negative_ = config.filter_limit_negative;
00090     keep_organized_ = config.keep_organized;
00091   }
00092 
00093   pcl::PointIndices::Ptr OrganizedPassThrough::filterIndices(const sensor_msgs::PointCloud2::ConstPtr& msg)
00094   {
00095     pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00096 
00097     if (filter_field_ == FIELD_X) {
00098       for (size_t j = 0; j < msg->height; j++) {
00099         for (size_t i = min_index_; i < max_index_ && i < msg->width; i++) {
00100           indices->indices.push_back(i + j * msg->width);
00101         }
00102       }
00103     }
00104     else if (filter_field_ == FIELD_Y) {
00105       for (size_t i = 0; i < msg->width; i++) {
00106         for (size_t j = min_index_; j < max_index_ && j < msg->height; j++) {
00107           indices->indices.push_back(i + j * msg->width);
00108         }
00109       }
00110     }
00111     return indices;
00112   }
00113   
00114   void OrganizedPassThrough::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
00115   {
00116     boost::mutex::scoped_lock lock(mutex_);
00117     vital_checker_->poke();
00118     pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00119     pcl::fromROSMsg(*msg, *cloud);
00120     pcl::PointIndices::Ptr indices = filterIndices(msg);
00121     filtered_points_counter_.add(indices->indices.size());
00122     pcl::ExtractIndices<PointT> ex;
00123     ex.setInputCloud(cloud);
00124     ex.setIndices(indices);
00125     ex.setNegative(filter_limit_negative_);
00126     ex.setKeepOrganized(keep_organized_);
00127     pcl::PointCloud<PointT> output;
00128     ex.filter(output);
00129     sensor_msgs::PointCloud2 ros_output;
00130     pcl::toROSMsg(output, ros_output);
00131     ros_output.header = msg->header;
00132     pub_.publish(ros_output);
00133     diagnostic_updater_->update();
00134   }
00135 
00136   void OrganizedPassThrough::updateDiagnostic(
00137     diagnostic_updater::DiagnosticStatusWrapper &stat)
00138   {
00139     if (vital_checker_->isAlive()) {
00140       stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00141                    name_ + " running");
00142       stat.add("Filtered points (Avg.)", filtered_points_counter_.mean());
00143       if (filter_field_ == FIELD_X) {
00144         stat.add("filter field", "x");
00145       }
00146       else if (filter_field_ == FIELD_Y) {
00147         stat.add("filter field", "y");
00148       }
00149       stat.add("min index", min_index_);
00150       stat.add("max index", max_index_);
00151       jsk_topic_tools::addDiagnosticBooleanStat("keep organized",
00152                                                 keep_organized_,
00153                                                 stat);
00154       jsk_topic_tools::addDiagnosticBooleanStat("filter_limit_negative",
00155                                                 filter_limit_negative_,
00156                                                 stat);
00157     }
00158     else {
00159       addDiagnosticErrorSummary(
00160         "ClusterPointIndicesDecomposer", vital_checker_, stat);
00161     }
00162   }
00163 }
00164 
00165 #include <pluginlib/class_list_macros.h>
00166 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OrganizedPassThrough, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48