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 #include <nodelet/nodelet.h>
00035 #include <image_transport/image_transport.h>
00036 #include <boost/thread.hpp>
00037 #include <cv_bridge/cv_bridge.h>
00038
00039
00040 namespace image_proc {
00041
00042 namespace enc = sensor_msgs::image_encodings;
00043
00044 class CropNonZeroNodelet : public nodelet::Nodelet
00045 {
00046
00047 boost::shared_ptr<image_transport::ImageTransport> it_;
00048 image_transport::Subscriber sub_raw_;
00049
00050
00051 boost::mutex connect_mutex_;
00052 image_transport::Publisher pub_;
00053
00054 virtual void onInit();
00055
00056 void connectCb();
00057
00058 void imageCb(const sensor_msgs::ImageConstPtr& raw_msg);
00059 };
00060
00061 void CropNonZeroNodelet::onInit()
00062 {
00063 ros::NodeHandle& nh = getNodeHandle();
00064 it_.reset(new image_transport::ImageTransport(nh));
00065
00066
00067 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&CropNonZeroNodelet::connectCb, this);
00068
00069 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00070 pub_ = it_->advertise("image", 1, connect_cb, connect_cb);
00071 }
00072
00073
00074 void CropNonZeroNodelet::connectCb()
00075 {
00076 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00077 if (pub_.getNumSubscribers() == 0)
00078 {
00079 sub_raw_.shutdown();
00080 }
00081 else if (!sub_raw_)
00082 {
00083 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00084 sub_raw_ = it_->subscribe("image_raw", 1, &CropNonZeroNodelet::imageCb, this, hints);
00085 }
00086 }
00087
00088 void CropNonZeroNodelet::imageCb(const sensor_msgs::ImageConstPtr& raw_msg)
00089 {
00090 cv_bridge::CvImagePtr cv_ptr;
00091 try
00092 {
00093 cv_ptr = cv_bridge::toCvCopy(raw_msg);
00094 }
00095 catch (cv_bridge::Exception& e)
00096 {
00097 ROS_ERROR("cv_bridge exception: %s", e.what());
00098 return;
00099 }
00100
00101
00102 if(sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1){
00103 NODELET_ERROR_THROTTLE(2, "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str());
00104 return;
00105 }
00106
00107 std::vector<std::vector<cv::Point> >cnt;
00108 cv::Mat1b m(raw_msg->width, raw_msg->height);
00109
00110 if (raw_msg->encoding == enc::TYPE_8UC1){
00111 m = cv_ptr->image;
00112 }else{
00113 double minVal, maxVal;
00114 cv::minMaxIdx(cv_ptr->image, &minVal, &maxVal, 0, 0, cv_ptr->image != 0.);
00115 double ra = maxVal - minVal;
00116
00117 cv_ptr->image.convertTo(m, CV_8U, 255./ra, -minVal*255./ra);
00118 }
00119
00120 cv::findContours(m, cnt, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
00121
00122
00123
00124
00125
00126
00127
00128 std::vector<std::vector<cv::Point> >::iterator it = cnt.begin();
00129 for(std::vector<std::vector<cv::Point> >::iterator i=cnt.begin();i!=cnt.end();++i){
00130 it = (*it).size() < (*i).size() ? i : it;
00131 }
00132 cv::Rect r = cv::boundingRect(cnt[std::distance(cnt.begin(), it)]);
00133
00134 cv_bridge::CvImage out_msg;
00135 out_msg.header = raw_msg->header;
00136 out_msg.encoding = raw_msg->encoding;
00137 out_msg.image = cv_ptr->image(r);
00138
00139 pub_.publish(out_msg.toImageMsg());
00140 }
00141
00142 }
00143
00144
00145 #include <pluginlib/class_list_macros.h>
00146 PLUGINLIB_EXPORT_CLASS(image_proc::CropNonZeroNodelet,nodelet::Nodelet);