median_blur_alg_node.cpp
Go to the documentation of this file.
00001 #include "median_blur_alg_node.h"
00002 
00003 
00004 using namespace cv;
00005 
00006 MedianBlurAlgNode::MedianBlurAlgNode(void) :
00007   algorithm_base::IriBaseAlgorithm<MedianBlurAlgorithm>()
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, &MedianBlurAlgNode::image_in_callback, this);
00017         
00018         // [init services]
00019         
00020         // [init clients]
00021         
00022         // [init action servers]
00023         
00024         // [init action clients]
00025         
00026 }
00027 
00028 MedianBlurAlgNode::~MedianBlurAlgNode(void)
00029 {
00030         // [free dynamic memory]
00031 }
00032 
00033 void MedianBlurAlgNode::mainNodeThread(void)
00034 {
00035         // [fill msg structures]
00036         //this->Image_msg_.data = my_var;
00037         
00038         // [fill srv structure and make request to the server]
00039         
00040         // [fill action structure and make request to the action server]
00041 
00042         // [publish messages]
00043         //this->image_out_publisher_.publish(this->Image_msg_);
00044 }
00045 
00046 /*  [subscriber callbacks] */
00047 void MedianBlurAlgNode::image_in_callback(const sensor_msgs::Image::ConstPtr& msg) 
00048 { 
00049         cv_bridge::CvImagePtr cv_ptr;
00050         
00051         try
00052         {
00053                 cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8);
00054         }
00055         catch (cv_bridge::Exception& e)
00056         {
00057                 ROS_ERROR("cv_bridge exception: %s", e.what());
00058                 return;
00059         }
00060         
00061         cv_ptr->image = processImage(cv_ptr->image);
00062         
00063         ROS_DEBUG_STREAM("Publishing median blur");
00064         
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->image_in_mutex_.enter(); 
00070 
00071         //std::cout << msg->data << std::endl; 
00072 
00073         //unlock previously blocked shared variables 
00074         //this->alg_.unlock(); 
00075         //this->image_in_mutex_.exit(); 
00076 }
00077 
00078 /*  [service callbacks] */
00079 
00080 /*  [action callbacks] */
00081 
00082 /*  [action requests] */
00083 
00084 /* Other */
00085 cv::Mat MedianBlurAlgNode::processImage(cv::Mat image)
00086 {
00087         Mat dst;
00088         
00089         cv::medianBlur(image, dst, medianblur_size);
00090         
00091         return dst;
00092 }
00093 
00094 void MedianBlurAlgNode::node_config_update(Config &config, uint32_t level)
00095 {
00096         this->alg_.lock();
00097         
00098         this->medianblur_size = config.medianblur_size;
00099         
00100         // save the current configuration
00101         this->alg_.config_=config;
00102         
00103         this->alg_.unlock();
00104 }
00105 
00106 void MedianBlurAlgNode::addNodeDiagnostics(void)
00107 {
00108 }
00109 
00110 /* main function */
00111 int main(int argc,char *argv[])
00112 {
00113         return algorithm_base::main<MedianBlurAlgNode>(argc, argv, "median_blur_alg_node");
00114 }


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