dissimilarity_getter.h
Go to the documentation of this file.
00001 /********************************************
00002  * Shape dissimilarity measurement based on the Multi-scale
00003  * Convexity Concavity (MCC) representation.
00004  *
00005  * Based on article 
00006  * @ARTICLE{Adamek2004,
00007  *    author={Adamek, T. and O''Connor, N.E.},
00008  *    journal={Circuits and Systems for Video Technology, IEEE Transactions on}, 
00009  *    title={A multiscale representation method for nonrigid shapes with a single closed contour},
00010  *    year={2004},
00011  *    volume={14},
00012  *    number={5},
00013  *    pages={742-753},
00014  *    doi={10.1109/TCSVT.2004.826776},
00015  *    ISSN={1051-8215},
00016  *    }
00017  *************************************/
00018 
00019 #ifndef PM_MCC_DISSIMILARITY_GETTER_H
00020 #define PM_MCC_DISSIMILARITY_GETTER_H
00021 
00022 #include <algorithm>
00023 #include <limits>
00024 #include <cmath>
00025 #include <cassert>
00026 
00027 #include <boost/numeric/ublas/matrix.hpp>
00028 
00029 #include <lama_common/point.h>
00030 #include <lama_common/polygon_utils.h> // for resamplePolygon().
00031 #include <place_matcher_msgs/PolygonDissimilarity.h>
00032 #include <ros/ros.h>
00033 #include <std_msgs/String.h>
00034 
00035 namespace place_matcher_mcc
00036 {
00037 
00038 typedef boost::numeric::ublas::matrix<double> matrix;
00039 typedef std::vector<geometry_msgs::Polygon> polygon_list;
00040 
00041 class DissimilarityGetter
00042 {
00043   public :
00044 
00045     DissimilarityGetter();
00046 
00047     double getDissimilarity(const geometry_msgs::Polygon& polygon1, const geometry_msgs::Polygon& polygon2);
00048     bool getDissimilarity(place_matcher_msgs::PolygonDissimilarityRequest& req, place_matcher_msgs::PolygonDissimilarityResponse& res);
00049 
00050     // Number of scales to compute, i.e. max. sigma for the Gaussian filtering.
00051     unsigned int scale_count;
00052     
00053     // Number of points to keep for the mcc computation.
00054     unsigned int sample_count;
00055 
00056     // Optional rotation invariance.
00057     bool rotation_invariance;
00058 
00059   private :
00060 
00061     double compute_convexity(const polygon_list& polygons, matrix& m);
00062     matrix compare(const matrix& a, const matrix& b);
00063 };
00064 
00065 } /* namespace place_matcher_mcc */
00066 
00067 #endif /* PM_MCC_DISSIMILARITY_GETTER_H */


place_matcher_mcc
Author(s): Gaël Ecorchard , Karel Košnar
autogenerated on Sat Jun 8 2019 19:53:05