Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00044 #include "opencv_apps/nodelet.h"
00045 #include <image_transport/image_transport.h>
00046 #include <sensor_msgs/image_encodings.h>
00047 #include <cv_bridge/cv_bridge.h>
00048
00049 #include <opencv2/highgui/highgui.hpp>
00050 #include "opencv2/imgproc/imgproc.hpp"
00051
00052 #include "opencv_apps/PyramidsConfig.h"
00053 #include <dynamic_reconfigure/server.h>
00054
00055 namespace opencv_apps
00056 {
00057 class PyramidsNodelet : public opencv_apps::Nodelet
00058 {
00059 image_transport::Publisher img_pub_;
00060 image_transport::Subscriber img_sub_;
00061 image_transport::CameraSubscriber cam_sub_;
00062 ros::Publisher msg_pub_;
00063
00064 boost::shared_ptr<image_transport::ImageTransport> it_;
00065
00066 typedef opencv_apps::PyramidsConfig Config;
00067 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00068 Config config_;
00069 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00070
00071 int queue_size_;
00072 bool debug_view_;
00073
00074 int num_of_pyramids_;
00075
00076 std::string window_name_;
00077
00078 void reconfigureCallback(Config& new_config, uint32_t level)
00079 {
00080 config_ = new_config;
00081
00082 num_of_pyramids_ = config_.num_of_pyramids;
00083 }
00084
00085 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00086 {
00087 if (frame.empty())
00088 return image_frame;
00089 return frame;
00090 }
00091
00092 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00093 {
00094 doWork(msg, cam_info->header.frame_id);
00095 }
00096
00097 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00098 {
00099 doWork(msg, msg->header.frame_id);
00100 }
00101
00102 void doWork(const sensor_msgs::ImageConstPtr& image_msg, const std::string& input_frame_from_msg)
00103 {
00104
00105 try
00106 {
00107
00108 cv::Mat src_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00109
00110
00111 int num = num_of_pyramids_;
00112 switch (config_.pyramids_type)
00113 {
00114 case opencv_apps::Pyramids_Up:
00115 {
00116 while (num)
00117 {
00118 num--;
00119 cv::pyrUp(src_image, src_image, cv::Size(src_image.cols * 2, src_image.rows * 2));
00120 }
00121 break;
00122 }
00123 case opencv_apps::Pyramids_Down:
00124 {
00125 while (num)
00126 {
00127 num--;
00128 cv::pyrDown(src_image, src_image, cv::Size(src_image.cols / 2, src_image.rows / 2));
00129 }
00130 break;
00131 }
00132 }
00133
00134
00135 if (debug_view_)
00136 {
00137 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00138 cv::imshow(window_name_, src_image);
00139 int c = cv::waitKey(1);
00140 }
00141
00142
00143 img_pub_.publish(cv_bridge::CvImage(image_msg->header, image_msg->encoding, src_image).toImageMsg());
00144 }
00145 catch (cv::Exception& e)
00146 {
00147 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00148 }
00149 }
00150
00151 void subscribe()
00152 {
00153 NODELET_DEBUG("Subscribing to image topic.");
00154 if (config_.use_camera_info)
00155 cam_sub_ = it_->subscribeCamera("image", queue_size_, &PyramidsNodelet::imageCallbackWithInfo, this);
00156 else
00157 img_sub_ = it_->subscribe("image", queue_size_, &PyramidsNodelet::imageCallback, this);
00158 }
00159
00160 void unsubscribe()
00161 {
00162 NODELET_DEBUG("Unsubscribing from image topic.");
00163 img_sub_.shutdown();
00164 cam_sub_.shutdown();
00165 }
00166
00167 public:
00168 virtual void onInit()
00169 {
00170 Nodelet::onInit();
00171 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00172
00173 pnh_->param("queue_size", queue_size_, 3);
00174 pnh_->param("debug_view", debug_view_, false);
00175
00176 if (debug_view_)
00177 {
00178 always_subscribe_ = true;
00179 }
00180
00181 window_name_ = "Image Pyramids Demo";
00182
00183 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00184 dynamic_reconfigure::Server<Config>::CallbackType f =
00185 boost::bind(&PyramidsNodelet::reconfigureCallback, this, _1, _2);
00186 reconfigure_server_->setCallback(f);
00187
00188 img_pub_ = advertiseImage(*pnh_, "image", 1);
00189
00190 onInitPostProcess();
00191 }
00192 };
00193 }
00194
00195 namespace pyramids
00196 {
00197 class PyramidsNodelet : public opencv_apps::PyramidsNodelet
00198 {
00199 public:
00200 virtual void onInit()
00201 {
00202 ROS_WARN("DeprecationWarning: Nodelet pyramids/pyramids is deprecated, "
00203 "and renamed to opencv_apps/pyramids.");
00204 opencv_apps::PyramidsNodelet::onInit();
00205 }
00206 };
00207 }
00208
00209 #include <pluginlib/class_list_macros.h>
00210 PLUGINLIB_EXPORT_CLASS(opencv_apps::PyramidsNodelet, nodelet::Nodelet);
00211 PLUGINLIB_EXPORT_CLASS(pyramids::PyramidsNodelet, nodelet::Nodelet);