fisheye_sphere_publisher_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
36 
37 #include <cv_bridge/cv_bridge.h>
38 #include <pcl/common/centroid.h>
41 
42 namespace jsk_pcl_ros
43 {
44  void FisheyeSpherePublisher::extract(const sensor_msgs::ImageConstPtr& input)
45  {
46  float max_degree = 90;
47  float max_radian = max_degree * 3.14159265 /180.0;
48  float tan_max_radian = tan(max_radian);
49  const float K = 341.656050955 * downsample_rate_;
50  const float absolute_max_degree = 85;
51  const float absolute_max_radian = absolute_max_degree * 3.14159265 /180.0;
52  float max_radius = max_radian * K;
53  cv::Mat distorted = cv_bridge::toCvCopy(input, sensor_msgs::image_encodings::BGR8)->image, shrink_distorted;
54  cv::resize(distorted, shrink_distorted, cv::Size(), downsample_rate_, downsample_rate_);
55  int center_x = shrink_distorted.rows/2, center_y = shrink_distorted.cols/2;
56 
57  pcl::PointCloud<pcl::PointXYZRGB> pointcloud;
58 
59  for(int i = 0; i < shrink_distorted.rows; ++i){
60  for(int j = 0; j < shrink_distorted.cols; ++j){
61  float radius = sqrt((i-center_x)*(i-center_x) + (j-center_y)*(j-center_y));
62  float radian = radius/K;
63  if( radian < max_radian ){
64  float l = sphere_radius_ * sin(radian);
65  float rate = l/radius;
66 
67  pcl::PointXYZRGB p;
68  p.x = -(i - center_x) * rate;
69  p.y = (j - center_y) * rate;
70  p.z = sphere_radius_ * cos(radian);
71  p.r = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 2];
72  p.g = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 1];
73  p.b = shrink_distorted.data[ int(i) * shrink_distorted.step + int(j) * shrink_distorted.elemSize() + 0];
74  pointcloud.push_back(p);
75  }
76  }
77  }
78 
79  sensor_msgs::PointCloud2 pc2;
80  pcl::toROSMsg(pointcloud, pc2);
81  pc2.header.frame_id = "fisheye";
82  pc2.header.stamp = ros::Time::now();
83  pub_sphere_.publish(pc2);
84  }
85 
87  {
88  sub_image_ = pnh_->subscribe("input", 1, &FisheyeSpherePublisher::extract, this);
89 
90  }
91 
93  {
95  }
96 
97  void FisheyeSpherePublisher::configCallback(Config &config, uint32_t level)
98  {
99  downsample_rate_ = config.downsample_rate;
100  sphere_radius_ = config.sphere_radius;
101  }
102 
104  {
105  DiagnosticNodelet::onInit();
106  downsample_rate_ = 0.5;
107  sphere_radius_ = 1.0;
108  pub_sphere_ = pnh_->advertise<sensor_msgs::PointCloud2>("output", 1);
109  sub_image_ = pnh_->subscribe("input", 1, &FisheyeSpherePublisher::extract, this);
110 
111  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
112  dynamic_reconfigure::Server<Config>::CallbackType f =
113  boost::bind (&FisheyeSpherePublisher::configCallback, this, _1, _2);
114  srv_->setCallback (f);
115 
117  }
118 }
119 
rate
void publish(const boost::shared_ptr< M > &message) const
double cos()
double sin()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
K
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::FisheyeSpherePublisher, nodelet::Nodelet)
virtual void configCallback(Config &config, uint32_t level)
long l
double sqrt()
boost::shared_ptr< ros::NodeHandle > pnh_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void extract(const sensor_msgs::ImageConstPtr &input)
void toROSMsg(const pcl::PointCloud< T > &pcl_cloud, sensor_msgs::PointCloud2 &cloud)
p
static Time now()
INLINE Rall1d< T, V, S > tan(const Rall1d< T, V, S > &arg)
GLdouble radius


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46