Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
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
00055 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00056
00058
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
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 remove_nan_ = config.remove_nan;
00095 }
00096
00097 pcl::PointIndices::Ptr OrganizedPassThrough::filterIndices(const pcl::PointCloud<PointT>::Ptr& pc)
00098 {
00099 pcl::PointIndices::Ptr indices (new pcl::PointIndices);
00100
00101 if (filter_field_ == FIELD_X) {
00102 for (size_t j = 0; j < pc->height; j++) {
00103 for (size_t i = min_index_; i < max_index_ && i < pc->width; i++) {
00104 size_t idx = i + j * pc->width;
00105 if (!remove_nan_ || (remove_nan_ && !isPointNaN(pc->points[idx])))
00106 indices->indices.push_back(idx);
00107 }
00108 }
00109 }
00110 else if (filter_field_ == FIELD_Y) {
00111 for (size_t i = 0; i < pc->width; i++) {
00112 for (size_t j = min_index_; j < max_index_ && j < pc->height; j++) {
00113 size_t idx = i + j * pc->width;
00114 if (!remove_nan_ || (remove_nan_ && !isPointNaN(pc->points[idx])))
00115 indices->indices.push_back(idx);
00116 }
00117 }
00118 }
00119 return indices;
00120 }
00121
00122 void OrganizedPassThrough::filter(const sensor_msgs::PointCloud2::ConstPtr& msg)
00123 {
00124 boost::mutex::scoped_lock lock(mutex_);
00125 vital_checker_->poke();
00126 pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00127 pcl::fromROSMsg(*msg, *cloud);
00128 pcl::PointIndices::Ptr indices = filterIndices(cloud);
00129 filtered_points_counter_.add(indices->indices.size());
00130 pcl::ExtractIndices<PointT> ex;
00131 ex.setInputCloud(cloud);
00132 ex.setIndices(indices);
00133 ex.setNegative(filter_limit_negative_);
00134 ex.setKeepOrganized(keep_organized_);
00135 pcl::PointCloud<PointT> output;
00136 ex.filter(output);
00137 sensor_msgs::PointCloud2 ros_output;
00138 pcl::toROSMsg(output, ros_output);
00139 ros_output.header = msg->header;
00140 pub_.publish(ros_output);
00141 diagnostic_updater_->update();
00142 }
00143
00144 void OrganizedPassThrough::updateDiagnostic(
00145 diagnostic_updater::DiagnosticStatusWrapper &stat)
00146 {
00147 if (vital_checker_->isAlive()) {
00148 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00149 name_ + " running");
00150 stat.add("Filtered points (Avg.)", filtered_points_counter_.mean());
00151 if (filter_field_ == FIELD_X) {
00152 stat.add("filter field", "x");
00153 }
00154 else if (filter_field_ == FIELD_Y) {
00155 stat.add("filter field", "y");
00156 }
00157 stat.add("min index", min_index_);
00158 stat.add("max index", max_index_);
00159 jsk_topic_tools::addDiagnosticBooleanStat("keep organized",
00160 keep_organized_,
00161 stat);
00162 jsk_topic_tools::addDiagnosticBooleanStat("remove_nan",
00163 remove_nan_,
00164 stat);
00165 jsk_topic_tools::addDiagnosticBooleanStat("filter_limit_negative",
00166 filter_limit_negative_,
00167 stat);
00168 }
00169 DiagnosticNodelet::updateDiagnostic(stat);
00170 }
00171 }
00172
00173 #include <pluginlib/class_list_macros.h>
00174 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::OrganizedPassThrough, nodelet::Nodelet);