remove_small_regions_alg_node.cpp
Go to the documentation of this file.
00001 #include "remove_small_regions_alg_node.h"
00002 
00003 //#include <opencv2/highgui/highgui.hpp>
00004 //static const char WINDOW[] = "Image window";
00005 
00006 RemoveSmallRegionsAlgNode::RemoveSmallRegionsAlgNode(void) :
00007   algorithm_base::IriBaseAlgorithm<RemoveSmallRegionsAlgorithm>()
00008 {
00009         //init class attributes if necessary
00010         //this->loop_rate_ = 2;//in [Hz]
00011         
00012         // [init publishers]
00013         this->image_out_publisher_ = this->public_node_handle_.advertise<sensor_msgs::Image>("image_out", 1);
00014         
00015         // [init subscribers]
00016         this->image_in_subscriber_ = this->public_node_handle_.subscribe("image_in", 1, &RemoveSmallRegionsAlgNode::image_in_callback, this);
00017         
00018         // [init services]
00019         
00020         // [init clients]
00021         
00022         // [init action servers]
00023         
00024         // [init action clients]
00025         
00026         //cv::namedWindow(WINDOW);
00027 }
00028 
00029 RemoveSmallRegionsAlgNode::~RemoveSmallRegionsAlgNode(void)
00030 {
00031         // [free dynamic memory]
00032         //cv::destroyWindow(WINDOW);
00033 }
00034 
00035 void RemoveSmallRegionsAlgNode::mainNodeThread(void)
00036 {
00037         // [fill msg structures]
00038         //this->Image_msg_.data = my_var;
00039         
00040         // [fill srv structure and make request to the server]
00041         
00042         // [fill action structure and make request to the action server]
00043 
00044         // [publish messages]
00045         //this->remove_border_out_publisher_.publish(this->Image_msg_);
00046 }
00047 
00048 /*  [subscriber callbacks] */
00049 void RemoveSmallRegionsAlgNode::image_in_callback(const sensor_msgs::Image::ConstPtr& msg) 
00050 { 
00051         cv_bridge::CvImagePtr cv_ptr;
00052         try
00053         {
00054                 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00055         }
00056         catch (cv_bridge::Exception& e)
00057         {
00058                 ROS_ERROR("cv_bridge exception: %s", e.what());
00059                 return;
00060         }
00061         
00062         cv_ptr->image = processImage(cv_ptr->image);
00063         
00064         ROS_DEBUG("Remove small regions publishing image");
00065         this->image_out_publisher_.publish(cv_ptr->toImageMsg());
00066         
00067         //use appropiate mutex to shared variables if necessary 
00068         //this->alg_.lock(); 
00069         //this->remove_border_in_mutex_.enter(); 
00070 
00071         //std::cout << msg->data << std::endl; 
00072 
00073         //unlock previously blocked shared variables 
00074         //this->alg_.unlock(); 
00075         //this->remove_border_in_mutex_.exit(); 
00076 }
00077 
00078 /*  [service callbacks] */
00079 
00080 /*  [action callbacks] */
00081 
00082 /*  [action requests] */
00083 
00084 
00085 /* Other functions */
00086 cv::Mat RemoveSmallRegionsAlgNode::processImage(cv::Mat image)
00087 {
00088         Mat src_gray, res, threshold_output;
00089         vector<vector<Point> > contours;
00090         int thresh = 10;
00091         cvtColor( image, src_gray, CV_BGR2GRAY );
00092         
00094         threshold( src_gray, threshold_output, thresh, 255, THRESH_BINARY );
00095         
00097         findContours( threshold_output, contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE, Point(0, 0) );
00098         
00099         Mat mask = Mat::zeros( threshold_output.size(), CV_8UC3 );
00100         Scalar color_white = Scalar( 255, 255, 255 );
00101         for( size_t i = 0; i< contours.size(); i++ )
00102         { 
00103                 if (contours[i].size() < min_area_threshold) {
00104                         drawContours( mask, contours, i, color_white, CV_FILLED); 
00105                 }
00106         }
00107         
00108         bitwise_not(mask,mask);
00109         //cv::imshow(WINDOW, mask);
00110         //cv::waitKey(3);
00111         
00112         bitwise_and(image,mask,image);
00113         
00114         return image;
00115 }
00116 
00117 void RemoveSmallRegionsAlgNode::node_config_update(Config &config, uint32_t level)
00118 {
00119         this->alg_.lock();
00120         
00121         this->min_area_threshold = config.min_area_threshold;
00122         
00123         // save the current configuration
00124         this->alg_.config_=config;
00125         
00126         this->alg_.unlock();
00127 }
00128 
00129 void RemoveSmallRegionsAlgNode::addNodeDiagnostics(void)
00130 {
00131 }
00132 
00133 /* main function */
00134 int main(int argc,char *argv[])
00135 {
00136         return algorithm_base::main<RemoveSmallRegionsAlgNode>(argc, argv, "remove_small_regions_alg_node");
00137 }


iri_opencv_filters
Author(s): David Martinez
autogenerated on Fri Dec 6 2013 22:43:25