Public Member Functions | Public Attributes | Private Member Functions
place_matcher_mcc::DissimilarityGetter Class Reference

#include <dissimilarity_getter.h>

List of all members.

Public Member Functions

 DissimilarityGetter ()
double getDissimilarity (const geometry_msgs::Polygon &polygon1, const geometry_msgs::Polygon &polygon2)
bool getDissimilarity (place_matcher_msgs::PolygonDissimilarityRequest &req, place_matcher_msgs::PolygonDissimilarityResponse &res)

Public Attributes

bool rotation_invariance
unsigned int sample_count
unsigned int scale_count

Private Member Functions

matrix compare (const matrix &a, const matrix &b)
double compute_convexity (const polygon_list &polygons, matrix &m)

Detailed Description

Definition at line 41 of file dissimilarity_getter.h.


Constructor & Destructor Documentation

Definition at line 98 of file dissimilarity_getter.cpp.


Member Function Documentation

matrix place_matcher_mcc::DissimilarityGetter::compare ( const matrix a,
const matrix b 
) [private]

Compute the distance between two MCC representations

Compute the distance between two MCC representations, i.e. for each contour point of a and b (rows) sum the absolute difference on all scale levels (columns). In order to achieve the optional rotational invariance, a circular shift is applied on the rows of the second matrix.

Parameters:
[in]aAn (na x m) matrix.
[in]bAn (nb x m) matrix.
[out]An(na x nb) matrix.

Definition at line 249 of file dissimilarity_getter.cpp.

double place_matcher_mcc::DissimilarityGetter::compute_convexity ( const polygon_list polygons,
matrix m 
) [private]

Compute the convexity of scaled polygons.

Compute the convexity of scaled polygons by looking at the signed distance between a point at scale s and the same point at scale (s - 1). This approximates the curvature.

Return the estimated shape complexity as the average of the differences between max and min convexity/concavity measures over all scale levels.

Parameters:
[in]polygonsA list of s scaled polygons of n points each.
[out]mA multi-scale convexity concavity representation, an (n x s) matrix.
Returns:
The polygon complexity.

Definition at line 201 of file dissimilarity_getter.cpp.

double place_matcher_mcc::DissimilarityGetter::getDissimilarity ( const geometry_msgs::Polygon &  polygon1,
const geometry_msgs::Polygon &  polygon2 
)

Definition at line 105 of file dissimilarity_getter.cpp.

bool place_matcher_mcc::DissimilarityGetter::getDissimilarity ( place_matcher_msgs::PolygonDissimilarityRequest &  req,
place_matcher_msgs::PolygonDissimilarityResponse &  res 
)

Definition at line 138 of file dissimilarity_getter.cpp.


Member Data Documentation

Definition at line 57 of file dissimilarity_getter.h.

Definition at line 54 of file dissimilarity_getter.h.

Definition at line 51 of file dissimilarity_getter.h.


The documentation for this class was generated from the following files:


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