Commit 562914e3 authored by Vadim Pisarevsky's avatar Vadim Pisarevsky

upgraded to FLANN 1.6. Added miniflann interface, which is now used in the rest…

upgraded to FLANN 1.6. Added miniflann interface, which is now used in the rest of OpenCV. Added Python bindings for FLANN.
parent 4e42bf63
......@@ -44,7 +44,7 @@
#define __OPENCV_FEATURES_2D_HPP__
#include "opencv2/core/core.hpp"
#include "opencv2/flann/flann.hpp"
#include "opencv2/flann/miniflann.hpp"
#ifdef __cplusplus
#include <limits>
......
......@@ -603,7 +603,7 @@ void FlannBasedMatcher::radiusMatchImpl( const Mat& queryDescriptors, vector<vec
Mat queryDescriptorsRow = queryDescriptors.row(qIdx);
Mat indicesRow = indices.row(qIdx);
Mat distsRow = dists.row(qIdx);
flannIndex->radiusSearch( queryDescriptorsRow, indicesRow, distsRow, maxDistance*maxDistance, *searchParams );
flannIndex->radiusSearch( queryDescriptorsRow, indicesRow, distsRow, maxDistance*maxDistance, count, *searchParams );
}
convertToDMatches( mergedDescriptors, indices, dists, matches );
......
......@@ -405,14 +405,14 @@ int CV_FlannTest::radiusSearch( Mat& points, Mat& neighbors )
// 1st way
Mat p( 1, points.cols, CV_32FC1, points.ptr<float>(i) ),
n( 1, neighbors.cols, CV_32SC1, neighbors.ptr<int>(i) );
index->radiusSearch( p, n, dist, radius, SearchParams() );
index->radiusSearch( p, n, dist, radius, neighbors.cols, SearchParams() );
// 2nd way
float* fltPtr = points.ptr<float>(i);
vector<float> query( fltPtr, fltPtr + points.cols );
vector<int> indices( neighbors1.cols, 0 );
vector<float> dists( dist.cols, 0 );
index->radiusSearch( query, indices, dists, radius, SearchParams() );
index->radiusSearch( query, indices, dists, radius, neighbors.cols, SearchParams() );
vector<int>::const_iterator it = indices.begin();
for( j = 0; it != indices.end(); ++it, j++ )
neighbors1.at<int>(i,j) = *it;
......
......@@ -27,50 +27,129 @@
*************************************************************************/
#ifndef _OPENCV_ALL_INDICES_H_
#define _OPENCV_ALL_INDICES_H_
#ifndef OPENCV_FLANN_ALL_INDICES_H_
#define OPENCV_FLANN_ALL_INDICES_H_
#include "opencv2/flann/general.h"
#include "general.h"
#include "nn_index.h"
#include "kdtree_index.h"
#include "kdtree_single_index.h"
#include "kmeans_index.h"
#include "composite_index.h"
#include "linear_index.h"
#include "hierarchical_clustering_index.h"
#include "lsh_index.h"
#include "autotuned_index.h"
#include "opencv2/flann/nn_index.h"
#include "opencv2/flann/kdtree_index.h"
#include "opencv2/flann/kmeans_index.h"
#include "opencv2/flann/composite_index.h"
#include "opencv2/flann/linear_index.h"
#include "opencv2/flann/autotuned_index.h"
namespace cvflann
{
template<typename T>
NNIndex<T>* create_index_by_type(const Matrix<T>& dataset, const IndexParams& params)
template<typename KDTreeCapability, typename VectorSpace, typename Distance>
struct index_creator
{
flann_algorithm_t index_type = params.getIndexType();
static NNIndex<Distance>* create(const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance)
{
flann_algorithm_t index_type = get_param<flann_algorithm_t>(params, "algorithm");
NNIndex<T>* nnIndex;
NNIndex<Distance>* nnIndex;
switch (index_type) {
case FLANN_INDEX_LINEAR:
nnIndex = new LinearIndex<T>(dataset, (const LinearIndexParams&)params);
nnIndex = new LinearIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_KDTREE_SINGLE:
nnIndex = new KDTreeSingleIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_KDTREE:
nnIndex = new KDTreeIndex<T>(dataset, (const KDTreeIndexParams&)params);
nnIndex = new KDTreeIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_KMEANS:
nnIndex = new KMeansIndex<T>(dataset, (const KMeansIndexParams&)params);
nnIndex = new KMeansIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_COMPOSITE:
nnIndex = new CompositeIndex<T>(dataset, (const CompositeIndexParams&) params);
nnIndex = new CompositeIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_AUTOTUNED:
nnIndex = new AutotunedIndex<T>(dataset, (const AutotunedIndexParams&) params);
nnIndex = new AutotunedIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_HIERARCHICAL:
nnIndex = new HierarchicalClusteringIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_LSH:
nnIndex = new LshIndex<Distance>(dataset, params, distance);
break;
default:
throw FLANNException("Unknown index type");
}
return nnIndex;
}
};
template<typename VectorSpace, typename Distance>
struct index_creator<False,VectorSpace,Distance>
{
static NNIndex<Distance>* create(const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance)
{
flann_algorithm_t index_type = get_param<flann_algorithm_t>(params, "algorithm");
NNIndex<Distance>* nnIndex;
switch (index_type) {
case FLANN_INDEX_LINEAR:
nnIndex = new LinearIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_KMEANS:
nnIndex = new KMeansIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_HIERARCHICAL:
nnIndex = new HierarchicalClusteringIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_LSH:
nnIndex = new LshIndex<Distance>(dataset, params, distance);
break;
default:
throw FLANNException("Unknown index type");
}
return nnIndex;
}
};
template<typename Distance>
struct index_creator<False,False,Distance>
{
static NNIndex<Distance>* create(const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance)
{
flann_algorithm_t index_type = get_param<flann_algorithm_t>(params, "algorithm");
NNIndex<Distance>* nnIndex;
switch (index_type) {
case FLANN_INDEX_LINEAR:
nnIndex = new LinearIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_HIERARCHICAL:
nnIndex = new HierarchicalClusteringIndex<Distance>(dataset, params, distance);
break;
case FLANN_INDEX_LSH:
nnIndex = new LshIndex<Distance>(dataset, params, distance);
break;
default:
throw FLANNException("Unknown index type");
}
return nnIndex;
}
};
template<typename Distance>
NNIndex<Distance>* create_index_by_type(const Matrix<typename Distance::ElementType>& dataset, const IndexParams& params, const Distance& distance)
{
return index_creator<typename Distance::is_kdtree_distance,
typename Distance::is_vector_space_distance,
Distance>::create(dataset, params,distance);
}
} //namespace cvflann
}
#endif /* _OPENCV_ALL_INDICES_H_ */
#endif /* OPENCV_FLANN_ALL_INDICES_H_ */
......@@ -28,12 +28,13 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_ALLOCATOR_H_
#define _OPENCV_ALLOCATOR_H_
#ifndef OPENCV_FLANN_ALLOCATOR_H_
#define OPENCV_FLANN_ALLOCATOR_H_
#include <stdlib.h>
#include <stdio.h>
namespace cvflann
{
......@@ -70,7 +71,7 @@ T* allocate(size_t count = 1)
const size_t WORDSIZE=16;
const size_t BLOCKSIZE=8192;
class CV_EXPORTS PooledAllocator
class PooledAllocator
{
/* We maintain memory alignment to word boundaries by requiring that all
allocations be in multiples of the machine wordsize. */
......@@ -106,10 +107,10 @@ public:
*/
~PooledAllocator()
{
void *prev;
void* prev;
while (base != NULL) {
prev = *((void **) base); /* Get pointer to prev block. */
prev = *((void**) base); /* Get pointer to prev block. */
::free(base);
base = prev;
}
......@@ -119,7 +120,7 @@ public:
* Returns a pointer to a piece of new memory of the given size in bytes
* allocated from the pool.
*/
void* allocateBytes(int size)
void* allocateMemory(int size)
{
int blocksize;
......@@ -144,11 +145,11 @@ public:
void* m = ::malloc(blocksize);
if (!m) {
fprintf(stderr,"Failed to allocate memory.\n");
exit(1);
return NULL;
}
/* Fill first word of new block with pointer to previous block. */
((void **) m)[0] = base;
((void**) m)[0] = base;
base = m;
int shift = 0;
......@@ -176,12 +177,12 @@ public:
template <typename T>
T* allocate(size_t count = 1)
{
T* mem = (T*) this->allocateBytes((int)(sizeof(T)*count));
T* mem = (T*) this->allocateMemory((int)(sizeof(T)*count));
return mem;
}
};
} // namespace cvflann
}
#endif //_OPENCV_ALLOCATOR_H_
#endif //OPENCV_FLANN_ALLOCATOR_H_
#ifndef OPENCV_FLANN_ANY_H_
#define OPENCV_FLANN_ANY_H_
/*
* (C) Copyright Christopher Diggins 2005-2011
* (C) Copyright Pablo Aguilar 2005
* (C) Copyright Kevlin Henney 2001
*
* Distributed under the Boost Software License, Version 1.0. (See
* accompanying file LICENSE_1_0.txt or copy at
* http://www.boost.org/LICENSE_1_0.txt
*
* Adapted for FLANN by Marius Muja
*/
#include <stdexcept>
#include <ostream>
#include <typeinfo>
namespace cdiggins
{
namespace anyimpl
{
struct bad_any_cast
{
};
struct empty_any
{
};
struct base_any_policy
{
virtual void static_delete(void** x) = 0;
virtual void copy_from_value(void const* src, void** dest) = 0;
virtual void clone(void* const* src, void** dest) = 0;
virtual void move(void* const* src, void** dest) = 0;
virtual void* get_value(void** src) = 0;
virtual size_t get_size() = 0;
virtual const std::type_info& type() = 0;
virtual void print(std::ostream& out, void* const* src) = 0;
};
template<typename T>
struct typed_base_any_policy : base_any_policy
{
virtual size_t get_size() { return sizeof(T); }
virtual const std::type_info& type() { return typeid(T); }
};
template<typename T>
struct small_any_policy : typed_base_any_policy<T>
{
virtual void static_delete(void**) { }
virtual void copy_from_value(void const* src, void** dest)
{
new (dest) T(* reinterpret_cast<T const*>(src));
}
virtual void clone(void* const* src, void** dest) { *dest = *src; }
virtual void move(void* const* src, void** dest) { *dest = *src; }
virtual void* get_value(void** src) { return reinterpret_cast<void*>(src); }
virtual void print(std::ostream& out, void* const* src) { out << *reinterpret_cast<T const*>(src); }
};
template<typename T>
struct big_any_policy : typed_base_any_policy<T>
{
virtual void static_delete(void** x)
{
if (* x) delete (* reinterpret_cast<T**>(x)); *x = NULL;
}
virtual void copy_from_value(void const* src, void** dest)
{
*dest = new T(*reinterpret_cast<T const*>(src));
}
virtual void clone(void* const* src, void** dest)
{
*dest = new T(**reinterpret_cast<T* const*>(src));
}
virtual void move(void* const* src, void** dest)
{
(*reinterpret_cast<T**>(dest))->~T();
**reinterpret_cast<T**>(dest) = **reinterpret_cast<T* const*>(src);
}
virtual void* get_value(void** src) { return *src; }
virtual void print(std::ostream& out, void* const* src) { out << *reinterpret_cast<T const*>(*src); }
};
template<typename T>
struct choose_policy
{
typedef big_any_policy<T> type;
};
template<typename T>
struct choose_policy<T*>
{
typedef small_any_policy<T*> type;
};
struct any;
/// Choosing the policy for an any type is illegal, but should never happen.
/// This is designed to throw a compiler error.
template<>
struct choose_policy<any>
{
typedef void type;
};
/// Specializations for small types.
#define SMALL_POLICY(TYPE) \
template<> \
struct choose_policy<TYPE> { typedef small_any_policy<TYPE> type; \
};
SMALL_POLICY(signed char);
SMALL_POLICY(unsigned char);
SMALL_POLICY(signed short);
SMALL_POLICY(unsigned short);
SMALL_POLICY(signed int);
SMALL_POLICY(unsigned int);
SMALL_POLICY(signed long);
SMALL_POLICY(unsigned long);
SMALL_POLICY(float);
SMALL_POLICY(bool);
#undef SMALL_POLICY
/// This function will return a different policy for each type.
template<typename T>
base_any_policy* get_policy()
{
static typename choose_policy<T>::type policy;
return &policy;
}
} // namespace anyimpl
struct any
{
private:
// fields
anyimpl::base_any_policy* policy;
void* object;
public:
/// Initializing constructor.
template <typename T>
any(const T& x)
: policy(anyimpl::get_policy<anyimpl::empty_any>()), object(NULL)
{
assign(x);
}
/// Empty constructor.
any()
: policy(anyimpl::get_policy<anyimpl::empty_any>()), object(NULL)
{ }
/// Special initializing constructor for string literals.
any(const char* x)
: policy(anyimpl::get_policy<anyimpl::empty_any>()), object(NULL)
{
assign(x);
}
/// Copy constructor.
any(const any& x)
: policy(anyimpl::get_policy<anyimpl::empty_any>()), object(NULL)
{
assign(x);
}
/// Destructor.
~any()
{
policy->static_delete(&object);
}
/// Assignment function from another any.
any& assign(const any& x)
{
reset();
policy = x.policy;
policy->clone(&x.object, &object);
return *this;
}
/// Assignment function.
template <typename T>
any& assign(const T& x)
{
reset();
policy = anyimpl::get_policy<T>();
policy->copy_from_value(&x, &object);
return *this;
}
/// Assignment operator.
template<typename T>
any& operator=(const T& x)
{
return assign(x);
}
/// Assignment operator, specialed for literal strings.
/// They have types like const char [6] which don't work as expected.
any& operator=(const char* x)
{
return assign(x);
}
/// Utility functions
any& swap(any& x)
{
std::swap(policy, x.policy);
std::swap(object, x.object);
return *this;
}
/// Cast operator. You can only cast to the original type.
template<typename T>
T& cast()
{
if (policy->type() != typeid(T)) throw anyimpl::bad_any_cast();
T* r = reinterpret_cast<T*>(policy->get_value(&object));
return *r;
}
/// Cast operator. You can only cast to the original type.
template<typename T>
const T& cast() const
{
if (policy->type() != typeid(T)) throw anyimpl::bad_any_cast();
void* obj = const_cast<void*>(object);
T* r = reinterpret_cast<T*>(policy->get_value(&obj));
return *r;
}
/// Returns true if the any contains no value.
bool empty() const
{
return policy->type() == typeid(anyimpl::empty_any);
}
/// Frees any allocated memory, and sets the value to NULL.
void reset()
{
policy->static_delete(&object);
policy = anyimpl::get_policy<anyimpl::empty_any>();
}
/// Returns true if the two types are the same.
bool compatible(const any& x) const
{
return policy->type() == x.policy->type();
}
/// Returns if the type is compatible with the policy
template<typename T>
bool has_type()
{
return policy->type() == typeid(T);
}
const std::type_info& type() const
{
return policy->type();
}
friend std::ostream& operator <<(std::ostream& out, const any& any_val);
};
inline std::ostream& operator <<(std::ostream& out, const any& any_val)
{
any_val.policy->print(out,&any_val.object);
return out;
}
}
#endif // OPENCV_FLANN_ANY_H_
......@@ -28,135 +28,167 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_COMPOSITETREE_H_
#define _OPENCV_COMPOSITETREE_H_
#ifndef OPENCV_FLANN_COMPOSITE_INDEX_H_
#define OPENCV_FLANN_COMPOSITE_INDEX_H_
#include "opencv2/flann/general.h"
#include "opencv2/flann/nn_index.h"
#include "general.h"
#include "nn_index.h"
#include "kdtree_index.h"
#include "kmeans_index.h"
namespace cvflann
{
struct CompositeIndexParams : public IndexParams {
CompositeIndexParams(int trees_ = 4, int branching_ = 32, int iterations_ = 11,
flann_centers_init_t centers_init_ = FLANN_CENTERS_RANDOM, float cb_index_ = 0.2 ) :
IndexParams(FLANN_INDEX_COMPOSITE),
trees(trees_),
branching(branching_),
iterations(iterations_),
centers_init(centers_init_),
cb_index(cb_index_) {};
int trees; // number of randomized trees to use (for kdtree)
int branching; // branching factor (for kmeans tree)
int iterations; // max iterations to perform in one kmeans clustering (kmeans tree)
flann_centers_init_t centers_init; // algorithm used for picking the initial cluster centers for kmeans tree
float cb_index; // cluster boundary index. Used when searching the kmeans tree
void print() const
/**
* Index parameters for the CompositeIndex.
*/
struct CompositeIndexParams : public IndexParams
{
CompositeIndexParams(int trees = 4, int branching = 32, int iterations = 11,
flann_centers_init_t centers_init = FLANN_CENTERS_RANDOM, float cb_index = 0.2 )
{
logger().info("Index type: %d\n",(int)algorithm);
logger().info("Trees: %d\n", trees);
logger().info("Branching: %d\n", branching);
logger().info("Iterations: %d\n", iterations);
logger().info("Centres initialisation: %d\n", centers_init);
logger().info("Cluster boundary weight: %g\n", cb_index);
(*this)["algorithm"] = FLANN_INDEX_KMEANS;
// number of randomized trees to use (for kdtree)
(*this)["trees"] = trees;
// branching factor
(*this)["branching"] = branching;
// max iterations to perform in one kmeans clustering (kmeans tree)
(*this)["iterations"] = iterations;
// algorithm used for picking the initial cluster centers for kmeans tree
(*this)["centers_init"] = centers_init;
// cluster boundary index. Used when searching the kmeans tree
(*this)["cb_index"] = cb_index;
}
};
template <typename ELEM_TYPE, typename DIST_TYPE = typename DistType<ELEM_TYPE>::type >
class CompositeIndex : public NNIndex<ELEM_TYPE>
/**
* This index builds a kd-tree index and a k-means index and performs nearest
* neighbour search both indexes. This gives a slight boost in search performance
* as some of the neighbours that are missed by one index are found by the other.
*/
template <typename Distance>
class CompositeIndex : public NNIndex<Distance>
{
KMeansIndex<ELEM_TYPE, DIST_TYPE>* kmeans;
KDTreeIndex<ELEM_TYPE, DIST_TYPE>* kdtree;
const Matrix<ELEM_TYPE> dataset;
const IndexParams& index_params;
CompositeIndex& operator=(const CompositeIndex&);
CompositeIndex(const CompositeIndex&);
public:
CompositeIndex(const Matrix<ELEM_TYPE>& inputData, const CompositeIndexParams& params = CompositeIndexParams() ) :
dataset(inputData), index_params(params)
typedef typename Distance::ElementType ElementType;
typedef typename Distance::ResultType DistanceType;
/**
* Index constructor
* @param inputData dataset containing the points to index
* @param params Index parameters
* @param d Distance functor
* @return
*/
CompositeIndex(const Matrix<ElementType>& inputData, const IndexParams& params = CompositeIndexParams(),
Distance d = Distance()) : index_params_(params)
{
KDTreeIndexParams kdtree_params(params.trees);
KMeansIndexParams kmeans_params(params.branching, params.iterations, params.centers_init, params.cb_index);
kdtree = new KDTreeIndex<ELEM_TYPE, DIST_TYPE>(inputData,kdtree_params);
kmeans = new KMeansIndex<ELEM_TYPE, DIST_TYPE>(inputData,kmeans_params);
kdtree_index_ = new KDTreeIndex<Distance>(inputData, params, d);
kmeans_index_ = new KMeansIndex<Distance>(inputData, params, d);
}
CompositeIndex(const CompositeIndex&);
CompositeIndex& operator=(const CompositeIndex&);
virtual ~CompositeIndex()
{
delete kdtree;
delete kmeans;
delete kdtree_index_;
delete kmeans_index_;
}
/**
* @return The index type
*/
flann_algorithm_t getType() const
{
return FLANN_INDEX_COMPOSITE;
}
/**
* @return Size of the index
*/
size_t size() const
{
return dataset.rows;
return kdtree_index_->size();
}
/**
* \returns The dimensionality of the features in this index.
*/
size_t veclen() const
{
return dataset.cols;
return kdtree_index_->veclen();
}
/**
* \returns The amount of memory (in bytes) used by the index.
*/
int usedMemory() const
{
return kmeans->usedMemory()+kdtree->usedMemory();
return kmeans_index_->usedMemory() + kdtree_index_->usedMemory();
}
/**
* \brief Builds the index
*/
void buildIndex()
{
logger().info("Building kmeans tree...\n");
kmeans->buildIndex();
logger().info("Building kdtree tree...\n");
kdtree->buildIndex();
Logger::info("Building kmeans tree...\n");
kmeans_index_->buildIndex();
Logger::info("Building kdtree tree...\n");
kdtree_index_->buildIndex();
}
/**
* \brief Saves the index to a stream
* \param stream The stream to save the index to
*/
void saveIndex(FILE* stream)
{
kmeans->saveIndex(stream);
kdtree->saveIndex(stream);
kmeans_index_->saveIndex(stream);
kdtree_index_->saveIndex(stream);
}
/**
* \brief Loads the index from a stream
* \param stream The stream from which the index is loaded
*/
void loadIndex(FILE* stream)
{
kmeans->loadIndex(stream);
kdtree->loadIndex(stream);
kmeans_index_->loadIndex(stream);
kdtree_index_->loadIndex(stream);
}
void findNeighbors(ResultSet<ELEM_TYPE>& result, const ELEM_TYPE* vec, const SearchParams& searchParams)
/**
* \returns The index parameters
*/
IndexParams getParameters() const
{
kmeans->findNeighbors(result,vec,searchParams);
kdtree->findNeighbors(result,vec,searchParams);
return index_params_;
}
const IndexParams* getParameters() const
/**
* \brief Method that searches for nearest-neighbours
*/
void findNeighbors(ResultSet<DistanceType>& result, const ElementType* vec, const SearchParams& searchParams)
{
return &index_params;
kmeans_index_->findNeighbors(result, vec, searchParams);
kdtree_index_->findNeighbors(result, vec, searchParams);
}
private:
/** The k-means index */
KMeansIndex<Distance>* kmeans_index_;
/** The kd-tree index */
KDTreeIndex<Distance>* kdtree_index_;
/** The index parameters */
const IndexParams index_params_;
};
} // namespace cvflann
}
#endif //_OPENCV_COMPOSITETREE_H_
#endif //OPENCV_FLANN_COMPOSITE_INDEX_H_
/***********************************************************************
* Software License Agreement (BSD License)
*
* Copyright 2008-2011 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
* Copyright 2008-2011 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef OPENCV_FLANN_CONFIG_H_
#define OPENCV_FLANN_CONFIG_H_
#define FLANN_VERSION "1.6.10"
#endif /* OPENCV_FLANN_CONFIG_H_ */
/***********************************************************************
* Software License Agreement (BSD License)
*
* Copyright 2008-2011 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
* Copyright 2008-2011 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef OPENCV_FLANN_DEFINES_H_
#define OPENCV_FLANN_DEFINES_H_
#include "config.h"
#ifdef WIN32
/* win32 dll export/import directives */
#ifdef FLANN_EXPORTS
#define FLANN_EXPORT __declspec(dllexport)
#elif defined(FLANN_STATIC)
#define FLANN_EXPORT
#else
#define FLANN_EXPORT __declspec(dllimport)
#endif
#else
/* unix needs nothing */
#define FLANN_EXPORT
#endif
#ifdef __GNUC__
#define FLANN_DEPRECATED __attribute__ ((deprecated))
#elif defined(_MSC_VER)
#define FLANN_DEPRECATED __declspec(deprecated)
#else
#pragma message("WARNING: You need to implement FLANN_DEPRECATED for this compiler")
#define FLANN_DEPRECATED
#endif
#if __amd64__ || __x86_64__ || _WIN64 || _M_X64
#define FLANN_PLATFORM_64_BIT
#else
#define FLANN_PLATFORM_32_BIT
#endif
#define FLANN_ARRAY_LEN(a) (sizeof(a)/sizeof(a[0]))
/* Nearest neighbour index algorithms */
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,
// deprecated constants, should use the FLANN_INDEX_* ones instead
LINEAR = 0,
KDTREE = 1,
KMEANS = 2,
COMPOSITE = 3,
KDTREE_SINGLE = 4,
SAVED = 254,
AUTOTUNED = 255
};
enum flann_centers_init_t
{
FLANN_CENTERS_RANDOM = 0,
FLANN_CENTERS_GONZALES = 1,
FLANN_CENTERS_KMEANSPP = 2,
// deprecated constants, should use the FLANN_CENTERS_* ones instead
CENTERS_RANDOM = 0,
CENTERS_GONZALES = 1,
CENTERS_KMEANSPP = 2
};
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,
};
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_CS = 7,
FLANN_DIST_KULLBACK_LEIBLER = 8,
FLANN_DIST_KL = 8,
// deprecated constants, should use the FLANN_DIST_* ones instead
EUCLIDEAN = 1,
MANHATTAN = 2,
MINKOWSKI = 3,
MAX_DIST = 4,
HIST_INTERSECT = 5,
HELLINGER = 6,
CS = 7,
KL = 8,
KULLBACK_LEIBLER = 8
};
enum flann_datatype_t
{
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_CHECKS_UNLIMITED = -1,
FLANN_CHECKS_AUTOTUNED = -2
};
#endif /* OPENCV_FLANN_DEFINES_H_ */
This diff is collapsed.
#ifndef OPENCV_FLANN_DUMMY_H_
#define OPENCV_FLANN_DUMMY_H_
namespace cvflann
{
#if (defined WIN32 || defined _WIN32 || defined WINCE) && defined CVAPI_EXPORTS
__declspec(dllexport)
#endif
void dummyfunc();
}
#endif /* OPENCV_FLANN_DUMMY_H_ */
/***********************************************************************
* Software License Agreement (BSD License)
*
* Copyright 2008-2009 Marius Muja (mariusm@cs.ubc.ca). All rights reserved.
* Copyright 2008-2009 David G. Lowe (lowe@cs.ubc.ca). All rights reserved.
*
* THE BSD LICENSE
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
* OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
* IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
* NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
* DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
* THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
/***********************************************************************
* Author: Vincent Rabaud
*************************************************************************/
#ifndef OPENCV_FLANN_DYNAMIC_BITSET_H_
#define OPENCV_FLANN_DYNAMIC_BITSET_H_
//#define FLANN_USE_BOOST 1
#if FLANN_USE_BOOST
#include <boost/dynamic_bitset.hpp>
typedef boost::dynamic_bitset<> DynamicBitset;
#else
#include <limits.h>
#include "dist.h"
/** Class re-implementing the boost version of it
* This helps not depending on boost, it also does not do the bound checks
* and has a way to reset a block for speed
*/
class DynamicBitset
{
public:
/** @param default constructor
*/
DynamicBitset()
{
}
/** @param only constructor we use in our code
* @param the size of the bitset (in bits)
*/
DynamicBitset(size_t size)
{
resize(size);
reset();
}
/** Sets all the bits to 0
*/
void clear()
{
std::fill(bitset_.begin(), bitset_.end(), 0);
}
/** @brief checks if the bitset is empty
* @return true if the bitset is empty
*/
bool empty() const
{
return bitset_.empty();
}
/** @param set all the bits to 0
*/
void reset()
{
std::fill(bitset_.begin(), bitset_.end(), 0);
}
/** @brief set one bit to 0
* @param
*/
void reset(size_t index)
{
bitset_[index / cell_bit_size_] &= ~(size_t(1) << (index % cell_bit_size_));
}
/** @brief sets a specific bit to 0, and more bits too
* This function is useful when resetting a given set of bits so that the
* whole bitset ends up being 0: if that's the case, we don't care about setting
* other bits to 0
* @param
*/
void reset_block(size_t index)
{
bitset_[index / cell_bit_size_] = 0;
}
/** @param resize the bitset so that it contains at least size bits
* @param size
*/
void resize(size_t size)
{
size_ = size;
bitset_.resize(size / cell_bit_size_ + 1);
}
/** @param set a bit to true
* @param index the index of the bit to set to 1
*/
void set(size_t index)
{
bitset_[index / cell_bit_size_] |= size_t(1) << (index % cell_bit_size_);
}
/** @param gives the number of contained bits
*/
size_t size() const
{
return size_;
}
/** @param check if a bit is set
* @param index the index of the bit to check
* @return true if the bit is set
*/
bool test(size_t index) const
{
return (bitset_[index / cell_bit_size_] & (size_t(1) << (index % cell_bit_size_))) != 0;
}
private:
std::vector<size_t> bitset_;
size_t size_;
static const unsigned int cell_bit_size_ = CHAR_BIT * sizeof(size_t);
};
#endif
#endif // OPENCV_FLANN_DYNAMIC_BITSET_H_
......@@ -28,119 +28,25 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_GENERAL_H_
#define _OPENCV_GENERAL_H_
#ifdef __cplusplus
#ifndef OPENCV_FLANN_GENERAL_H_
#define OPENCV_FLANN_GENERAL_H_
#include "defines.h"
#include <stdexcept>
#include <cassert>
#include "opencv2/flann/object_factory.h"
#include "opencv2/flann/logger.h"
namespace cvflann {
#undef ARRAY_LEN
#define ARRAY_LEN(a) (sizeof(a)/sizeof(a[0]))
/* Nearest neighbour index algorithms */
enum flann_algorithm_t {
FLANN_INDEX_LINEAR = 0,
FLANN_INDEX_KDTREE = 1,
FLANN_INDEX_KMEANS = 2,
FLANN_INDEX_COMPOSITE = 3,
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
};
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_CS = 7,
FLANN_DIST_KULLBACK_LEIBLER = 8,
FLANN_DIST_KL = 8
};
enum flann_datatype_t {
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
};
template <typename ELEM_TYPE>
struct DistType
namespace cvflann
{
typedef ELEM_TYPE type;
};
template <>
struct DistType<unsigned char>
{
typedef float type;
};
template <>
struct DistType<int>
class FLANNException : public std::runtime_error
{
typedef float type;
};
class FLANNException : public std::runtime_error {
public:
public:
FLANNException(const char* message) : std::runtime_error(message) { }
FLANNException(const std::string& message) : std::runtime_error(message) { }
};
struct CV_EXPORTS IndexParams {
protected:
IndexParams(flann_algorithm_t algorithm_) : algorithm(algorithm_) {};
public:
virtual ~IndexParams() {}
virtual flann_algorithm_t getIndexType() const { return algorithm; }
virtual void print() const = 0;
flann_algorithm_t algorithm;
};
typedef ObjectFactory<IndexParams, flann_algorithm_t> ParamsFactory;
CV_EXPORTS ParamsFactory& ParamsFactory_instance();
struct CV_EXPORTS SearchParams {
SearchParams(int checks_ = 32) :
checks(checks_) {};
int checks;
};
} // namespace cvflann
}
#endif
#endif /* _OPENCV_GENERAL_H_ */
#endif /* OPENCV_FLANN_GENERAL_H_ */
......@@ -28,39 +28,41 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_GROUND_TRUTH_H_
#define _OPENCV_GROUND_TRUTH_H_
#ifndef OPENCV_FLANN_GROUND_TRUTH_H_
#define OPENCV_FLANN_GROUND_TRUTH_H_
#include "dist.h"
#include "matrix.h"
#include "opencv2/flann/dist.h"
#include "opencv2/flann/matrix.h"
namespace cvflann
{
template <typename T>
void find_nearest(const Matrix<T>& dataset, T* query, int* matches, int nn, int skip = 0)
template <typename Distance>
void find_nearest(const Matrix<typename Distance::ElementType>& dataset, typename Distance::ElementType* query, int* matches, int nn,
int skip = 0, Distance distance = Distance())
{
typedef typename Distance::ElementType ElementType;
typedef typename Distance::ResultType DistanceType;
int n = nn + skip;
T* query_end = query + dataset.cols;
long* match = new long[n];
T* dists = new T[n];
int* match = new int[n];
DistanceType* dists = new DistanceType[n];
dists[0] = (float)flann_dist(query, query_end, dataset[0]);
dists[0] = distance(dataset[0], query, dataset.cols);
match[0] = 0;
int dcnt = 1;
for (size_t i=1;i<dataset.rows;++i) {
T tmp = (T)flann_dist(query, query_end, dataset[i]);
for (size_t i=1; i<dataset.rows; ++i) {
DistanceType tmp = distance(dataset[i], query, dataset.cols);
if (dcnt<n) {
match[dcnt] = (long)i;
match[dcnt] = i;
dists[dcnt++] = tmp;
}
else if (tmp < dists[dcnt-1]) {
dists[dcnt-1] = tmp;
match[dcnt-1] = (long)i;
match[dcnt-1] = i;
}
int j = dcnt-1;
......@@ -72,7 +74,7 @@ void find_nearest(const Matrix<T>& dataset, T* query, int* matches, int nn, int
}
}
for (int i=0;i<nn;++i) {
for (int i=0; i<nn; ++i) {
matches[i] = match[i+skip];
}
......@@ -81,15 +83,16 @@ void find_nearest(const Matrix<T>& dataset, T* query, int* matches, int nn, int
}
template <typename T>
void compute_ground_truth(const Matrix<T>& dataset, const Matrix<T>& testset, Matrix<int>& matches, int skip=0)
template <typename Distance>
void compute_ground_truth(const Matrix<typename Distance::ElementType>& dataset, const Matrix<typename Distance::ElementType>& testset, Matrix<int>& matches,
int skip=0, Distance d = Distance())
{
for (size_t i=0;i<testset.rows;++i) {
find_nearest(dataset, testset[i], matches[i], (int)matches.cols, skip);
for (size_t i=0; i<testset.rows; ++i) {
find_nearest<Distance>(dataset, testset[i], matches[i], (int)matches.cols, skip, d);
}
}
} // namespace cvflann
}
#endif //_OPENCV_GROUND_TRUTH_H_
#endif //OPENCV_FLANN_GROUND_TRUTH_H_
......@@ -27,137 +27,207 @@
*************************************************************************/
#ifndef _OPENCV_HDF5_H_
#define _OPENCV_HDF5_H_
#ifndef OPENCV_FLANN_HDF5_H_
#define OPENCV_FLANN_HDF5_H_
#include <H5Cpp.h>
#include <hdf5.h>
#include "opencv2/flann/matrix.h"
#include "matrix.h"
#ifndef H5_NO_NAMESPACE
using namespace H5;
#endif
namespace cvflann
{
namespace {
namespace
{
template<typename T>
PredType get_hdf5_type()
hid_t get_hdf5_type()
{
throw FLANNException("Unsupported type for IO operations");
}
template<> PredType get_hdf5_type<char>() { return PredType::NATIVE_CHAR; }
template<> PredType get_hdf5_type<unsigned char>() { return PredType::NATIVE_UCHAR; }
template<> PredType get_hdf5_type<short int>() { return PredType::NATIVE_SHORT; }
template<> PredType get_hdf5_type<unsigned short int>() { return PredType::NATIVE_USHORT; }
template<> PredType get_hdf5_type<int>() { return PredType::NATIVE_INT; }
template<> PredType get_hdf5_type<unsigned int>() { return PredType::NATIVE_UINT; }
template<> PredType get_hdf5_type<long>() { return PredType::NATIVE_LONG; }
template<> PredType get_hdf5_type<unsigned long>() { return PredType::NATIVE_ULONG; }
template<> PredType get_hdf5_type<float>() { return PredType::NATIVE_FLOAT; }
template<> PredType get_hdf5_type<double>() { return PredType::NATIVE_DOUBLE; }
template<> PredType get_hdf5_type<long double>() { return PredType::NATIVE_LDOUBLE; }
template<>
hid_t get_hdf5_type<char>() { return H5T_NATIVE_CHAR; }
template<>
hid_t get_hdf5_type<unsigned char>() { return H5T_NATIVE_UCHAR; }
template<>
hid_t get_hdf5_type<short int>() { return H5T_NATIVE_SHORT; }
template<>
hid_t get_hdf5_type<unsigned short int>() { return H5T_NATIVE_USHORT; }
template<>
hid_t get_hdf5_type<int>() { return H5T_NATIVE_INT; }
template<>
hid_t get_hdf5_type<unsigned int>() { return H5T_NATIVE_UINT; }
template<>
hid_t get_hdf5_type<long>() { return H5T_NATIVE_LONG; }
template<>
hid_t get_hdf5_type<unsigned long>() { return H5T_NATIVE_ULONG; }
template<>
hid_t get_hdf5_type<float>() { return H5T_NATIVE_FLOAT; }
template<>
hid_t get_hdf5_type<double>() { return H5T_NATIVE_DOUBLE; }
template<>
hid_t get_hdf5_type<long double>() { return H5T_NATIVE_LDOUBLE; }
}
#define CHECK_ERROR(x,y) if ((x)<0) throw FLANNException((y));
template<typename T>
void save_to_file(const cvflann::Matrix<T>& flann_dataset, const std::string& filename, const std::string& name)
void save_to_file(const cvflann::Matrix<T>& dataset, const std::string& filename, const std::string& name)
{
// Try block to detect exceptions raised by any of the calls inside it
try
{
/*
* Turn off the auto-printing when failure occurs so that we can
* handle the errors appropriately
*/
Exception::dontPrint();
/*
* Create a new file using H5F_ACC_TRUNC access,
* default file creation properties, and default file
* access properties.
*/
H5File file( filename, H5F_ACC_TRUNC );
#if H5Eset_auto_vers == 2
H5Eset_auto( H5E_DEFAULT, NULL, NULL );
#else
H5Eset_auto( NULL, NULL );
#endif
herr_t status;
hid_t file_id;
file_id = H5Fopen(filename.c_str(), H5F_ACC_RDWR, H5P_DEFAULT);
if (file_id < 0) {
file_id = H5Fcreate(filename.c_str(), H5F_ACC_EXCL, H5P_DEFAULT, H5P_DEFAULT);
}
CHECK_ERROR(file_id,"Error creating hdf5 file.");
/*
* Define the size of the array and create the data space for fixed
* size dataset.
*/
hsize_t dimsf[2]; // dataset dimensions
dimsf[0] = flann_dataset.rows;
dimsf[1] = flann_dataset.cols;
DataSpace dataspace( 2, dimsf );
dimsf[0] = dataset.rows;
dimsf[1] = dataset.cols;
/*
* Create a new dataset within the file using defined dataspace and
* datatype and default dataset creation properties.
*/
DataSet dataset = file.createDataSet( name, get_hdf5_type<T>(), dataspace );
hid_t space_id = H5Screate_simple(2, dimsf, NULL);
hid_t memspace_id = H5Screate_simple(2, dimsf, NULL);
/*
* Write the data to the dataset using default memory space, file
* space, and transfer properties.
*/
dataset.write( flann_dataset.data, get_hdf5_type<T>() );
} // end of try block
catch( H5::Exception& error )
{
error.printError();
throw FLANNException(error.getDetailMsg());
hid_t dataset_id;
#if H5Dcreate_vers == 2
dataset_id = H5Dcreate2(file_id, name.c_str(), get_hdf5_type<T>(), space_id, H5P_DEFAULT, H5P_DEFAULT, H5P_DEFAULT);
#else
dataset_id = H5Dcreate(file_id, name.c_str(), get_hdf5_type<T>(), space_id, H5P_DEFAULT);
#endif
if (dataset_id<0) {
#if H5Dopen_vers == 2
dataset_id = H5Dopen2(file_id, name.c_str(), H5P_DEFAULT);
#else
dataset_id = H5Dopen(file_id, name.c_str());
#endif
}
CHECK_ERROR(dataset_id,"Error creating or opening dataset in file.");
status = H5Dwrite(dataset_id, get_hdf5_type<T>(), memspace_id, space_id, H5P_DEFAULT, dataset.data );
CHECK_ERROR(status, "Error writing to dataset");
H5Sclose(memspace_id);
H5Sclose(space_id);
H5Dclose(dataset_id);
H5Fclose(file_id);
}
template<typename T>
void load_from_file(cvflann::Matrix<T>& flann_dataset, const std::string& filename, const std::string& name)
void load_from_file(cvflann::Matrix<T>& dataset, const std::string& filename, const std::string& name)
{
try
{
Exception::dontPrint();
herr_t status;
hid_t file_id = H5Fopen(filename.c_str(), H5F_ACC_RDWR, H5P_DEFAULT);
CHECK_ERROR(file_id,"Error opening hdf5 file.");
hid_t dataset_id;
#if H5Dopen_vers == 2
dataset_id = H5Dopen2(file_id, name.c_str(), H5P_DEFAULT);
#else
dataset_id = H5Dopen(file_id, name.c_str());
#endif
CHECK_ERROR(dataset_id,"Error opening dataset in file.");
H5File file( filename, H5F_ACC_RDONLY );
DataSet dataset = file.openDataSet( name );
hid_t space_id = H5Dget_space(dataset_id);
/*
* Check the type used by the dataset matches
*/
if ( !(dataset.getDataType()==get_hdf5_type<T>())) {
throw FLANNException("Dataset matrix type does not match the type to be read.");
}
hsize_t dims_out[2];
H5Sget_simple_extent_dims(space_id, dims_out, NULL);
/*
* Get dataspace of the dataset.
*/
DataSpace dataspace = dataset.getSpace();
dataset = cvflann::Matrix<T>(new T[dims_out[0]*dims_out[1]], dims_out[0], dims_out[1]);
/*
* Get the dimension size of each dimension in the dataspace and
* display them.
*/
hsize_t dims_out[2];
dataspace.getSimpleExtentDims( dims_out, NULL);
flann_dataset.rows = dims_out[0];
flann_dataset.cols = dims_out[1];
flann_dataset.data = new T[flann_dataset.rows*flann_dataset.cols];
dataset.read( flann_dataset.data, get_hdf5_type<T>() );
} // end of try block
catch( H5::Exception &error )
{
error.printError();
throw FLANNException(error.getDetailMsg());
}
status = H5Dread(dataset_id, get_hdf5_type<T>(), H5S_ALL, H5S_ALL, H5P_DEFAULT, dataset[0]);
CHECK_ERROR(status, "Error reading dataset");
H5Sclose(space_id);
H5Dclose(dataset_id);
H5Fclose(file_id);
}
} // namespace cvflann
#ifdef HAVE_MPI
namespace mpi
{
/**
* Loads a the hyperslice corresponding to this processor from a hdf5 file.
* @param flann_dataset Dataset where the data is loaded
* @param filename HDF5 file name
* @param name Name of dataset inside file
*/
template<typename T>
void load_from_file(cvflann::Matrix<T>& dataset, const std::string& filename, const std::string& name)
{
MPI_Comm comm = MPI_COMM_WORLD;
MPI_Info info = MPI_INFO_NULL;
int mpi_size, mpi_rank;
MPI_Comm_size(comm, &mpi_size);
MPI_Comm_rank(comm, &mpi_rank);
herr_t status;
hid_t plist_id = H5Pcreate(H5P_FILE_ACCESS);
H5Pset_fapl_mpio(plist_id, comm, info);
hid_t file_id = H5Fopen(filename.c_str(), H5F_ACC_RDWR, plist_id);
CHECK_ERROR(file_id,"Error opening hdf5 file.");
H5Pclose(plist_id);
hid_t dataset_id;
#if H5Dopen_vers == 2
dataset_id = H5Dopen2(file_id, name.c_str(), H5P_DEFAULT);
#else
dataset_id = H5Dopen(file_id, name.c_str());
#endif
CHECK_ERROR(dataset_id,"Error opening dataset in file.");
hid_t space_id = H5Dget_space(dataset_id);
hsize_t dims[2];
H5Sget_simple_extent_dims(space_id, dims, NULL);
hsize_t count[2];
hsize_t offset[2];
hsize_t item_cnt = dims[0]/mpi_size+(dims[0]%mpi_size==0 ? 0 : 1);
hsize_t cnt = (mpi_rank<mpi_size-1 ? item_cnt : dims[0]-item_cnt*(mpi_size-1));
count[0] = cnt;
count[1] = dims[1];
offset[0] = mpi_rank*item_cnt;
offset[1] = 0;
hid_t memspace_id = H5Screate_simple(2,count,NULL);
H5Sselect_hyperslab(space_id, H5S_SELECT_SET, offset, NULL, count, NULL);
dataset.rows = count[0];
dataset.cols = count[1];
dataset.data = new T[dataset.rows*dataset.cols];
plist_id = H5Pcreate(H5P_DATASET_XFER);
H5Pset_dxpl_mpio(plist_id, H5FD_MPIO_COLLECTIVE);
status = H5Dread(dataset_id, get_hdf5_type<T>(), memspace_id, space_id, plist_id, dataset.data);
CHECK_ERROR(status, "Error reading dataset");
H5Pclose(plist_id);
H5Sclose(space_id);
H5Sclose(memspace_id);
H5Dclose(dataset_id);
H5Fclose(file_id);
}
}
#endif // HAVE_MPI
} // namespace cvflann::mpi
#endif /* _OPENCV_HDF5_H_ */
#endif /* OPENCV_FLANN_HDF5_H_ */
......@@ -28,11 +28,11 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_HEAP_H_
#define _OPENCV_HEAP_H_
#ifndef OPENCV_FLANN_HEAP_H_
#define OPENCV_FLANN_HEAP_H_
#include <algorithm>
#include <vector>
namespace cvflann
{
......@@ -43,17 +43,16 @@ namespace cvflann
* The priority queue is implemented with a heap. A heap is a complete
* (full) binary tree in which each parent is less than both of its
* children, but the order of the children is unspecified.
* Note that a heap uses 1-based indexing to allow for power-of-2
* location of parents and children. We ignore element 0 of Heap array.
*/
template <typename T>
class Heap {
class Heap
{
/**
* Storage array for the heap.
* Type T must be comparable.
*/
T* heap;
std::vector<T> heap;
int length;
/**
......@@ -73,21 +72,11 @@ public:
Heap(int size)
{
length = size+1;
heap = new T[length]; // heap uses 1-based indexing
length = size;
heap.reserve(length);
count = 0;
}
/**
* Destructor.
*
*/
~Heap()
{
delete[] heap;
}
/**
*
* Returns: heap size
......@@ -112,9 +101,17 @@ public:
*/
void clear()
{
heap.clear();
count = 0;
}
struct CompareT
{
bool operator()(const T& t_1, const T& t_2) const
{
return t_2 < t_1;
}
};
/**
* Insert a new element in the heap.
......@@ -128,21 +125,14 @@ public:
void insert(T value)
{
/* If heap is full, then return without adding this element. */
if (count == length-1) {
if (count == length) {
return;
}
int loc = ++(count); /* Remember 1-based indexing. */
/* Keep moving parents down until a place is found for this node. */
int par = loc / 2; /* Location of parent. */
while (par > 0 && value < heap[par]) {
heap[loc] = heap[par]; /* Move parent down to loc. */
loc = par;
par = loc / 2;
}
/* Insert the element at the determined location. */
heap[loc] = value;
heap.push_back(value);
static CompareT compareT;
std::push_heap(heap.begin(), heap.end(), compareT);
++count;
}
......@@ -160,49 +150,16 @@ public:
return false;
}
/* Switch first node with last. */
std::swap(heap[1],heap[count]);
count -= 1;
heapify(1); /* Move new node 1 to right position. */
value = heap[0];
static CompareT compareT;
std::pop_heap(heap.begin(), heap.end(), compareT);
heap.pop_back();
--count;
value = heap[count + 1];
return true; /* Return old last node. */
}
/**
* Reorganizes the heap (a parent is smaller than its children)
* starting with a node.
*
* Params:
* parent = node form which to start heap reorganization.
*/
void heapify(int parent)
{
int minloc = parent;
/* Check the left child */
int left = 2 * parent;
if (left <= count && heap[left] < heap[parent]) {
minloc = left;
}
/* Check the right child */
int right = left + 1;
if (right <= count && heap[right] < heap[minloc]) {
minloc = right;
}
/* If a child was smaller, than swap parent with it and Heapify. */
if (minloc != parent) {
std::swap(heap[parent],heap[minloc]);
heapify(minloc);
}
}
};
} // namespace cvflann
}
#endif //_OPENCV_HEAP_H_
#endif //OPENCV_FLANN_HEAP_H_
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -28,8 +28,8 @@
* THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*************************************************************************/
#ifndef _OPENCV_TIMER_H_
#define _OPENCV_TIMER_H_
#ifndef FLANN_TIMER_H
#define FLANN_TIMER_H
#include <time.h>
......@@ -42,7 +42,7 @@ namespace cvflann
*
* Can be used to time portions of code.
*/
class CV_EXPORTS StartStopTimer
class StartStopTimer
{
clock_t startTime;
......@@ -64,14 +64,16 @@ public:
/**
* Starts the timer.
*/
void start() {
void start()
{
startTime = clock();
}
/**
* Stops the timer and updates timer value.
*/
void stop() {
void stop()
{
clock_t stopTime = clock();
value += ( (double)stopTime - startTime) / CLOCKS_PER_SEC;
}
......@@ -79,12 +81,13 @@ public:
/**
* Resets the timer value to 0.
*/
void reset() {
void reset()
{
value = 0;
}
};
}// namespace cvflann
}
#endif // _OPENCV_TIMER_H_
#endif // FLANN_TIMER_H
This diff is collapsed.
This diff is collapsed.
......@@ -5,10 +5,13 @@
#include <cstdarg>
#include <sstream>
#include "opencv2/flann/miniflann.hpp"
#include "opencv2/flann/dist.h"
#include "opencv2/flann/index_testing.h"
#include "opencv2/flann/params.h"
#include "opencv2/flann/saving.h"
#include "opencv2/flann/general.h"
#include "opencv2/flann/dummy.h"
// index types
#include "opencv2/flann/all_indices.h"
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -3,6 +3,7 @@ import os, sys, re, string
# the list only for debugging. The real list, used in the real OpenCV build, is specified in CMakeLists.txt
opencv_hdr_list = [
"../../core/include/opencv2/core/core.hpp",
"../../flann/include/opencv2/flann/miniflann.hpp",
"../../ml/include/opencv2/ml/ml.hpp",
"../../imgproc/include/opencv2/imgproc/imgproc.hpp",
"../../calib3d/include/opencv2/calib3d/calib3d.hpp",
......
......@@ -10,7 +10,7 @@ using namespace std;
void help()
{
cout <<
"\nThis program demonstrates dense, Farnback, optical flow\n"
"\nThis program demonstrates dense optical flow algorithm by Gunnar Farneback\n"
"Mainly the function: calcOpticalFlowFarneback()\n"
"Call:\n"
"./fback\n"
......
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment