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 #include <ros/ros.h>
00036 #include "opencv_apps/nodelet.h"
00037 #include <image_transport/image_transport.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040
00041 #include <opencv2/highgui/highgui.hpp>
00042 #include <opencv2/imgproc/imgproc.hpp>
00043
00044 #include <dynamic_reconfigure/server.h>
00045 #include "opencv_apps/CornerHarrisConfig.h"
00046
00047
00054 namespace corner_harris {
00055 class CornerHarrisNodelet : public opencv_apps::Nodelet
00056 {
00057 image_transport::Publisher img_pub_;
00058 image_transport::Subscriber img_sub_;
00059 image_transport::CameraSubscriber cam_sub_;
00060 ros::Publisher msg_pub_;
00061
00062 boost::shared_ptr<image_transport::ImageTransport> it_;
00063
00064 typedef corner_harris::CornerHarrisConfig Config;
00065 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00066 Config config_;
00067 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00068
00069 bool debug_view_;
00070
00071 std::string window_name_;
00072 static bool need_config_update_;
00073
00074 int threshold_;
00075
00076 void reconfigureCallback(Config &new_config, uint32_t level)
00077 {
00078 config_ = new_config;
00079 threshold_ = config_.threshold;
00080 }
00081
00082 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00083 {
00084 if (frame.empty())
00085 return image_frame;
00086 return frame;
00087 }
00088
00089 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00090 {
00091 do_work(msg, cam_info->header.frame_id);
00092 }
00093
00094 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00095 {
00096 do_work(msg, msg->header.frame_id);
00097 }
00098
00099 static void trackbarCallback( int, void* )
00100 {
00101 need_config_update_ = true;
00102 }
00103
00104 void do_work(const sensor_msgs::ImageConstPtr& image_msg, const std::string input_frame_from_msg)
00105 {
00106
00107 try
00108 {
00109
00110 cv::Mat frame = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::BGR8)->image;
00111
00112
00113 cv::Mat dst, dst_norm, dst_norm_scaled;
00114 dst = cv::Mat::zeros( frame.size(), CV_32FC1 );
00115
00116 cv::Mat src_gray;
00117
00118 if ( frame.channels() > 1 ) {
00119 cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
00120 } else {
00121 src_gray = frame;
00122 cv::cvtColor( src_gray, frame, cv::COLOR_GRAY2BGR );
00123 }
00124
00126 int blockSize = 2;
00127 int apertureSize = 3;
00128 double k = 0.04;
00129
00131 cv::cornerHarris( src_gray, dst, blockSize, apertureSize, k, cv::BORDER_DEFAULT );
00132
00134 cv::normalize( dst, dst_norm, 0, 255, cv::NORM_MINMAX, CV_32FC1, cv::Mat() );
00135 cv::convertScaleAbs( dst_norm, dst_norm_scaled );
00136
00138 for( int j = 0; j < dst_norm.rows ; j++ ) {
00139 for( int i = 0; i < dst_norm.cols; i++ ) {
00140 if( (int) dst_norm.at<float>(j,i) > threshold_ ) {
00141 cv::circle( frame, cv::Point(i, j), 5, cv::Scalar(0), 2, 8, 0 );
00142 }
00143 }
00144 }
00145
00147 if( debug_view_) {
00148 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00149 const int max_threshold = 255;
00150 if (need_config_update_) {
00151 config_.threshold = threshold_;
00152 reconfigure_server_->updateConfig(config_);
00153 need_config_update_ = false;
00154 }
00155 cv::createTrackbar( "Threshold:", window_name_, &threshold_, max_threshold, trackbarCallback);
00156 }
00157
00158 if( debug_view_) {
00159 cv::imshow( window_name_, frame );
00160 int c = cv::waitKey(1);
00161 }
00162
00163
00164 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::BGR8, frame).toImageMsg();
00165 img_pub_.publish(out_img);
00166 }
00167 catch (cv::Exception &e)
00168 {
00169 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00170 }
00171 }
00172
00173 void subscribe()
00174 {
00175 NODELET_DEBUG("Subscribing to image topic.");
00176 if (config_.use_camera_info)
00177 cam_sub_ = it_->subscribeCamera("image", 3, &CornerHarrisNodelet::imageCallbackWithInfo, this);
00178 else
00179 img_sub_ = it_->subscribe("image", 3, &CornerHarrisNodelet::imageCallback, this);
00180 }
00181
00182 void unsubscribe()
00183 {
00184 NODELET_DEBUG("Unsubscribing from image topic.");
00185 img_sub_.shutdown();
00186 cam_sub_.shutdown();
00187 }
00188
00189 public:
00190 virtual void onInit()
00191 {
00192 Nodelet::onInit();
00193 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00194
00195 pnh_->param("debug_view", debug_view_, false);
00196
00197 if (debug_view_) {
00198 always_subscribe_ = true;
00199 }
00200
00201 window_name_ = "CornerHarris Demo";
00202
00203 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00204 dynamic_reconfigure::Server<Config>::CallbackType f =
00205 boost::bind(&CornerHarrisNodelet::reconfigureCallback, this, _1, _2);
00206 reconfigure_server_->setCallback(f);
00207
00208 img_pub_ = advertiseImage(*pnh_, "image", 1);
00209
00210 onInitPostProcess();
00211 }
00212 };
00213 bool CornerHarrisNodelet::need_config_update_ = false;
00214 }
00215
00216 #include <pluginlib/class_list_macros.h>
00217 PLUGINLIB_EXPORT_CLASS(corner_harris::CornerHarrisNodelet, nodelet::Nodelet);