polygon_points_sampler_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, 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 "jsk_pcl_ros/polygon_points_sampler.h"
00039 
00040 namespace jsk_pcl_ros
00041 {
00042   void PolygonPointsSampler::onInit()
00043   {
00044     DiagnosticNodelet::onInit();
00045     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00046     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00047       boost::bind (&PolygonPointsSampler::configCallback, this, _1, _2);
00048     srv_->setCallback (f);
00049 
00050     pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00051     pub_xyz_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output_xyz", 1);
00052   }
00053 
00054   void PolygonPointsSampler::subscribe()
00055   {
00056     sub_polygons_.subscribe(*pnh_, "input/polygons", 1);
00057     sub_coefficients_.subscribe(*pnh_, "input/coefficients", 1);
00058     sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00059     sync_->connectInput(sub_polygons_, sub_coefficients_);
00060     sync_->registerCallback(boost::bind(&PolygonPointsSampler::sample, this, _1, _2));
00061   }
00062 
00063   void PolygonPointsSampler::unsubscribe()
00064   {
00065     sub_polygons_.unsubscribe();
00066     sub_coefficients_.unsubscribe();
00067   }
00068 
00069   bool PolygonPointsSampler::isValidMessage(
00070     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00071     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00072   {
00073     if (polygon_msg->polygons.size() == 0) {
00074       JSK_NODELET_DEBUG("empty polygons");
00075       return false;
00076     }
00077     if (coefficients_msg->coefficients.size() != polygon_msg->polygons.size()) {
00078       JSK_NODELET_ERROR("The size of coefficients and polygons are not same");
00079       return false;
00080     }
00081 
00082     std::string frame_id = polygon_msg->header.frame_id;
00083     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00084       if (frame_id != polygon_msg->polygons[i].header.frame_id) {
00085         JSK_NODELET_ERROR("Frame id of polygon is not same: %s, %s",
00086                       frame_id.c_str(),
00087                       polygon_msg->polygons[i].header.frame_id.c_str());
00088         return false;
00089       }
00090     }
00091     for (size_t i = 0; i < coefficients_msg->coefficients.size(); i++) {
00092       if (frame_id != coefficients_msg->coefficients[i].header.frame_id) {
00093         JSK_NODELET_ERROR("Frame id of coefficient is not same: %s, %s",
00094                       frame_id.c_str(),
00095                       coefficients_msg->coefficients[i].header.frame_id.c_str());
00096         return false;
00097       }
00098     }
00099     return true;
00100   }
00101   
00102   void PolygonPointsSampler::sample(
00103     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg,
00104     const jsk_recognition_msgs::ModelCoefficientsArray::ConstPtr& coefficients_msg)
00105   {
00106     boost::mutex::scoped_lock lock(mutex_);
00107     // check frame_ids
00108     if (!isValidMessage(polygon_msg, coefficients_msg)) {
00109       return;
00110     }
00111     // Sample points... 
00112     pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZRGBNormal>);
00113     pcl::PointCloud<pcl::PointXYZ>::Ptr xyz_cloud (new pcl::PointCloud<pcl::PointXYZ>);
00114     for (size_t i = 0; i < polygon_msg->polygons.size(); i++) {
00115       Polygon polygon = Polygon::fromROSMsg(polygon_msg->polygons[i].polygon);
00116       pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr one_cloud
00117         = polygon.samplePoints<pcl::PointXYZRGBNormal>(grid_size_);
00118       pcl::PointCloud<pcl::PointXYZ> one_xyz_cloud;
00119       one_xyz_cloud.points.resize(one_cloud->points.size());
00120       for (size_t i = 0; i < one_cloud->points.size(); i++) {
00121         pcl::PointXYZ p;
00122         p.getVector3fMap() = one_cloud->points[i].getVector3fMap();
00123         one_xyz_cloud.points[i] = p;
00124       }
00125       *xyz_cloud = *xyz_cloud + one_xyz_cloud;
00126       *cloud = *cloud + *one_cloud;
00127     }
00128     sensor_msgs::PointCloud2 ros_cloud;
00129     pcl::toROSMsg(*cloud, ros_cloud);
00130     ros_cloud.header = polygon_msg->header;
00131     pub_.publish(ros_cloud);
00132     sensor_msgs::PointCloud2 ros_xyz_cloud;
00133     pcl::toROSMsg(*xyz_cloud, ros_xyz_cloud);
00134     ros_xyz_cloud.header = polygon_msg->header;
00135     pub_xyz_.publish(ros_xyz_cloud);
00136   }
00137 
00138   
00139   void PolygonPointsSampler::configCallback(Config& config, uint32_t level)
00140   {
00141     boost::mutex::scoped_lock lock(mutex_);
00142     grid_size_ = config.grid_size;
00143   }
00144 }
00145 
00146 #include <pluginlib/class_list_macros.h>
00147 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PolygonPointsSampler, nodelet::Nodelet);


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