#include <algorithm>#include <iostream>#include <fstream>#include <limits>#include <cmath>#include <cassert>#include <boost/numeric/ublas/matrix.hpp>#include <boost/numeric/ublas/io.hpp>#include <ros/ros.h>#include <std_msgs/String.h>#include <lama_common/point.h>#include <lama_common/polygon.h>#include <polygon_matcher/PolygonDissimilarity.h>
Go to the source code of this file.
Typedefs | |
| typedef boost::numeric::ublas::matrix < double > | matrix |
| typedef std::vector < geometry_msgs::Polygon > | polygon_list |
Functions | |
| geometry_msgs::Polygon | center (geometry_msgs::Polygon &p) |
| matrix | compare (matrix &a, matrix &b) |
| double | compute_convexity (const polygon_list &polygons, matrix &m) |
| bool | dissimilarity (polygon_matcher::PolygonDissimilarity::Request &req, polygon_matcher::PolygonDissimilarity::Response &res) |
| bool | evolve (geometry_msgs::Polygon &input, polygon_list &output, unsigned int maxSigma) |
| int | inpoly (const geometry_msgs::Polygon &p, const geometry_msgs::Point32 &point) |
| int | main (int argc, char **argv) |
| double | minDistance (const matrix &compared, const int start) |
Variables | |
| unsigned int | g_max_sigma |
| unsigned int | g_num_samples |
| bool | g_rotation_invariance |
| typedef boost::numeric::ublas::matrix<double> matrix |
Definition at line 46 of file pm_mcc_node.cpp.
| typedef std::vector<geometry_msgs::Polygon> polygon_list |
Definition at line 47 of file pm_mcc_node.cpp.
| geometry_msgs::Polygon center | ( | geometry_msgs::Polygon & | p | ) |
Definition at line 185 of file pm_mcc_node.cpp.
| double compute_convexity | ( | const polygon_list & | polygons, |
| matrix & | m | ||
| ) |
Definition at line 108 of file pm_mcc_node.cpp.
| bool dissimilarity | ( | polygon_matcher::PolygonDissimilarity::Request & | req, |
| polygon_matcher::PolygonDissimilarity::Response & | res | ||
| ) |
Definition at line 245 of file pm_mcc_node.cpp.
| bool evolve | ( | geometry_msgs::Polygon & | input, |
| polygon_list & | output, | ||
| unsigned int | maxSigma | ||
| ) |
Definition at line 64 of file pm_mcc_node.cpp.
| int inpoly | ( | const geometry_msgs::Polygon & | p, |
| const geometry_msgs::Point32 & | point | ||
| ) |
Definition at line 49 of file pm_mcc_node.cpp.
| int main | ( | int | argc, |
| char ** | argv | ||
| ) |
Definition at line 301 of file pm_mcc_node.cpp.
| double minDistance | ( | const matrix & | compared, |
| const int | start | ||
| ) |
Definition at line 208 of file pm_mcc_node.cpp.
| unsigned int g_max_sigma |
Definition at line 39 of file pm_mcc_node.cpp.
| unsigned int g_num_samples |
Definition at line 36 of file pm_mcc_node.cpp.
Definition at line 41 of file pm_mcc_node.cpp.