Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
rtflann Namespace Reference

Namespaces

 anyimpl
 
 lsh
 
 serialization
 

Classes

struct  Accumulator
 
struct  Accumulator< char >
 
struct  Accumulator< int >
 
struct  Accumulator< short >
 
struct  Accumulator< unsigned char >
 
struct  Accumulator< unsigned int >
 
struct  Accumulator< unsigned short >
 
class  any
 
class  AutotunedIndex
 
struct  AutotunedIndexParams
 
class  BoundedHeap
 
struct  BranchStruct
 
class  CenterChooser
 
struct  ChiSquareDistance
 
class  CompositeIndex
 
struct  CompositeIndexParams
 
class  CountRadiusResultSet
 
class  CreatorNotFound
 
struct  disable_if
 
struct  disable_if< true, T >
 
struct  DistanceIndex
 
struct  DummyDistance
 
class  DynamicBitset
 
struct  enable_if
 
struct  enable_if< true, T >
 
struct  flann_datatype_type
 
struct  flann_datatype_type< FLANN_FLOAT32 >
 
struct  flann_datatype_type< FLANN_FLOAT64 >
 
struct  flann_datatype_type< FLANN_INT16 >
 
struct  flann_datatype_type< FLANN_INT32 >
 
struct  flann_datatype_type< FLANN_INT8 >
 
struct  flann_datatype_type< FLANN_UINT16 >
 
struct  flann_datatype_type< FLANN_UINT32 >
 
struct  flann_datatype_type< FLANN_UINT8 >
 
struct  flann_datatype_value
 
struct  flann_datatype_value< char >
 
struct  flann_datatype_value< double >
 
struct  flann_datatype_value< float >
 
struct  flann_datatype_value< int >
 
struct  flann_datatype_value< short >
 
struct  flann_datatype_value< unsigned char >
 
struct  flann_datatype_value< unsigned int >
 
struct  flann_datatype_value< unsigned short >
 
class  FLANNException
 
class  GonzalesCenterChooser
 
class  GroupWiseCenterChooser
 
struct  Hamming
 
struct  HammingLUT
 
struct  HammingPopcnt
 
class  Heap
 
struct  HellingerDistance
 
class  HierarchicalClusteringIndex
 
struct  HierarchicalClusteringIndexParams
 
struct  HistIntersectionDistance
 
class  Index
 
class  IndexBase
 
struct  IndexHeader
 
struct  IndexHeaderStruct
 
class  IntervalHeap
 
class  KDTreeIndex
 
struct  KDTreeIndexParams
 
class  KDTreeSingleIndex
 
struct  KDTreeSingleIndexParams
 
struct  KL_Divergence
 
class  KMeansIndex
 
struct  KMeansIndexParams
 
class  KMeansppCenterChooser
 
class  KNNRadiusResultSet
 
class  KNNRadiusUniqueResultSet
 
class  KNNResultSet
 
class  KNNResultSet2
 
class  KNNSimpleResultSet
 
class  KNNUniqueResultSet
 
struct  L1
 
struct  L2
 
struct  L2_3D
 
struct  L2_Simple
 
class  LinearIndex
 
struct  LinearIndexParams
 
class  Logger
 
class  LshIndex
 
struct  LshIndexParams
 
class  Matrix
 
class  Matrix_
 
struct  MaxDistance
 
struct  MinkowskiDistance
 
class  NNIndex
 
class  ObjectFactory
 
class  PooledAllocator
 
class  RadiusResultSet
 
class  RadiusUniqueResultSet
 
class  RandomCenterChooser
 
class  RandomGenerator
 
class  ResultSet
 
struct  same_type
 
struct  same_type< T, T >
 
struct  SavedIndexParams
 
struct  SearchParams
 
struct  squareDistance
 
struct  squareDistance< ChiSquareDistance< ElementType >, ElementType >
 
struct  squareDistance< HellingerDistance< ElementType >, ElementType >
 
struct  squareDistance< L2< ElementType >, ElementType >
 
struct  squareDistance< L2_3D< ElementType >, ElementType >
 
struct  squareDistance< L2_Simple< ElementType >, ElementType >
 
class  StartStopTimer
 
class  UniqueRandom
 
class  UniqueResultSet
 
struct  valid_combination
 

Typedefs

typedef std::map< std::string, anyIndexParams
 
typedef unsigned char uchar
 

Enumerations

enum  flann_algorithm_t {
  FLANN_INDEX_LINEAR = 0, FLANN_INDEX_KDTREE = 1, FLANN_INDEX_KMEANS = 2, FLANN_INDEX_COMPOSITE = 3,
  FLANN_INDEX_KDTREE_SINGLE = 4, FLANN_INDEX_HIERARCHICAL = 5, FLANN_INDEX_LSH = 6, FLANN_INDEX_SAVED = 254,
  FLANN_INDEX_AUTOTUNED = 255
}
 
enum  flann_centers_init_t { FLANN_CENTERS_RANDOM = 0, FLANN_CENTERS_GONZALES = 1, FLANN_CENTERS_KMEANSPP = 2, FLANN_CENTERS_GROUPWISE = 3 }
 
enum  flann_checks_t { FLANN_CHECKS_UNLIMITED = -1, FLANN_CHECKS_AUTOTUNED = -2 }
 
enum  flann_datatype_t {
  FLANN_NONE = -1, FLANN_INT8 = 0, FLANN_INT16 = 1, FLANN_INT32 = 2,
  FLANN_INT64 = 3, FLANN_UINT8 = 4, FLANN_UINT16 = 5, FLANN_UINT32 = 6,
  FLANN_UINT64 = 7, FLANN_FLOAT32 = 8, FLANN_FLOAT64 = 9
}
 
enum  flann_distance_t {
  FLANN_DIST_EUCLIDEAN = 1, FLANN_DIST_L2 = 1, FLANN_DIST_MANHATTAN = 2, FLANN_DIST_L1 = 2,
  FLANN_DIST_MINKOWSKI = 3, FLANN_DIST_MAX = 4, FLANN_DIST_HIST_INTERSECT = 5, FLANN_DIST_HELLINGER = 6,
  FLANN_DIST_CHI_SQUARE = 7, FLANN_DIST_KULLBACK_LEIBLER = 8, FLANN_DIST_HAMMING = 9, FLANN_DIST_HAMMING_LUT = 10,
  FLANN_DIST_HAMMING_POPCNT = 11, FLANN_DIST_L2_SIMPLE = 12
}
 
enum  flann_log_level_t {
  FLANN_LOG_NONE = 0, FLANN_LOG_FATAL = 1, FLANN_LOG_ERROR = 2, FLANN_LOG_WARN = 3,
  FLANN_LOG_INFO = 4, FLANN_LOG_DEBUG = 5
}
 
enum  tri_type { FLANN_False = 0, FLANN_True = 1, FLANN_Undefined }
 

Functions

template<typename T >
void addValue (int pos, float val, float *vals, T *point, T *points, int n)
 
template<typename T >
T * allocate (size_t count=1)
 
template<typename Distance >
void compute_ground_truth (const Matrix< typename Distance::ElementType > &dataset, const Matrix< typename Distance::ElementType > &testset, Matrix< size_t > &matches, int skip=0, Distance d=Distance())
 
template<typename Distance >
Distance::ResultType computeDistanceRaport (const Matrix< typename Distance::ElementType > &inputData, typename Distance::ElementType *target, size_t *neighbors, size_t *groundTruth, int veclen, int n, const Distance &distance)
 
int countCorrectMatches (size_t *neighbors, size_t *groundTruth, int n)
 
template<template< typename > class Index, typename Distance , typename T >
NNIndex< Distance > * create_index_ (rtflann::Matrix< T > data, const rtflann::IndexParams &params, const Distance &distance, typename enable_if< valid_combination< Index, Distance, T >::value, void >::type *=0)
 
template<template< typename > class Index, typename Distance , typename T >
NNIndex< Distance > * create_index_ (rtflann::Matrix< T > data, const rtflann::IndexParams &params, const Distance &distance, typename disable_if< valid_combination< Index, Distance, T >::value, void >::type *=0)
 
template<typename Distance >
NNIndex< Distance > * create_index_by_type (const flann_algorithm_t index_type, const Matrix< typename Distance::ElementType > &dataset, const IndexParams &params, const Distance &distance)
 
template<typename Distance >
Distance::ResultType ensureSquareDistance (typename Distance::ResultType dist)
 
template<typename Distance >
void find_nearest (const Matrix< typename Distance::ElementType > &dataset, typename Distance::ElementType *query, size_t *matches, size_t nn, size_t skip=0, Distance distance=Distance())
 
size_t flann_datatype_size (flann_datatype_t type)
 
template<typename T >
get_param (const IndexParams &params, std::string name, const T &default_value)
 
template<typename T >
get_param (const IndexParams &params, std::string name)
 
bool has_param (const IndexParams &params, std::string name)
 
template<typename Distance >
int hierarchicalClustering (const Matrix< typename Distance::ElementType > &points, Matrix< typename Distance::ResultType > &centers, const KMeansIndexParams &params, Distance d=Distance())
 
IndexHeader load_header (FILE *stream)
 
void log_verbosity (int level)
 
std::ostream & operator<< (std::ostream &out, const any &any_val)
 
template<typename T , typename F >
float optimizeSimplexDownhill (T *points, int n, F func, float *vals=NULL)
 
void print_params (const IndexParams &params)
 
void print_params (const SearchParams &params)
 
double rand_double (double high=1.0, double low=0)
 
int rand_int (int high=RAND_MAX, int low=0)
 
template<typename T >
Matrix< T > random_sample (Matrix< T > &srcMatrix, size_t size, bool remove=false)
 
template<typename Index >
void save_header (FILE *stream, const Index &index)
 
template<typename Index , typename Distance >
float search_with_ground_truth (Index &index, const Matrix< typename Distance::ElementType > &inputData, const Matrix< typename Distance::ElementType > &testData, const Matrix< size_t > &matches, int nn, int checks, float &time, typename Distance::ResultType &dist, const Distance &distance, int skipMatches)
 
void seed_random (unsigned int seed)
 
template<typename Index , typename Distance >
float test_index_checks (Index &index, const Matrix< typename Distance::ElementType > &inputData, const Matrix< typename Distance::ElementType > &testData, const Matrix< size_t > &matches, int checks, float &precision, const Distance &distance, int nn=1, int skipMatches=0)
 
template<typename Index , typename Distance >
float test_index_precision (Index &index, const Matrix< typename Distance::ElementType > &inputData, const Matrix< typename Distance::ElementType > &testData, const Matrix< size_t > &matches, float precision, int &checks, const Distance &distance, int nn=1, int skipMatches=0)
 
template<typename Index , typename Distance >
void test_index_precisions (Index &index, const Matrix< typename Distance::ElementType > &inputData, const Matrix< typename Distance::ElementType > &testData, const Matrix< int > &matches, float *precisions, int precisions_length, const Distance &distance, int nn=1, int skipMatches=0, float maxTime=0)
 

Variables

const size_t BLOCKSIZE =8192
 
const size_t WORDSIZE =16
 

Typedef Documentation

typedef std::map<std::string, any> rtflann::IndexParams

Definition at line 51 of file params.h.

typedef unsigned char rtflann::uchar

Definition at line 41 of file matrix.h.

Enumeration Type Documentation

Enumerator
FLANN_INDEX_LINEAR 
FLANN_INDEX_KDTREE 
FLANN_INDEX_KMEANS 
FLANN_INDEX_COMPOSITE 
FLANN_INDEX_KDTREE_SINGLE 
FLANN_INDEX_HIERARCHICAL 
FLANN_INDEX_LSH 
FLANN_INDEX_SAVED 
FLANN_INDEX_AUTOTUNED 

Definition at line 79 of file defines.h.

Enumerator
FLANN_CENTERS_RANDOM 
FLANN_CENTERS_GONZALES 
FLANN_CENTERS_KMEANSPP 
FLANN_CENTERS_GROUPWISE 

Definition at line 95 of file defines.h.

Enumerator
FLANN_CHECKS_UNLIMITED 
FLANN_CHECKS_AUTOTUNED 

Definition at line 146 of file defines.h.

Enumerator
FLANN_NONE 
FLANN_INT8 
FLANN_INT16 
FLANN_INT32 
FLANN_INT64 
FLANN_UINT8 
FLANN_UINT16 
FLANN_UINT32 
FLANN_UINT64 
FLANN_FLOAT32 
FLANN_FLOAT64 

Definition at line 131 of file defines.h.

Enumerator
FLANN_DIST_EUCLIDEAN 
FLANN_DIST_L2 
FLANN_DIST_MANHATTAN 
FLANN_DIST_L1 
FLANN_DIST_MINKOWSKI 
FLANN_DIST_MAX 
FLANN_DIST_HIST_INTERSECT 
FLANN_DIST_HELLINGER 
FLANN_DIST_CHI_SQUARE 
FLANN_DIST_KULLBACK_LEIBLER 
FLANN_DIST_HAMMING 
FLANN_DIST_HAMMING_LUT 
FLANN_DIST_HAMMING_POPCNT 
FLANN_DIST_L2_SIMPLE 

Definition at line 113 of file defines.h.

Enumerator
FLANN_LOG_NONE 
FLANN_LOG_FATAL 
FLANN_LOG_ERROR 
FLANN_LOG_WARN 
FLANN_LOG_INFO 
FLANN_LOG_DEBUG 

Definition at line 103 of file defines.h.

Enumerator
FLANN_False 
FLANN_True 
FLANN_Undefined 

Definition at line 54 of file params.h.

Function Documentation

template<typename T >
void rtflann::addValue ( int  pos,
float  val,
float *  vals,
T *  point,
T *  points,
int  n 
)

Adds val to array vals (and point to array points) and keeping the arrays sorted by vals.

Definition at line 41 of file simplex_downhill.h.

template<typename T >
T* rtflann::allocate ( size_t  count = 1)

Allocates (using C's malloc) a generic type T.

Params: count = number of instances to allocate. Returns: pointer (of type T*) to memory buffer

Definition at line 49 of file allocator.h.

template<typename Distance >
void rtflann::compute_ground_truth ( const Matrix< typename Distance::ElementType > &  dataset,
const Matrix< typename Distance::ElementType > &  testset,
Matrix< size_t > &  matches,
int  skip = 0,
Distance  d = Distance() 
)

Definition at line 87 of file ground_truth.h.

template<typename Distance >
Distance::ResultType rtflann::computeDistanceRaport ( const Matrix< typename Distance::ElementType > &  inputData,
typename Distance::ElementType *  target,
size_t *  neighbors,
size_t *  groundTruth,
int  veclen,
int  n,
const Distance &  distance 
)

Definition at line 64 of file index_testing.h.

int rtflann::countCorrectMatches ( size_t *  neighbors,
size_t *  groundTruth,
int  n 
)
inline

Definition at line 48 of file index_testing.h.

template<template< typename > class Index, typename Distance , typename T >
NNIndex<Distance>* rtflann::create_index_ ( rtflann::Matrix< T >  data,
const rtflann::IndexParams params,
const Distance &  distance,
typename enable_if< valid_combination< Index, Distance, T >::value, void >::type *  = 0 
)
inline

Definition at line 129 of file all_indices.h.

template<template< typename > class Index, typename Distance , typename T >
NNIndex<Distance>* rtflann::create_index_ ( rtflann::Matrix< T >  data,
const rtflann::IndexParams params,
const Distance &  distance,
typename disable_if< valid_combination< Index, Distance, T >::value, void >::type *  = 0 
)
inline

Definition at line 136 of file all_indices.h.

template<typename Distance >
NNIndex< Distance > * rtflann::create_index_by_type ( const flann_algorithm_t  index_type,
const Matrix< typename Distance::ElementType > &  dataset,
const IndexParams params,
const Distance &  distance 
)
inline

#define this symbol before including flann.h to enable GPU search algorithms. But you have to link libflann_cuda then!

Definition at line 144 of file all_indices.h.

template<typename Distance >
Distance::ResultType rtflann::ensureSquareDistance ( typename Distance::ResultType  dist)

Definition at line 63 of file center_chooser.h.

template<typename Distance >
void rtflann::find_nearest ( const Matrix< typename Distance::ElementType > &  dataset,
typename Distance::ElementType *  query,
size_t *  matches,
size_t  nn,
size_t  skip = 0,
Distance  distance = Distance() 
)

Definition at line 42 of file ground_truth.h.

size_t rtflann::flann_datatype_size ( flann_datatype_t  type)
inline

Definition at line 196 of file general.h.

template<typename T >
T rtflann::get_param ( const IndexParams params,
std::string  name,
const T &  default_value 
)

Definition at line 95 of file params.h.

template<typename T >
T rtflann::get_param ( const IndexParams params,
std::string  name 
)

Definition at line 107 of file params.h.

bool rtflann::has_param ( const IndexParams params,
std::string  name 
)
inline

Definition at line 89 of file params.h.

template<typename Distance >
int rtflann::hierarchicalClustering ( const Matrix< typename Distance::ElementType > &  points,
Matrix< typename Distance::ResultType > &  centers,
const KMeansIndexParams params,
Distance  d = Distance() 
)

Performs a hierarchical clustering of the points passed as argument and then takes a cut in the the clustering tree to return a flat clustering.

Parameters
[in]pointsPoints to be clustered
centersThe computed cluster centres. Matrix should be preallocated and centers.rows is the number of clusters requested.
paramsClustering parameters (The same as for flann::KMeansIndex)
dDistance to be used for clustering (eg: flann::L2)
Returns
number of clusters computed (can be different than clusters.rows and is the highest number of the form (branching-1)*K+1 smaller than clusters.rows).

Definition at line 434 of file flann.hpp.

IndexHeader rtflann::load_header ( FILE *  stream)
inline
Parameters
stream- Stream to load from
Returns
Index header

Definition at line 106 of file saving.h.

void rtflann::log_verbosity ( int  level)
inline

Sets the log level used for all flann functions

Parameters
levelVerbosity level

Definition at line 54 of file flann.hpp.

std::ostream& rtflann::operator<< ( std::ostream &  out,
const any any_val 
)
inline

Definition at line 286 of file any.h.

template<typename T , typename F >
float rtflann::optimizeSimplexDownhill ( T *  points,
int  n,
func,
float *  vals = NULL 
)

Simplex downhill optimization function. Preconditions: points is a 2D mattrix of size (n+1) x n func is the cost function taking n an array of n params and returning float vals is the cost function in the n+1 simplex points, if NULL it will be computed

Postcondition: returns optimum value and points[0..n] are the optimum parameters

Definition at line 69 of file simplex_downhill.h.

void rtflann::print_params ( const IndexParams params)
inline

Definition at line 118 of file params.h.

void rtflann::print_params ( const SearchParams params)
inline

Definition at line 127 of file params.h.

double rtflann::rand_double ( double  high = 1.0,
double  low = 0 
)
inline

Generates a random double value.

Parameters
highUpper limit
lowLower limit
Returns
Random double value

Definition at line 62 of file random.h.

int rtflann::rand_int ( int  high = RAND_MAX,
int  low = 0 
)
inline

Generates a random integer value.

Parameters
highUpper limit
lowLower limit
Returns
Random integer value

Definition at line 73 of file random.h.

template<typename T >
Matrix<T> rtflann::random_sample ( Matrix< T > &  srcMatrix,
size_t  size,
bool  remove = false 
)

Definition at line 40 of file sampling.h.

template<typename Index >
void rtflann::save_header ( FILE *  stream,
const Index index 
)

Saves index header to stream

Parameters
stream- Stream to save to
index- The index to save

Definition at line 89 of file saving.h.

template<typename Index , typename Distance >
float rtflann::search_with_ground_truth ( Index index,
const Matrix< typename Distance::ElementType > &  inputData,
const Matrix< typename Distance::ElementType > &  testData,
const Matrix< size_t > &  matches,
int  nn,
int  checks,
float &  time,
typename Distance::ResultType &  dist,
const Distance &  distance,
int  skipMatches 
)

Definition at line 86 of file index_testing.h.

void rtflann::seed_random ( unsigned int  seed)
inline

Seeds the random number generator

Parameters
seedRandom seed

Definition at line 48 of file random.h.

template<typename Index , typename Distance >
float rtflann::test_index_checks ( Index index,
const Matrix< typename Distance::ElementType > &  inputData,
const Matrix< typename Distance::ElementType > &  testData,
const Matrix< size_t > &  matches,
int  checks,
float &  precision,
const Distance &  distance,
int  nn = 1,
int  skipMatches = 0 
)

Definition at line 142 of file index_testing.h.

template<typename Index , typename Distance >
float rtflann::test_index_precision ( Index index,
const Matrix< typename Distance::ElementType > &  inputData,
const Matrix< typename Distance::ElementType > &  testData,
const Matrix< size_t > &  matches,
float  precision,
int &  checks,
const Distance &  distance,
int  nn = 1,
int  skipMatches = 0 
)

Definition at line 159 of file index_testing.h.

template<typename Index , typename Distance >
void rtflann::test_index_precisions ( Index index,
const Matrix< typename Distance::ElementType > &  inputData,
const Matrix< typename Distance::ElementType > &  testData,
const Matrix< int > &  matches,
float *  precisions,
int  precisions_length,
const Distance &  distance,
int  nn = 1,
int  skipMatches = 0,
float  maxTime = 0 
)

Definition at line 232 of file index_testing.h.

Variable Documentation

const size_t rtflann::BLOCKSIZE =8192

Definition at line 73 of file allocator.h.

const size_t rtflann::WORDSIZE =16

Pooled storage allocator

The following routines allow for the efficient allocation of storage in small chunks from a specified pool. Rather than allowing each structure to be freed individually, an entire pool of storage is freed at once. This method has two advantages over just using malloc() and free(). First, it is far more efficient for allocating small objects, as there is no overhead for remembering all the information needed to free each object or consolidating fragmented memory. Second, the decision about how long to keep an object is made at the time of allocation, and there is no need to track down all the objects to free them.

Definition at line 72 of file allocator.h.



rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:37:09