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
00041 #include <image_transport/image_transport.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045
00046 #include <opencv2/highgui/highgui.hpp>
00047 #include "opencv2/imgproc/imgproc.hpp"
00048
00049 #include "opencv_apps/nodelet.h"
00050 #include "opencv_apps/ThresholdConfig.h"
00051
00052 #include <dynamic_reconfigure/server.h>
00053
00054 namespace opencv_apps
00055 {
00056 class ThresholdNodelet : public opencv_apps::Nodelet
00057 {
00059
00061 typedef opencv_apps::ThresholdConfig Config;
00062 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00063 Config config_;
00064 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00065
00066 int queue_size_;
00067 bool debug_view_;
00068
00069 std::string window_name_;
00070
00071 image_transport::Publisher img_pub_;
00072 image_transport::Subscriber img_sub_;
00073 image_transport::CameraSubscriber cam_sub_;
00074
00075 boost::shared_ptr<image_transport::ImageTransport> it_;
00076
00077 boost::mutex mutex_;
00078 int threshold_type_;
00079 int max_binary_value_;
00080 int threshold_value_;
00081 bool apply_otsu_;
00082
00083 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00084 {
00085 doWork(msg, cam_info->header.frame_id);
00086 }
00087
00088 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00089 {
00090 doWork(msg, msg->header.frame_id);
00091 }
00092
00093 void subscribe()
00094 {
00095 NODELET_DEBUG("Subscribing to image topic.");
00096 if (config_.use_camera_info)
00097 cam_sub_ = it_->subscribeCamera("image", queue_size_, &ThresholdNodelet::imageCallbackWithInfo, this);
00098 else
00099 img_sub_ = it_->subscribe("image", queue_size_, &ThresholdNodelet::imageCallback, this);
00100 }
00101
00102 void unsubscribe()
00103 {
00104 NODELET_DEBUG("Unsubscribing from image topic.");
00105 img_sub_.shutdown();
00106 cam_sub_.shutdown();
00107 }
00108
00109 void reconfigureCallback(Config& config, uint32_t level)
00110 {
00111 boost::mutex::scoped_lock lock(mutex_);
00112 config_ = config;
00113 threshold_value_ = config.threshold;
00114 threshold_type_ = config.threshold_type;
00115 max_binary_value_ = config.max_binary;
00116 apply_otsu_ = config.apply_otsu;
00117 }
00118
00119 void doWork(const sensor_msgs::Image::ConstPtr& image_msg, const std::string& input_frame_from_msg)
00120 {
00121 try
00122 {
00123 cv::Mat src_image = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00124 cv::Mat gray_image;
00125 cv::cvtColor(src_image, gray_image, cv::COLOR_BGR2GRAY);
00126 cv::Mat result_image;
00127
00128 if (apply_otsu_)
00129 {
00130 threshold_type_ |= CV_THRESH_OTSU;
00131 }
00132 cv::threshold(gray_image, result_image, threshold_value_, max_binary_value_, threshold_type_);
00133
00134 if (debug_view_)
00135 {
00136 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00137 cv::imshow(window_name_, result_image);
00138 int c = cv::waitKey(1);
00139 }
00140 img_pub_.publish(
00141 cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::MONO8, result_image).toImageMsg());
00142 }
00143 catch (cv::Exception& e)
00144 {
00145 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00146 }
00147 }
00148
00149 public:
00150 virtual void onInit()
00151 {
00152 Nodelet::onInit();
00153 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00154
00155 pnh_->param("queue_size", queue_size_, 3);
00156 pnh_->param("debug_view", debug_view_, false);
00157 if (debug_view_)
00158 {
00159 always_subscribe_ = true;
00160 }
00162
00164 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00165 dynamic_reconfigure::Server<Config>::CallbackType f =
00166 boost::bind(&ThresholdNodelet::reconfigureCallback, this, _1, _2);
00167 reconfigure_server_->setCallback(f);
00168
00169 img_pub_ = advertiseImage(*pnh_, "image", 1);
00170 onInitPostProcess();
00171 }
00172 };
00173 }
00174
00175 namespace threshold
00176 {
00177 class ThresholdNodelet : public opencv_apps::ThresholdNodelet
00178 {
00179 public:
00180 virtual void onInit()
00181 {
00182 ROS_WARN("DeprecationWarning: Nodelet threshold/threshold is deprecated, "
00183 "and renamed to opencv_apps/threshold.");
00184 opencv_apps::ThresholdNodelet::onInit();
00185 }
00186 };
00187 }
00188
00189 #include <pluginlib/class_list_macros.h>
00190 PLUGINLIB_EXPORT_CLASS(opencv_apps::ThresholdNodelet, nodelet::Nodelet);
00191 PLUGINLIB_EXPORT_CLASS(threshold::ThresholdNodelet, nodelet::Nodelet);