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/or 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 
37 #include <jsk_topic_tools/log_utils.h>
38 #include <cv_bridge/cv_bridge.h>
41 #include <jsk_recognition_msgs/PanoramaInfo.h>
42 #include <algorithm>
43 #include <math.h>
44 #include <boost/assign.hpp>
45 
46 // #define PI 3.141592
47 
48 namespace jsk_perception
49 {
51  {
52  DiagnosticNodelet::onInit();
53  pnh_->param("light_compen", enb_lc_, false);
54  pnh_->param("refine_align", enb_ra_, false);
55  pnh_->param("fovd", fovd_, 195.0f);
56  pnh_->param("save_unwarped", save_unwarped_, false);
57  pnh_->param("mls_map_path", mls_map_path_, std::string(""));
58  pnh_->param("blend_image_height", blend_image_height_, 1920);
59  pnh_->param("blend_image_width", blend_image_width_, 3840);
60  pnh_->param("blend_param_p_wid", blend_param_p_wid_, 55);
61  pnh_->param("blend_param_p_x1", blend_param_p_x1_, 90 - 15);
62  pnh_->param("blend_param_p_x2", blend_param_p_x2_, 1780 - 5);
63  pnh_->param("blend_param_row_start", blend_param_row_start_, 590);
64  pnh_->param("blend_param_row_end", blend_param_row_end_, 1320);
65  pnh_->param("output_image_height", output_image_height_, 2000);
66  pnh_->param("output_image_width", output_image_width_, 4000);
67  ROS_INFO("light_compen : %s", enb_lc_?"true":"false");
68  ROS_INFO("refine_align : %s", enb_ra_?"true":"false");
69  ROS_INFO("fovd : %7.3f", fovd_);
70  ROS_INFO("save_unwarped: %s", save_unwarped_?"true":"false");
71  ROS_INFO("mls_map_path : %s", mls_map_path_.c_str());
72  ROS_INFO("blend_image_height : %d", blend_image_height_);
73  ROS_INFO("blend_image_width : %d", blend_image_width_);
74  ROS_INFO("blend_param_p_wid : %d", blend_param_p_wid_);
75  ROS_INFO("blend_param_p_x1 : %d", blend_param_p_x1_);
76  ROS_INFO("blend_param_p_x2 : %d", blend_param_p_x2_);
77  ROS_INFO("blend_param_row_start : %d", blend_param_row_start_);
78  ROS_INFO("blend_param_row_end : %d", blend_param_row_end_);
79  ROS_INFO("output_image_height : %d", output_image_height_);
80  ROS_INFO("output_image_width : %d", output_image_width_);
81  pub_panorama_image_ = advertiseImage(*pnh_, "output", 1);
82  pub_panorama_info_ = advertise<jsk_recognition_msgs::PanoramaInfo>(*pnh_, "panorama_info", 1);
83 
84  sticher_initialized_ = false;
85  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
86  dynamic_reconfigure::Server<Config>::CallbackType f =
87  boost::bind (&DualFisheyeToPanorama::configCallback, this, _1, _2);
88  srv_->setCallback (f);
89 
90  msg_panorama_info_.projection_model = "equirectangular";
91  msg_panorama_info_.theta_min = 0;
92  msg_panorama_info_.theta_max = M_PI;
93  msg_panorama_info_.phi_min = -M_PI;
94  msg_panorama_info_.phi_max = M_PI;
97 
98  onInitPostProcess();
99  }
100 
101  void DualFisheyeToPanorama::configCallback(Config &new_config, uint32_t level)
102  {
103  }
104 
105 
107  {
109  image_transport::TransportHints hints("raw", ros::TransportHints(), *pnh_, "image_transport");
110  sub_image_ = it.subscribe(pnh_->resolveName("input"), 1, &DualFisheyeToPanorama::rectify, this, hints);
111  ros::V_string names = boost::assign::list_of("~input");
112  jsk_topic_tools::warnNoRemap(names);
113  }
114 
116  {
118  }
119 
120 
121  void DualFisheyeToPanorama::rectify(const sensor_msgs::Image::ConstPtr& image_msg)
122  {
123  vital_checker_->poke();
124  cv::Mat img;
125  cv::resize(cv_bridge::toCvCopy(image_msg, image_msg->encoding)->image, img, cv::Size(blend_image_width_,blend_image_height_));
126 
127  if ( ! sticher_initialized_ ) {
128  ROS_INFO("initialize stitcher w:%d h:%d", img.size().width, img.size().height);
129  stitcher_.reset(new stitcher::FisheyeStitcher(img.size().width,
130  img.size().height,
131  fovd_,
132  enb_lc_,
135  mls_map_path_));
136  sticher_initialized_ = true;
137  }
138  cv::Mat img_l, img_r;
139  // Left fisheye
140  img_l = img(cv::Rect(0, 0,
141  static_cast<int>(img.size().width / 2), img.size().height));
142  // Right fisheye
143  img_r = img(cv::Rect(static_cast<int>(img.size().width / 2), 0,
144  static_cast<int>(img.size().width / 2), img.size().height));
145  // Stitch video frames
146  cv::Mat pano;
147  pano = stitcher_->stitch(img_l, img_r,
153  );
154  // resize panorama image;
155  cv::Mat pano_resized;
156  cv::resize(pano, pano_resized, cv::Size(output_image_width_,output_image_height_));
157 
159  image_msg->encoding,
160  pano_resized).toImageMsg());
161  msg_panorama_info_.header = image_msg->header;
163  }
164 }
165 
166 
jsk_perception::DualFisheyeToPanorama::fovd_
float fovd_
Definition: dual_fisheye_to_panorama.h:153
image_encodings.h
image_transport::ImageTransport
jsk_perception::DualFisheyeToPanorama::blend_param_row_end_
int blend_param_row_end_
Definition: dual_fisheye_to_panorama.h:160
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
M_PI
#define M_PI
jsk_perception::DualFisheyeToPanorama::msg_panorama_info_
jsk_recognition_msgs::PanoramaInfo msg_panorama_info_
Definition: dual_fisheye_to_panorama.h:148
jsk_perception::DualFisheyeToPanorama::rectify
virtual void rectify(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: dual_fisheye_to_panorama.cpp:153
ros::TransportHints
jsk_perception::DualFisheyeToPanorama::enb_ra_
bool enb_ra_
Definition: dual_fisheye_to_panorama.h:151
jsk_perception::DualFisheyeToPanorama::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: dual_fisheye_to_panorama.h:135
jsk_perception::DualFisheyeToPanorama::blend_image_width_
int blend_image_width_
Definition: dual_fisheye_to_panorama.h:155
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_perception::DualFisheyeToPanorama::subscribe
virtual void subscribe()
Definition: dual_fisheye_to_panorama.cpp:138
jsk_perception::DualFisheyeToPanorama::configCallback
void configCallback(Config &new_config, uint32_t level)
Definition: dual_fisheye_to_panorama.cpp:133
img
img
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::DualFisheyeToPanorama, nodelet::Nodelet)
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
jsk_perception::DualFisheyeToPanorama::pub_panorama_image_
image_transport::Publisher pub_panorama_image_
Definition: dual_fisheye_to_panorama.h:145
jsk_perception::DualFisheyeToPanorama::save_unwarped_
bool save_unwarped_
Definition: dual_fisheye_to_panorama.h:152
jsk_perception::DualFisheyeToPanorama::blend_param_row_start_
int blend_param_row_start_
Definition: dual_fisheye_to_panorama.h:159
jsk_perception::DualFisheyeToPanorama::onInit
virtual void onInit()
Definition: dual_fisheye_to_panorama.cpp:82
math.h
jsk_perception::DualFisheyeToPanorama::sub_image_
image_transport::Subscriber sub_image_
Definition: dual_fisheye_to_panorama.h:144
dual_fisheye_to_panorama.h
jsk_perception::DualFisheyeToPanorama::output_image_height_
int output_image_height_
Definition: dual_fisheye_to_panorama.h:161
jsk_perception::DualFisheyeToPanorama::output_image_width_
int output_image_width_
Definition: dual_fisheye_to_panorama.h:162
jsk_perception::DualFisheyeToPanorama::enb_lc_
bool enb_lc_
Definition: dual_fisheye_to_panorama.h:150
jsk_perception::DualFisheyeToPanorama::mls_map_path_
std::string mls_map_path_
Definition: dual_fisheye_to_panorama.h:163
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
jsk_perception::DualFisheyeToPanorama::blend_image_height_
int blend_image_height_
Definition: dual_fisheye_to_panorama.h:154
image_transport.h
jsk_perception::DualFisheyeToPanorama::pub_panorama_info_
ros::Publisher pub_panorama_info_
Definition: dual_fisheye_to_panorama.h:146
jsk_perception::DualFisheyeToPanorama::unsubscribe
virtual void unsubscribe()
Definition: dual_fisheye_to_panorama.cpp:147
jsk_perception::DualFisheyeToPanorama
Definition: dual_fisheye_to_panorama.h:92
jsk_perception::DualFisheyeToPanorama::blend_param_p_x1_
int blend_param_p_x1_
Definition: dual_fisheye_to_panorama.h:157
f
f
nodelet::Nodelet
jsk_perception::DualFisheyeToPanorama::sticher_initialized_
bool sticher_initialized_
Definition: dual_fisheye_to_panorama.h:142
cv_bridge.h
cv_bridge::CvImage
ros::V_string
std::vector< std::string > V_string
image_transport::TransportHints
jsk_perception::DualFisheyeToPanorama::blend_param_p_wid_
int blend_param_p_wid_
Definition: dual_fisheye_to_panorama.h:156
jsk_perception::DualFisheyeToPanorama::stitcher_
boost::shared_ptr< stitcher::FisheyeStitcher > stitcher_
Definition: dual_fisheye_to_panorama.h:143
ROS_INFO
#define ROS_INFO(...)
jsk_perception::DualFisheyeToPanorama::blend_param_p_x2_
int blend_param_p_x2_
Definition: dual_fisheye_to_panorama.h:158
stitcher::FisheyeStitcher
Definition: fisheye_stitcher.hpp:62
image_transport::Subscriber::shutdown
void shutdown()


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16