fisheye_sphere_publisher_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include "jsk_pcl_ros/fisheye_sphere_publisher.h"
00036 
00037 #include <cv_bridge/cv_bridge.h>
00038 #include <pcl/common/centroid.h>
00039 #include "jsk_recognition_utils/pcl_conversion_util.h"
00040 #include <sensor_msgs/image_encodings.h>
00041 
00042 namespace jsk_pcl_ros
00043 {
00044   void FisheyeSpherePublisher::extract(const sensor_msgs::ImageConstPtr& input)
00045   {
00046     float max_degree = 90;
00047     float max_radian = max_degree * 3.14159265 /180.0;
00048     float tan_max_radian = tan(max_radian);
00049     const float K = 341.656050955 * downsample_rate_;
00050     const float absolute_max_degree = 85;
00051     const float absolute_max_radian = absolute_max_degree * 3.14159265 /180.0;
00052     float max_radius = max_radian * K;
00053     cv::Mat distorted = cv_bridge::toCvCopy(input, sensor_msgs::image_encodings::BGR8)->image, shrink_distorted;
00054     cv::resize(distorted, shrink_distorted, cv::Size(), downsample_rate_, downsample_rate_);
00055     int center_x = shrink_distorted.rows/2, center_y = shrink_distorted.cols/2;
00056 
00057     pcl::PointCloud<pcl::PointXYZRGB> pointcloud;
00058 
00059     for(int i = 0; i < shrink_distorted.rows; ++i){
00060       for(int j = 0; j < shrink_distorted.cols; ++j){
00061         float radius = sqrt((i-center_x)*(i-center_x) + (j-center_y)*(j-center_y));
00062         float radian = radius/K;
00063         if( radian < max_radian ){
00064           float l = sphere_radius_ * sin(radian);
00065           float rate = l/radius;
00066 
00067           pcl::PointXYZRGB p;
00068           p.x = -(i - center_x) * rate;
00069           p.y = (j - center_y) * rate;
00070           p.z = sphere_radius_ * cos(radian);
00071           p.r = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 2];
00072           p.g = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 1];
00073           p.b = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 0];
00074           pointcloud.push_back(p);
00075         }
00076       }
00077     }
00078 
00079     sensor_msgs::PointCloud2 pc2;
00080     pcl::toROSMsg(pointcloud, pc2);
00081     pc2.header.frame_id = "fisheye";
00082     pc2.header.stamp = ros::Time::now();
00083     pub_sphere_.publish(pc2);
00084   }
00085 
00086   void FisheyeSpherePublisher::subscribe()
00087   {
00088     sub_image_ = pnh_->subscribe("input", 1, &FisheyeSpherePublisher::extract, this);
00089 
00090   }
00091 
00092   void FisheyeSpherePublisher::unsubscribe()
00093   {
00094     sub_image_.shutdown();
00095   }
00096 
00097   void FisheyeSpherePublisher::configCallback(Config &config, uint32_t level)
00098   {
00099     downsample_rate_ = config.downsample_rate;
00100     sphere_radius_ = config.sphere_radius;
00101   }
00102 
00103   void FisheyeSpherePublisher::onInit(void)
00104   {
00105     DiagnosticNodelet::onInit();
00106     downsample_rate_ = 0.5;
00107     sphere_radius_ = 1.0;
00108     pub_sphere_ = pnh_->advertise<sensor_msgs::PointCloud2>("output", 1);
00109     sub_image_ = pnh_->subscribe("input", 1, &FisheyeSpherePublisher::extract, this);
00110 
00111     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00112     dynamic_reconfigure::Server<Config>::CallbackType f =
00113       boost::bind (&FisheyeSpherePublisher::configCallback, this, _1, _2);
00114     srv_->setCallback (f);
00115 
00116     onInitPostProcess();
00117   }
00118 }
00119 
00120 #include <pluginlib/class_list_macros.h>
00121 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::FisheyeSpherePublisher, nodelet::Nodelet);


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