feature_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 _feature_map_alg_h_
00026 #define _feature_map_alg_h_
00027 
00028 #include <iri_feature_map/FeatureMapConfig.h>
00029 #include "mutex.h"
00030 #include <sensor_msgs/PointCloud2.h>
00031 #include <iri_publish_params/classifier_update.h>
00032 #include <iri_publish_params/classifier_params.h>
00033 #include <normal_descriptor_node/ndesc_pc.h>
00034 #include <normal_descriptor_node/ndesc.h>
00035 #include <pcl/point_cloud.h>
00036 #include <pcl/point_types.h>
00037 #include <pcl/ros/conversions.h>
00038 #include <vector>
00039 #include <Eigen/Dense>
00040 #include <string.h>
00041 #include <string>
00042 
00043 //include feature_map_alg main library
00044 
00050 class FeatureMapAlgorithm
00051 {
00052   protected:
00059     CMutex alg_mutex_;
00060 
00061     // private attributes and methods
00062     int sel_vector_; //selected centroid/classifier
00063     int filter_method_; //0=clustering dist to sel, 1=clustering supress nonsel,  2=linear classifier, 3=logistic classifier
00064     Eigen::MatrixXf classifiers_; // classifier params
00065     std::string filename_;
00066 
00067     float eval_clusters(const std::vector<float> & vect, bool suppress_nonselected);
00068     float eval_linear(const std::vector<float> & vect);
00069     float eval_logistic(const std::vector<float> & vect);
00070 
00071     // save last eval_cluter result (useful for logging)
00072     float last_eval_cluster_max_score;
00073     float last_eval_cluster_min_score;
00074 
00075   public:
00082     typedef iri_feature_map::FeatureMapConfig Config;
00083 
00084     void compute_feature_response_map(const normal_descriptor_node::ndesc_pc &ndesc_pc_msg, pcl::PointCloud<pcl::PointXYZRGB> &hmap);
00085     
00086     void update_params(const iri_publish_params::classifier_update &params);
00087     void update_selected_vector(const int selected);
00088 
00095     Config config_;
00096 
00105     FeatureMapAlgorithm(void);
00106 
00112     void lock(void) { alg_mutex_.enter(); };
00113 
00119     void unlock(void) { alg_mutex_.exit(); };
00120 
00128     bool try_enter(void) { return alg_mutex_.try_enter(); };
00129 
00141     void config_update(Config& new_cfg, uint32_t level=0);
00142 
00143     // here define all feature_map_alg interface methods to retrieve and set
00144     // the driver parameters
00145 
00146     // Save the max value scored
00147     float get_last_cluster_max_score();
00148     // Save the min value scored (non zero)
00149     float get_last_cluster_min_score();
00150 
00157     ~FeatureMapAlgorithm(void);
00158 };
00159 
00160 #endif


iri_feature_map
Author(s): Arnau Ramisa
autogenerated on Fri Dec 6 2013 21:14:32