border_estimator_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 #define BOOST_PARAMETER_MAX_ARITY 7
00037 #include "jsk_pcl_ros/pcl_conversion_util.h"
00038 #include <pcl/range_image/range_image_planar.h>
00039 #include <pcl/range_image/range_image_spherical.h>
00040 #include "jsk_pcl_ros/border_estimator.h"
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 
00044 namespace jsk_pcl_ros
00045 {
00046   void BorderEstimator::onInit()
00047   {
00048     ConnectionBasedNodelet::onInit();
00049     // planar or spherical
00050     pnh_->param("model_type", model_type_, std::string("planar"));
00051     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00052     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00053       boost::bind (&BorderEstimator::configCallback, this, _1, _2);
00054     srv_->setCallback (f);
00055 
00056     pub_border_ = advertise<PCLIndicesMsg>(*pnh_, "output_border_indices", 1);
00057     pub_veil_ = advertise<PCLIndicesMsg>(*pnh_, "output_veil_indices", 1);
00058     pub_shadow_ = advertise<PCLIndicesMsg>(*pnh_, "output_shadow_indices", 1);
00059     pub_range_image_ = advertise<sensor_msgs::Image>(
00060       *pnh_, "output_range_image", 1);
00061     pub_cloud_ = advertise<sensor_msgs::PointCloud2>(
00062       *pnh_, "output_cloud", 1);
00063   }
00064 
00065   void BorderEstimator::subscribe()
00066   {
00067     if (model_type_ == "planar") {
00068       sub_point_.subscribe(*pnh_, "input", 1);
00069       sub_camera_info_.subscribe(*pnh_, "input_camera_info", 1);
00070       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00071       sync_->connectInput(sub_point_, sub_camera_info_);
00072       sync_->registerCallback(boost::bind(&BorderEstimator::estimate, this, _1, _2));
00073     }
00074     else if (model_type_ == "laser") {
00075       sub_ = pnh_->subscribe("input", 1, &BorderEstimator::estimate, this);
00076     }
00077   }
00078 
00079   void BorderEstimator::unsubscribe()
00080   {
00081     if (model_type_ == "planar") {
00082       sub_point_.unsubscribe();
00083       sub_camera_info_.unsubscribe();
00084     }
00085     else if (model_type_ == "laser") {
00086       sub_.shutdown();
00087     }
00088   }
00089   
00090   void BorderEstimator::publishCloud(
00091     ros::Publisher& pub,
00092     const pcl::PointIndices& inlier,
00093     const std_msgs::Header& header)
00094   {
00095     PCLIndicesMsg msg;
00096     msg.header = header;
00097     msg.indices = inlier.indices;
00098     pub.publish(msg);
00099   }
00100 
00101   void BorderEstimator::estimate(
00102     const sensor_msgs::PointCloud2::ConstPtr& msg)
00103   {
00104     boost::mutex::scoped_lock lock(mutex_);
00105     pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>);
00106     pcl::fromROSMsg(*msg, *cloud);
00107     pcl::RangeImage range_image;
00108     if (model_type_ == "sphere") {
00109       range_image = pcl::RangeImageSpherical();
00110     }
00111     range_image.createFromPointCloud(
00112       *cloud,
00113       angular_resolution_,
00114       max_angle_width_, max_angle_height_,
00115       Eigen::Affine3f::Identity(),
00116       pcl::RangeImage::CAMERA_FRAME,
00117       noise_level_,
00118       min_range_,
00119       border_size_);
00120     range_image.setUnseenToMaxRange();
00121     computeBorder(range_image, msg->header);
00122   }
00123 
00124   void BorderEstimator::computeBorder(
00125     const pcl::RangeImage& range_image,
00126     const std_msgs::Header& header)
00127   {
00128     pcl::RangeImageBorderExtractor border_extractor (&range_image);
00129     pcl::PointCloud<pcl::BorderDescription> border_descriptions;
00130     border_extractor.compute (border_descriptions);
00131     pcl::PointIndices border_indices, veil_indices, shadow_indices;
00132     for (int y = 0; y < (int)range_image.height; ++y) {
00133       for (int x = 0; x < (int)range_image.width; ++x) {
00134         if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__OBSTACLE_BORDER]) {
00135           border_indices.indices.push_back (y*range_image.width + x);
00136         }
00137         if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__VEIL_POINT]) {
00138           veil_indices.indices.push_back (y*range_image.width + x);
00139         }
00140         if (border_descriptions.points[y*range_image.width + x].traits[pcl::BORDER_TRAIT__SHADOW_BORDER]) {
00141           shadow_indices.indices.push_back (y*range_image.width + x);
00142         }
00143       }
00144     }
00145     publishCloud(pub_border_, border_indices, header);
00146     publishCloud(pub_veil_, veil_indices, header);
00147     publishCloud(pub_shadow_, shadow_indices, header);
00148     cv::Mat image;
00149     rangeImageToCvMat(range_image, image);
00150     pub_range_image_.publish(
00151       cv_bridge::CvImage(header,
00152                          sensor_msgs::image_encodings::BGR8,
00153                          image).toImageMsg());
00154     // publish pointcloud
00155     sensor_msgs::PointCloud2 ros_cloud;
00156     pcl::toROSMsg(range_image, ros_cloud);
00157     ros_cloud.header = header;
00158     pub_cloud_.publish(ros_cloud);
00159   }
00160   
00161   void BorderEstimator::estimate(
00162     const sensor_msgs::PointCloud2::ConstPtr& msg,
00163     const sensor_msgs::CameraInfo::ConstPtr& info)
00164   {
00165     if (msg->height == 1) {
00166       JSK_NODELET_ERROR("[BorderEstimator::estimate] pointcloud must be organized");
00167       return;
00168     }
00169     pcl::RangeImagePlanar range_image;
00170     pcl::PointCloud<pcl::PointXYZ> cloud;
00171     pcl::fromROSMsg(*msg, cloud);
00172     Eigen::Affine3f dummytrans = Eigen::Affine3f::Identity();
00173     float fx = info->P[0];
00174     float cx = info->P[2];
00175     float tx = info->P[3];
00176     float fy = info->P[5];
00177     float cy = info->P[6];
00178     range_image.createFromPointCloudWithFixedSize (cloud,
00179                                                    msg->width,
00180                                                    msg->height,
00181                                                    cx, cy,
00182                                                    fx, fy,
00183                                                    dummytrans);
00184     range_image.setUnseenToMaxRange();
00185     computeBorder(range_image, msg->header);
00186   }
00187 
00188   void BorderEstimator::configCallback(Config &config, uint32_t level)
00189   {
00190     boost::mutex::scoped_lock lock(mutex_);
00191     noise_level_ = config.noise_level;
00192     min_range_ = config.min_range;
00193     border_size_ = config.border_size;
00194     angular_resolution_ = config.angular_resolution;
00195     max_angle_height_ = config.max_angle_height;
00196     max_angle_width_ = config.max_angle_width;
00197   }
00198 }
00199 
00200 #include <pluginlib/class_list_macros.h>
00201 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::BorderEstimator,
00202                         nodelet::Nodelet);


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