wrinkled_map_alg.h
Go to the documentation of this file.
00001 // Copyright (C) 2010-2011 Institut de Robotica i Informatica Industrial, CSIC-UPC.
00002 // Author 
00003 // All rights reserved.
00004 //
00005 // This file is part of iri-ros-pkg
00006 // iri-ros-pkg is free software: you can redistribute it and/or modify
00007 // it under the terms of the GNU Lesser General Public License as published by
00008 // the Free Software Foundation, either version 3 of the License, or
00009 // at your option) any later version.
00010 //
00011 // This program is distributed in the hope that it will be useful,
00012 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00013 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014 // GNU Lesser General Public License for more details.
00015 //
00016 // You should have received a copy of the GNU Lesser General Public License
00017 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00018 // 
00019 // IMPORTANT NOTE: This code has been generated through a script from the 
00020 // iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness
00021 // of the scripts. ROS topics can be easly add by using those scripts. Please
00022 // refer to the IRI wiki page for more information:
00023 // http://wikiri.upc.es/index.php/Robotics_Lab
00024 
00025 #ifndef _wrinkled_map_alg_h_
00026 #define _wrinkled_map_alg_h_
00027 
00028 #include <iri_wrinkled_map/WrinkledMapConfig.h>
00029 #include "mutex.h"
00030 #include <sensor_msgs/PointCloud2.h>
00031 #include <pcl/point_cloud.h>
00032 #include <pcl/point_types.h>
00033 #include <pcl/ros/conversions.h>
00034 #include <vector>
00035 //borrar 24/2/12 #include <normal_descriptor_node/heat_map.h>
00036 #include <normal_descriptor_node/ndesc_pc.h>
00037 #include <normal_descriptor_node/ndesc.h>
00038 //#include <normal_descriptor_node/ndesc_pc_service.h>
00039 
00040 /* borrar 24/2/12
00041 typedef union {
00042     struct //anonymous
00043     {
00044       unsigned char Blue;
00045       unsigned char Green;
00046       unsigned char Red;
00047       unsigned char Alpha;
00048     };
00049     float float_value;
00050     long long_value;
00051 } RGBValue; 
00052   */
00053 
00054 //include wrinkled_map_alg main library
00055 
00061 class WrinkledMapAlgorithm
00062 {
00063   protected:
00070     CMutex alg_mutex_;
00071 
00072     // private attributes and methods
00073     // [wrinkledness/heat map computation]
00074     float min_entropy_;
00075 
00083     inline float 
00084       compute_entropy(const normal_descriptor_node::ndesc &nd)
00085     {
00086       float entropy=0;
00087       float norm_L1=0;
00088 
00089       for(uint i=0; i<nd.descriptor.size(); i++)
00090       {
00091         if(!isnan(nd.descriptor[i]))
00092           norm_L1 += nd.descriptor[i]; 
00093 
00094       }
00095       for(uint i=0; i<nd.descriptor.size(); i++)
00096       {
00097         if(!isnan(nd.descriptor[i]) && nd.descriptor[i]!=0)
00098         {
00099           float normalized_descriptor = nd.descriptor[i]/norm_L1;
00100           entropy += log(normalized_descriptor) * normalized_descriptor;
00101         }
00102       }
00103       if(isnan(entropy) || (-entropy)<this->min_entropy_)
00104         return this->min_entropy_;
00105       return -entropy;
00106     }
00107 
00108   public:
00109 
00110     void compute_entropy_wrinkled_map(const normal_descriptor_node::ndesc_pc &ndesc_pc_msg, pcl::PointCloud<pcl::PointXYZRGB> &hmap);
00111 
00112     bool publish_wrinkled_map_;
00113 
00120     typedef iri_wrinkled_map::WrinkledMapConfig Config;
00121 
00128     Config config_;
00129 
00138     WrinkledMapAlgorithm(void);
00139 
00145     void lock(void) { alg_mutex_.enter(); };
00146 
00152     void unlock(void) { alg_mutex_.exit(); };
00153 
00161     bool try_enter(void) { return alg_mutex_.try_enter(); };
00162 
00174     void config_update(Config& new_cfg, uint32_t level=0);
00175 
00176     // here define all wrinkled_map_alg interface methods to retrieve and set
00177     // the driver parameters
00178 
00185     ~WrinkledMapAlgorithm(void);
00186 };
00187 
00188 #endif


iri_wrinkled_map
Author(s): Arnau Ramisa
autogenerated on Fri Dec 6 2013 20:20:47