color_find_hsv.h
Go to the documentation of this file.
00001 /* 
00002  * Copyright (c) 2010, Dejan Pangercic <dejan.pangercic@cs.tum.edu>, 
00003  Zoltan-Csaba Marton <marton@cs.tum.edu>, Nico Blodow <blodow@cs.tum.edu>
00004  * All rights reserved.
00005  * 
00006  * Redistribution and use in source and binary forms, with or without
00007  * modification, are permitted provided that the following conditions are met:
00008  * 
00009  *     * Redistributions of source code must retain the above copyright
00010  *       notice, this list of conditions and the following disclaimer.
00011  *     * Redistributions in binary form must reproduce the above copyright
00012  *       notice, this list of conditions and the following disclaimer in the
00013  *       documentation and/or other materials provided with the distribution.
00014  *     * Neither the name of Willow Garage, Inc. nor the names of its
00015  *       contributors may be used to endorse or promote products derived from
00016  *       this software without specific prior written permission.
00017  * 
00018  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00021  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00022  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00023  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00024  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00025  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00026  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00027  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00028  * POSSIBILITY OF SUCH DAMAGE.
00029  */
00030 
00031 #ifndef IMAGE_ALGOS_COLOR_FIND_HSV_H
00032 #define IMAGE_ALGOS_COLOR_FIND_HSV_H
00033 #include <fstream>
00034 
00035 #include <ros/ros.h>
00036 #include <ros/node_handle.h>
00037 
00038 #include <image_algos/image_algos.h>
00039 #include <ias_table_msgs/TableObject.h>
00040 //in image_algos.h:
00041 //#include "sensor_msgs/Image.h"
00042 
00043 #include "yaml-cpp/yaml.h"
00044 #include "cv.h"  
00045 #include "cv_bridge/CvBridge.h"
00046 #include "image_transport/image_transport.h"
00047 
00048 namespace image_algos
00049 {
00050 
00051 class ColorFindHSV : public ImageAlgo
00052 {
00053 public:
00054   ColorFindHSV () 
00055   { 
00056     colors_yaml_file_ = std::string ("data/colors.yaml");
00057   };
00058   typedef sensor_msgs::Image InputType;
00059   typedef ias_table_msgs::TableObject OutputType;
00060 
00061   static std::string default_input_topic ()
00062     {return std::string ("image");}
00063 
00064   static std::string default_output_topic ()
00065     {return std::string ("color");};
00066 
00067   static std::string default_node_name () 
00068     {return std::string ("find_color_hsv_node");};
00069 
00070   void init (ros::NodeHandle&);
00071   void pre  ();
00072   void post ();
00073   std::vector<std::string> requires ();
00074   std::vector<std::string> provides ();
00075   std::string process (const boost::shared_ptr<const InputType>);
00076   boost::shared_ptr<const OutputType> output ();
00077 
00078 protected:
00079   ros::NodeHandle nh_;
00080   struct threshold_values
00081   {
00082     //saturation threshold
00083     int sthreshold_min, sthreshold_max;  
00084     //hue threshold
00085     double hupper, hlower;
00086     //how many pixels of this color
00087     int pixel_frequency;
00088   } threshold_values_;
00089   
00090   std::map<std::string, threshold_values> color_values_map_;
00091   //output
00092   boost::shared_ptr<OutputType> color_;
00093   //learnt colors
00094   std::string colors_yaml_file_;
00095   //ros Image to IplImage conversion
00096   sensor_msgs::CvBridge bridge_;
00097   //result image publisher (if debug on)
00098   ros::Publisher result_image_pub_;
00099   //image_transport::ImageTransport it_;
00100 };
00101 
00102 }//namespace image_algos
00103 #endif
00104 
00105 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


image_algos
Author(s): Dejan Pangercic
autogenerated on Thu May 23 2013 18:41:31