dual_fisheye_to_panorama.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2021, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
38 #include <cv_bridge/cv_bridge.h>
39 #include <sensor_msgs/Image.h>
41 #include <algorithm>
42 #include <math.h>
43 #include <boost/assign.hpp>
44 
45 // #define PI 3.141592
46 
47 namespace jsk_perception
48 {
50  {
51  DiagnosticNodelet::onInit();
52  pnh_->param("light_compen", enb_lc_, false);
53  pnh_->param("refine_align", enb_ra_, false);
54  pnh_->param("fovd", fovd_, 195.0f);
55  pnh_->param("save_unwarped", save_unwarped_, false);
56  pnh_->param("mls_map_path", mls_map_path_, std::string(""));
57  ROS_INFO("light_compen : %s", enb_lc_?"true":"false");
58  ROS_INFO("refine_align : %s", enb_ra_?"true":"false");
59  ROS_INFO("fovd : %7.3f", fovd_);
60  ROS_INFO("save_unwarped: %7.3f", save_unwarped_?"true":"false");
61  ROS_INFO("mls_map_path : %s", mls_map_path_.c_str());
62  pub_panorama_image_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
63 
64  sticher_initialized_ = false;
65  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
66  dynamic_reconfigure::Server<Config>::CallbackType f =
67  boost::bind (&DualFisheyeToPanorama::configCallback, this, _1, _2);
68  srv_->setCallback (f);
69 
71  }
72 
73  void DualFisheyeToPanorama::configCallback(Config &new_config, uint32_t level)
74  {
75  }
76 
77 
79  {
80  sub_image_ = pnh_->subscribe("input", 1, &DualFisheyeToPanorama::rectify, this);
81  ros::V_string names = boost::assign::list_of("~input");
83  }
84 
86  {
88  }
89 
90 
91  void DualFisheyeToPanorama::rectify(const sensor_msgs::Image::ConstPtr& image_msg)
92  {
93  cv::Mat img;
94  cv::resize(cv_bridge::toCvCopy(image_msg, image_msg->encoding)->image, img, cv::Size(3840,1920));
95 
96  if ( ! sticher_initialized_ ) {
97  ROS_INFO("initialize stitcher w:%d h:%d", img.size().width, img.size().height);
98  stitcher_.reset(new stitcher::FisheyeStitcher(img.size().width,
99  img.size().height,
100  fovd_,
101  enb_lc_,
102  enb_ra_,
104  mls_map_path_));
105  sticher_initialized_ = true;
106  }
107  cv::Mat img_l, img_r;
108  // Left fisheye
109  img_l = img(cv::Rect(0, 0,
110  static_cast<int>(img.size().width / 2), img.size().height));
111  // Right fisheye
112  img_r = img(cv::Rect(static_cast<int>(img.size().width / 2), 0,
113  static_cast<int>(img.size().width / 2), img.size().height));
114  // Stitch video frames
115  cv::Mat pano;
116  pano = stitcher_->stitch(img_l, img_r);
117 
119  image_msg->encoding,
120  pano).toImageMsg());
121  }
122 }
123 
124 
f
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< stitcher::FisheyeStitcher > stitcher_
jsk_perception::DualFisheyeConfig Config
std::vector< std::string > V_string
#define ROS_INFO(...)
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void rectify(const sensor_msgs::Image::ConstPtr &image_msg)
PLUGINLIB_EXPORT_CLASS(jsk_perception::DualFisheyeToPanorama, nodelet::Nodelet)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::ImagePtr toImageMsg() const
void configCallback(Config &new_config, uint32_t level)


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27