36 #include <dynamic_reconfigure/server.h> 
   39 #include <sensor_msgs/CameraInfo.h> 
   40 #include <sensor_msgs/Image.h> 
   43 #include "image_proc/ResizeConfig.h" 
   51   std::shared_ptr<ros::NodeHandle> 
nh_;
 
   52   std::shared_ptr<ros::NodeHandle> 
pnh_;
 
   63   typedef image_proc::ResizeConfig 
Config;
 
   72   void imageCb(
const sensor_msgs::ImageConstPtr& image_msg);
 
   73   void infoCb(
const sensor_msgs::CameraInfoConstPtr& info_msg);
 
   87   ReconfigureServer::CallbackType 
f =
 
   97   pub_info_ = 
pnh_->advertise<sensor_msgs::CameraInfo>(
"camera_info", 1, connect_cb, connect_cb);
 
  136   sensor_msgs::CameraInfoPtr dst_info_msg(
new sensor_msgs::CameraInfo(*info_msg));
 
  140   if (config.use_scale)
 
  142     scale_y = config.scale_height;
 
  143     scale_x = config.scale_width;
 
  144     dst_info_msg->height = 
static_cast<int>(info_msg->height * config.scale_height);
 
  145     dst_info_msg->width = 
static_cast<int>(info_msg->width * config.scale_width);
 
  149     scale_y = 
static_cast<double>(config.height) / info_msg->height;
 
  150     scale_x = 
static_cast<double>(config.width) / info_msg->width;
 
  151     dst_info_msg->height = config.height;
 
  152     dst_info_msg->width = config.width;
 
  155   dst_info_msg->K[0] = dst_info_msg->K[0] * scale_x;  
 
  156   dst_info_msg->K[2] = dst_info_msg->K[2] * scale_x;  
 
  157   dst_info_msg->K[4] = dst_info_msg->K[4] * scale_y;  
 
  158   dst_info_msg->K[5] = dst_info_msg->K[5] * scale_y;  
 
  160   dst_info_msg->P[0] = dst_info_msg->P[0] * scale_x;  
 
  161   dst_info_msg->P[2] = dst_info_msg->P[2] * scale_x;  
 
  162   dst_info_msg->P[3] = dst_info_msg->P[3] * scale_x;  
 
  163   dst_info_msg->P[5] = dst_info_msg->P[5] * scale_y;  
 
  164   dst_info_msg->P[6] = dst_info_msg->P[6] * scale_y;  
 
  166   dst_info_msg->roi.x_offset = 
static_cast<int>(dst_info_msg->roi.x_offset * scale_x);
 
  167   dst_info_msg->roi.y_offset = 
static_cast<int>(dst_info_msg->roi.y_offset * scale_y);
 
  168   dst_info_msg->roi.width = 
static_cast<int>(dst_info_msg->roi.width * scale_x);
 
  169   dst_info_msg->roi.height = 
static_cast<int>(dst_info_msg->roi.height * scale_y);
 
  189     ROS_ERROR(
"cv_bridge exception: %s", e.what());
 
  193   if (config.use_scale)
 
  195     cv::resize(cv_ptr->image, 
scaled_cv_.
image, cv::Size(0, 0), config.scale_width, config.scale_height,
 
  196                config.interpolation);
 
  200     int height = config.height == -1 ? image_msg->height : config.height;
 
  201     int width = config.width == -1 ? image_msg->width : config.width;
 
  202     cv::resize(cv_ptr->image, 
scaled_cv_.
image, cv::Size(width, height), 0, 0, config.interpolation);