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 #include <nodelet/nodelet.h>
00036 #include <image_transport/image_transport.h>
00037 #include <boost/thread.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <opencv2/imgproc/imgproc.hpp>
00040
00041 namespace depth_image_proc {
00042
00043 namespace enc = sensor_msgs::image_encodings;
00044
00045 class CropForemostNodelet : public nodelet::Nodelet
00046 {
00047
00048 boost::shared_ptr<image_transport::ImageTransport> it_;
00049 image_transport::Subscriber sub_raw_;
00050
00051
00052 boost::mutex connect_mutex_;
00053 image_transport::Publisher pub_depth_;
00054
00055 virtual void onInit();
00056
00057 void connectCb();
00058
00059 void depthCb(const sensor_msgs::ImageConstPtr& raw_msg);
00060
00061 double distance_;
00062 };
00063
00064 void CropForemostNodelet::onInit()
00065 {
00066 ros::NodeHandle& nh = getNodeHandle();
00067 ros::NodeHandle& private_nh = getPrivateNodeHandle();
00068 private_nh.getParam("distance", distance_);
00069 it_.reset(new image_transport::ImageTransport(nh));
00070
00071
00072 image_transport::SubscriberStatusCallback connect_cb = boost::bind(&CropForemostNodelet::connectCb, this);
00073
00074 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00075 pub_depth_ = it_->advertise("image", 1, connect_cb, connect_cb);
00076 }
00077
00078
00079 void CropForemostNodelet::connectCb()
00080 {
00081 boost::lock_guard<boost::mutex> lock(connect_mutex_);
00082 if (pub_depth_.getNumSubscribers() == 0)
00083 {
00084 sub_raw_.shutdown();
00085 }
00086 else if (!sub_raw_)
00087 {
00088 image_transport::TransportHints hints("raw", ros::TransportHints(), getPrivateNodeHandle());
00089 sub_raw_ = it_->subscribe("image_raw", 1, &CropForemostNodelet::depthCb, this, hints);
00090 }
00091 }
00092
00093 void CropForemostNodelet::depthCb(const sensor_msgs::ImageConstPtr& raw_msg)
00094 {
00095 cv_bridge::CvImagePtr cv_ptr;
00096 try
00097 {
00098 cv_ptr = cv_bridge::toCvCopy(raw_msg);
00099 }
00100 catch (cv_bridge::Exception& e)
00101 {
00102 ROS_ERROR("cv_bridge exception: %s", e.what());
00103 return;
00104 }
00105
00106
00107 if(sensor_msgs::image_encodings::numChannels(raw_msg->encoding) != 1){
00108 NODELET_ERROR_THROTTLE(2, "Only grayscale image is acceptable, got [%s]", raw_msg->encoding.c_str());
00109 return;
00110 }
00111
00112
00113 double minVal;
00114 cv::minMaxIdx(cv_ptr->image, &minVal, 0, 0, 0, cv_ptr->image != 0);
00115
00116 int imtype = cv_bridge::getCvType(raw_msg->encoding);
00117 switch (imtype){
00118 case CV_8UC1:
00119 case CV_8SC1:
00120 case CV_32F:
00121 cv::threshold(cv_ptr->image, cv_ptr->image, minVal + distance_, 0, CV_THRESH_TOZERO_INV);
00122 break;
00123 case CV_16UC1:
00124 case CV_16SC1:
00125 case CV_32SC1:
00126 case CV_64F:
00127
00128 cv_ptr->image.convertTo(cv_ptr->image, CV_32F);
00129 cv::threshold(cv_ptr->image, cv_ptr->image, minVal + distance_, 1, CV_THRESH_TOZERO_INV);
00130
00131 cv_ptr->image.convertTo(cv_ptr->image, imtype);
00132 break;
00133 }
00134
00135 pub_depth_.publish(cv_ptr->toImageMsg());
00136 }
00137
00138 }
00139
00140
00141 #include <pluginlib/class_list_macros.h>
00142 PLUGINLIB_EXPORT_CLASS(depth_image_proc::CropForemostNodelet,nodelet::Nodelet);