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 #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);