log_polar_nodelet.cpp
Go to the documentation of this file.
2 
4 {
6  DiagnosticNodelet::onInit();
8  initParams();
10  }
11 
12 
14  reconfigure_server_ = boost::make_shared <dynamic_reconfigure::Server<LogPolarConfig> > (*pnh_);
15  ReconfigureServer::CallbackType f
16  = boost::bind(&LogPolar::config_cb, this, _1, _2);
17  reconfigure_server_->setCallback(f);
18  }
19 
22  period_ = ros::Duration(1.0);
23  pnh_->param("log_polar_scale", log_polar_scale_, 100.0);
24  NODELET_INFO("log polar scale : %f", log_polar_scale_);
25 
26  pnh_->param("inverse_log_polar", inverse_log_polar_, false);
27  if (inverse_log_polar_){
28  NODELET_INFO("log polar");
29  }else{
30  NODELET_INFO("inverse log polar");
31  }
32  }
33 
34  void LogPolar::config_cb ( LogPolarConfig &config, uint32_t level) {
35  NODELET_INFO("config_cb");
36  resize_x_ = config.resize_scale_x;
37  resize_y_ = config.resize_scale_y;
38  log_polar_scale_ = config.log_polar_scale;
39  period_ = ros::Duration(1.0/config.msg_par_second);
40  verbose_ = config.verbose;
41  NODELET_DEBUG("resize_scale_x : %f", resize_x_);
42  NODELET_DEBUG("resize_scale_y : %f", resize_y_);
43  NODELET_DEBUG("log_polar_scale : %f", log_polar_scale_);
44  NODELET_DEBUG("message period : %f", period_.toSec());
45  }
46 
47 
48  void LogPolar::process(const sensor_msgs::ImageConstPtr &src_img, const sensor_msgs::CameraInfoConstPtr &src_info,
49  sensor_msgs::ImagePtr &dst_img, sensor_msgs::CameraInfo &dst_info){
50  int image_width, image_height;
51  if(use_camera_info_){
52  image_width = src_info->width;
53  image_height = src_info->height;
54  }else{
55  image_width = src_img->width;
56  image_height = src_img->height;
57  }
58 
59  int width = dst_width_ ? dst_width_ : (resize_x_ * image_width);
60  int height = dst_height_ ? dst_height_ : (resize_y_ * image_height);
61 
62  double scale_x = dst_width_ ? ((double)dst_width_)/image_width : resize_x_;
63  double scale_y = dst_height_ ? ((double)dst_height_)/image_height : resize_y_;
64 
66 #if ( CV_MAJOR_VERSION >= 4)
67  IplImage src = cvIplImage(cv_img->image);
68 #else
69  IplImage src = cv_img->image;
70 #endif
71  IplImage* dst = cvCloneImage(&src);
72 
73  int log_polar_flags = CV_INTER_LINEAR+CV_WARP_FILL_OUTLIERS;
74  if ( inverse_log_polar_ ){
75  log_polar_flags += CV_WARP_INVERSE_MAP;
76  }
77  cvLogPolar( &src, dst, cvPoint2D32f(image_width/2, image_height/2), log_polar_scale_, log_polar_flags);
78  // http://answers.opencv.org/question/23440/any-way-to-convert-iplimage-to-cvmat-in-opencv-300/
79  cv_img->image = cv::cvarrToMat(dst);
80 
81  dst_img = cv_img->toImageMsg();
82  if(use_camera_info_){
83  dst_info = *src_info;
84  dst_info.height = height;
85  dst_info.width = width;
86  dst_info.K[0] = dst_info.K[0] * scale_x; // fx
87  dst_info.K[2] = dst_info.K[2] * scale_x; // cx
88  dst_info.K[4] = dst_info.K[4] * scale_y; // fy
89  dst_info.K[5] = dst_info.K[5] * scale_y; // cy
90 
91  dst_info.P[0] = dst_info.P[0] * scale_x; // fx
92  dst_info.P[2] = dst_info.P[2] * scale_x; // cx
93  dst_info.P[3] = dst_info.P[3] * scale_x; // T
94  dst_info.P[5] = dst_info.P[5] * scale_y; // fy
95  dst_info.P[6] = dst_info.P[6] * scale_y; // cy
96  }
97  }
98 }
99 
void process(const sensor_msgs::ImageConstPtr &src_img, const sensor_msgs::CameraInfoConstPtr &src_info, sensor_msgs::ImagePtr &dst_img, sensor_msgs::CameraInfo &dst_info)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
f
resized_image_transport::LogPolar LogPolar
PLUGINLIB_EXPORT_CLASS(LogPolar, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > pnh_
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void config_cb(LogPolarConfig &config, uint32_t level)
#define NODELET_INFO(...)
#define NODELET_DEBUG(...)


resized_image_transport
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:39