adding_images_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) JSK, 2016 Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 // https://github.com/opencv/opencv/tree/2.4/samples/cpp/tutorial_code/ImgProc/AddingImages.cpp
00041 #include <opencv2/opencv.hpp>
00042 #include <cv_bridge/cv_bridge.h>
00043 #include <sensor_msgs/image_encodings.h>
00044 #include <sensor_msgs/CameraInfo.h>
00045 #include <dynamic_reconfigure/server.h>
00046 
00047 #include <image_transport/image_transport.h>
00048 #include <image_transport/subscriber_filter.h>
00049 
00050 #include <message_filters/subscriber.h>
00051 #include <message_filters/synchronizer.h>
00052 #include <message_filters/sync_policies/exact_time.h>
00053 #include <message_filters/sync_policies/approximate_time.h>
00054 
00055 #include "opencv_apps/AddingImagesConfig.h"
00056 #include "opencv_apps/nodelet.h"
00057 
00058 namespace opencv_apps
00059 {
00060 class AddingImagesNodelet : public opencv_apps::Nodelet
00061 {
00062 private:
00063   boost::shared_ptr<image_transport::ImageTransport> it_;
00064 
00065   typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo>
00066       SyncPolicyWithCameraInfo;
00067   typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image,
00068                                                           sensor_msgs::CameraInfo>
00069       ApproxSyncPolicyWithCameraInfo;
00070   typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image> SyncPolicy;
00071   typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image> ApproxSyncPolicy;
00072 
00074   // Dynamic Reconfigure
00076   typedef opencv_apps::AddingImagesConfig Config;
00077   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00078   Config config_;
00079   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00080 
00081   int queue_size_;
00082   bool debug_view_;
00083   ros::Time prev_stamp_;
00084 
00085   std::string window_name_;
00086 
00087   image_transport::SubscriberFilter sub_image1_, sub_image2_;
00088   image_transport::Publisher img_pub_;
00089   message_filters::Subscriber<sensor_msgs::CameraInfo> sub_camera_info_;
00090   boost::shared_ptr<message_filters::Synchronizer<SyncPolicyWithCameraInfo> > sync_with_info_;
00091   boost::shared_ptr<message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> > async_with_info_;
00092   boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > sync_;
00093   boost::shared_ptr<message_filters::Synchronizer<ApproxSyncPolicy> > async_;
00094   boost::mutex mutex_;
00095 
00096   bool approximate_sync_;
00097   double alpha_;
00098   double beta_;
00099   double gamma_;
00100 
00101   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2,
00102                              const sensor_msgs::CameraInfoConstPtr& cam_info)
00103   {
00104     doWork(msg1, msg2, cam_info->header.frame_id);
00105   }
00106 
00107   void imageCallback(const sensor_msgs::ImageConstPtr& msg1, const sensor_msgs::ImageConstPtr& msg2)
00108   {
00109     doWork(msg1, msg2, msg1->header.frame_id);
00110   }
00111 
00112   void subscribe()  // NOLINT(modernize-use-override)
00113   {
00114     NODELET_DEBUG("Subscribing to image topic.");
00115     sub_image1_.subscribe(*it_, "image1", 3);
00116     sub_image2_.subscribe(*it_, "image2", 3);
00117     sub_camera_info_.subscribe(*nh_, "camera_info", 3);
00118     if (config_.use_camera_info)
00119     {
00120       if (approximate_sync_)
00121       {
00122         async_with_info_ =
00123             boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicyWithCameraInfo> >(queue_size_);
00124         async_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
00125         async_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
00126       }
00127       else
00128       {
00129         sync_with_info_ = boost::make_shared<message_filters::Synchronizer<SyncPolicyWithCameraInfo> >(queue_size_);
00130         sync_with_info_->connectInput(sub_image1_, sub_image2_, sub_camera_info_);
00131         sync_with_info_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallbackWithInfo, this, _1, _2, _3));
00132       }
00133     }
00134     else
00135     {
00136       if (approximate_sync_)
00137       {
00138         async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
00139         async_->connectInput(sub_image1_, sub_image2_);
00140         async_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
00141       }
00142       else
00143       {
00144         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00145         sync_->connectInput(sub_image1_, sub_image2_);
00146         sync_->registerCallback(boost::bind(&AddingImagesNodelet::imageCallback, this, _1, _2));
00147       }
00148     }
00149   }
00150 
00151   void unsubscribe()  // NOLINT(modernize-use-override)
00152   {
00153     NODELET_DEBUG("Unsubscribing from image topic.");
00154     sub_image1_.unsubscribe();
00155     sub_image2_.unsubscribe();
00156     sub_camera_info_.unsubscribe();
00157   }
00158 
00159   void reconfigureCallback(Config& config, uint32_t level)
00160   {
00161     boost::mutex::scoped_lock lock(mutex_);
00162     config_ = config;
00163     alpha_ = config.alpha;
00164     if (config.auto_beta)
00165     {
00166       beta_ = 1.0 - alpha_;
00167       config.beta = beta_;
00168     }
00169     else
00170     {
00171       beta_ = config.beta;
00172     }
00173     gamma_ = config.gamma;
00174   }
00175 
00176   void doWork(const sensor_msgs::Image::ConstPtr& image_msg1, const sensor_msgs::Image::ConstPtr& image_msg2,
00177               const std::string& input_frame_from_msg)
00178   {
00179     boost::mutex::scoped_lock lock(mutex_);
00180     // Work on the image.
00181     try
00182     {
00183       cv::Mat image1 = cv_bridge::toCvCopy(image_msg1, image_msg1->encoding)->image;
00184       cv::Mat image2 = cv_bridge::toCvCopy(image_msg2, image_msg1->encoding)->image;
00185       if (cv_bridge::getCvType(image_msg1->encoding) != cv_bridge::getCvType(image_msg2->encoding))
00186       {
00187         NODELET_ERROR("Encoding of input images must be same type: %s, %s", image_msg1->encoding.c_str(),
00188                       image_msg2->encoding.c_str());
00189         return;
00190       }
00191 
00192       cv::Mat result_image;
00193       if (image1.rows != image2.rows || image1.cols != image2.cols)
00194       {
00195         int new_rows = std::max(image1.rows, image2.rows);
00196         int new_cols = std::max(image1.cols, image2.cols);
00197         // if ( new_rows != image1.rows || new_cols != image1.cols ) {
00198         cv::Mat image1 = cv::Mat(new_rows, new_cols, image1.type());
00199         image1.copyTo(image1(cv::Rect(0, 0, image1.cols, image1.rows)));
00200         image1 = image1.clone();  // need clone becuase toCvShare??
00201 
00202         // if ( new_rows != image2.rows || new_cols != image2.cols ) {
00203         cv::Mat image2 = cv::Mat(new_rows, new_cols, image2.type());
00204         image2.copyTo(image2(cv::Rect(0, 0, image2.cols, image2.rows)));
00205         image2 = image2.clone();
00206       }
00207       cv::addWeighted(image1, alpha_, image2, beta_, gamma_, result_image);
00208       //-- Show what you got
00209       sensor_msgs::ImagePtr image_msg3 =
00210           cv_bridge::CvImage(image_msg1->header, image_msg1->encoding, result_image).toImageMsg();
00211       if (debug_view_)
00212       {
00213         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00214 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_IS_NOT_SUPPORTED
00215         cv::imshow(window_name_, result_image);
00216 #else
00217 #ifdef CV_BRIDGE_CVT_COLOR_FOR_DISPLAY_OPTION_IS_NOT_SUPPORTED
00218         cv::imshow(window_name_,
00219                    cv_bridge::cvtColorForDisplay(cv_bridge::toCvShare(image_msg3, image_msg3->encoding))->image);
00220 #else
00221         cv_bridge::CvtColorForDisplayOptions options;
00222         if (sensor_msgs::image_encodings::bitDepth(image_msg1->encoding) == 32 ||
00223             sensor_msgs::image_encodings::bitDepth(image_msg1->encoding) == 64)
00224         {
00225           // float or double image
00226           options.do_dynamic_scaling = true;
00227         }
00228         cv::imshow(window_name_, cv_bridge::cvtColorForDisplay(cv_bridge::toCvShare(image_msg3), "", options)->image);
00229 #endif
00230 #endif
00231         int c = cv::waitKey(1);
00232       }
00233       img_pub_.publish(image_msg3);
00234     }
00235     catch (cv::Exception& e)
00236     {
00237       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00238     }
00239 
00240     prev_stamp_ = image_msg1->header.stamp;
00241   }
00242 
00243 public:
00244   virtual void onInit()  // NOLINT(modernize-use-override)
00245   {
00246     Nodelet::onInit();
00247     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00248 
00249     pnh_->param("debug_view", debug_view_, false);
00250     if (debug_view_)
00251     {
00252       always_subscribe_ = true;
00253     }
00254     prev_stamp_ = ros::Time(0, 0);
00255 
00256     window_name_ = "AddingImages Demo";
00258     // Dynamic Reconfigure
00260     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00261     dynamic_reconfigure::Server<Config>::CallbackType f =
00262         boost::bind(&AddingImagesNodelet::reconfigureCallback, this, _1, _2);
00263     reconfigure_server_->setCallback(f);
00264 
00265     pnh_->param("approximate_sync", approximate_sync_, true);
00266     pnh_->param("queue_size", queue_size_, 100);
00267     img_pub_ = advertiseImage(*pnh_, "image", 1);
00268     onInitPostProcess();
00269   }
00270 };
00271 }  // namespace opencv_apps
00272 
00273 namespace adding_images
00274 {
00275 class AddingImagesNodelet : public opencv_apps::AddingImagesNodelet
00276 {
00277 public:
00278   virtual void onInit()  // NOLINT(modernize-use-override)
00279   {
00280     ROS_WARN("DeprecationWarning: Nodelet adding_images/adding_images is deprecated, "
00281              "and renamed to opencv_apps/adding_images.");
00282     opencv_apps::AddingImagesNodelet::onInit();
00283   }
00284 };
00285 }  // namespace adding_images
00286 
00287 #include <pluginlib/class_list_macros.h>
00288 PLUGINLIB_EXPORT_CLASS(opencv_apps::AddingImagesNodelet, nodelet::Nodelet);
00289 PLUGINLIB_EXPORT_CLASS(adding_images::AddingImagesNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26