41 #include <opencv2/opencv.hpp> 
   44 #include <sensor_msgs/CameraInfo.h> 
   45 #include <dynamic_reconfigure/server.h> 
   55 #include "opencv_apps/AddingImagesConfig.h" 
   75   typedef opencv_apps::AddingImagesConfig 
Config;
 
  100   void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg1, 
const sensor_msgs::ImageConstPtr& msg2,
 
  101                              const sensor_msgs::CameraInfoConstPtr& cam_info)
 
  103     doWork(msg1, msg2, cam_info->header.frame_id);
 
  106   void imageCallback(
const sensor_msgs::ImageConstPtr& msg1, 
const sensor_msgs::ImageConstPtr& msg2)
 
  108     doWork(msg1, msg2, msg1->header.frame_id);
 
  122             boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(
queue_size_);
 
  166     boost::mutex::scoped_lock lock(
mutex_);
 
  169     if (config.auto_beta)
 
  181   void doWork(
const sensor_msgs::Image::ConstPtr& image_msg1, 
const sensor_msgs::Image::ConstPtr& image_msg2,
 
  182               const std::string& input_frame_from_msg)
 
  184     boost::mutex::scoped_lock lock(
mutex_);
 
  192         NODELET_ERROR(
"Encoding of input images must be same type: %s, %s", image_msg1->encoding.c_str(),
 
  193                       image_msg2->encoding.c_str());
 
  197       cv::Mat result_image;
 
  198       if (image1.rows != image2.rows || image1.cols != image2.cols)
 
  200         int new_rows = std::max(image1.rows, image2.rows);
 
  201         int new_cols = std::max(image1.cols, image2.cols);
 
  203         cv::Mat image1_tmp = cv::Mat(new_rows, new_cols, image1.type());
 
  204         image1.copyTo(image1_tmp(cv::Rect(0, 0, image1.cols, image1.rows)));
 
  205         image1 = image1_tmp.clone();  
 
  208         cv::Mat image2_tmp = cv::Mat(new_rows, new_cols, image2.type());
 
  209         image2.copyTo(image2_tmp(cv::Rect(0, 0, image2.cols, image2.rows)));
 
  210         image2 = image2_tmp.clone();
 
  214       sensor_msgs::ImagePtr image_msg3 =
 
  219 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_IS_NOT_SUPPORTED 
  222 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_OPTION_IS_NOT_SUPPORTED 
  236         int c = cv::waitKey(1);
 
  240     catch (cv::Exception& e)
 
  242       NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
 
  266     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
  285     ROS_WARN(
"DeprecationWarning: Nodelet adding_images/adding_images is deprecated, " 
  286              "and renamed to opencv_apps/adding_images.");
 
  292 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H