Go to the documentation of this file.
31 #ifndef RTABMAP_FLANN_DIST_H_
32 #define RTABMAP_FLANN_DIST_H_
51 struct Accumulator {
typedef T Type; };
53 struct Accumulator<unsigned char> {
typedef float Type; };
55 struct Accumulator<unsigned short> {
typedef float Type; };
57 struct Accumulator<unsigned
int> {
typedef float Type; };
59 struct Accumulator<char> {
typedef float Type; };
61 struct Accumulator<short> {
typedef float Type; };
63 struct Accumulator<
int> {
typedef float Type; };
81 template <
typename Iterator1,
typename Iterator2>
86 for(
size_t i = 0;
i <
size; ++
i ) {
93 template <
typename U,
typename V>
108 template <
typename Iterator1,
typename Iterator2>
122 template <
typename U,
typename V>
149 template <
typename Iterator1,
typename Iterator2>
155 Iterator1 lastgroup =
last - 3;
158 while (
a < lastgroup) {
163 result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3;
167 if ((worst_dist>0)&&(
result>worst_dist)) {
185 template <
typename U,
typename V>
210 template <
typename Iterator1,
typename Iterator2>
216 Iterator1 lastgroup =
last - 3;
219 while (a < lastgroup) {
224 result += diff0 + diff1 + diff2 + diff3;
228 if ((worst_dist>0)&&(
result>worst_dist)) {
243 template <
typename U,
typename V>
253 struct MinkowskiDistance
273 template <
typename Iterator1,
typename Iterator2>
279 Iterator1 lastgroup =
last - 3;
282 while (a < lastgroup) {
291 if ((worst_dist>0)&&(result>worst_dist)) {
306 template <
typename U,
typename V>
328 template <
typename Iterator1,
typename Iterator2>
334 Iterator1 lastgroup =
last - 3;
337 while (a < lastgroup) {
345 if (diff3>result) {
result = diff3; }
349 if ((worst_dist>0)&&(result>worst_dist)) {
382 for (
int i = 0;
i <
size;
i++) {
396 static const unsigned char table[256] = {
476 template<
typename Iterator1,
typename Iterator2>
482 typedef unsigned long long pop_t;
485 #if ANDROID && HAVE_NEON
486 static uint64_t features = android_getCpuFeatures();
487 if ((features& ANDROID_CPU_ARM_FEATURE_NEON)) {
488 for (
size_t i = 0;
i <
size;
i += 16) {
489 uint8x16_t A_vec = vld1q_u8 (
a +
i);
490 uint8x16_t B_vec = vld1q_u8 (
b +
i);
492 uint8x16_t AxorB = veorq_u8 (A_vec, B_vec);
494 uint8x16_t bitsSet += vcntq_u8 (AxorB);
496 uint16x8_t bitSet8 = vpaddlq_u8 (bitsSet);
497 uint32x4_t bitSet4 = vpaddlq_u16 (bitSet8);
499 uint64x2_t bitSet2 = vpaddlq_u32 (bitSet4);
500 result += vgetq_lane_u64 (bitSet2,0);
507 typedef unsigned long long pop_t;
508 const size_t modulo =
size %
sizeof(pop_t);
509 const pop_t*
a2 =
reinterpret_cast<const pop_t*
> (
a);
510 const pop_t*
b2 =
reinterpret_cast<const pop_t*
> (
b);
511 const pop_t* a2_end =
a2 + (
size /
sizeof(pop_t));
513 for (;
a2 != a2_end; ++
a2, ++
b2) result += __builtin_popcountll((*a2) ^ (*b2));
518 pop_t a_final = 0, b_final = 0;
519 memcpy(&a_final, a2, modulo);
520 memcpy(&b_final, b2, modulo);
521 result += __builtin_popcountll(a_final ^ b_final);
525 result = lut(
reinterpret_cast<const unsigned char*
> (a),
526 reinterpret_cast<const unsigned char*
> (b), size *
sizeof(pop_t));
542 n -= ((
n >> 1) & 0x55555555);
543 n = (
n & 0x33333333) + ((n >> 2) & 0x33333333);
544 return (((n + (n >> 4))& 0xF0F0F0F)* 0x1010101) >> 24;
549 n -= ((
n >> 1) & 0x5555555555555555LL);
550 n = (
n & 0x3333333333333333LL) + ((n >> 2) & 0x3333333333333333LL);
551 return (((n + (n >> 4))& 0x0f0f0f0f0f0f0f0fLL)* 0x0101010101010101LL) >> 56;
554 template <
typename Iterator1,
typename Iterator2>
557 #ifdef FLANN_PLATFORM_64_BIT
562 for(
size_t i = 0;
i <
size; ++
i ) {
572 for(
size_t i = 0;
i <
size; ++
i ) {
597 template <
typename Iterator1,
typename Iterator2>
603 Iterator1 lastgroup =
last - 3;
606 while (
a < lastgroup) {
614 if ((worst_dist>0)&&(
result>worst_dist)) {
631 template <
typename U,
typename V>
641 struct HellingerDistance
651 template <
typename Iterator1,
typename Iterator2>
657 Iterator1 lastgroup =
last - 3;
660 while (a < lastgroup) {
665 result += diff0 * diff0 + diff1 * diff1 + diff2 * diff2 + diff3 * diff3;
679 template <
typename U,
typename V>
689 struct ChiSquareDistance
699 template <
typename Iterator1,
typename Iterator2>
715 if ((worst_dist>0)&&(
result>worst_dist)) {
725 template <
typename U,
typename V>
752 template <
typename Iterator1,
typename Iterator2>
759 if ( *
a != 0 && *
b != 0 ) {
768 if ((worst_dist>0)&&(
result>worst_dist)) {
778 template <
typename U,
typename V>
782 if( a != 0 && b != 0 ) {
794 #endif //FLANN_DIST_H_
Accumulator< T >::Type ResultType
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
ResultType accum_dist(const U &a, const V &b, int) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
Accumulator< T >::Type ResultType
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType=-1) const
bool is_vector_space_distance
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType=-1) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
unsigned char ElementType
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType=-1) const
ResultType accum_dist(const U &a, const V &b, int) const
ResultType accum_dist(const U &a, const V &b, int) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType=0) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
static const symbolic::SymbolExpr< internal::symbolic_last_tag > last
Accumulator< T >::Type ResultType
static unsigned char byteBitsLookUp(unsigned char b)
given a byte, count the bits using a look up table
GLM_FUNC_DECL genType pow(genType const &base, genType const &exponent)
Accumulator< T >::Type ResultType
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
GLM_FUNC_DECL vecType< T, P > sqrt(vecType< T, P > const &x)
ResultType accum_dist(const U &a, const V &b, int) const
ResultType accum_dist(const U &a, const V &b, int) const
unsigned int popcnt32(uint32_t n) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
Accumulator< T >::Type ResultType
Accumulator< T >::Type ResultType
GLM_FUNC_DECL genType log(genType const &x)
unsigned int popcnt64(uint64_t n) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType worst_dist=-1) const
ResultType operator()(Iterator1 a, Iterator2 b, size_t size, ResultType=-1) const
GLM_FUNC_DECL genType abs(genType const &x)
ResultType accum_dist(const U &a, const V &b, int) const
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size ratio
ResultType accum_dist(const U &a, const V &b, int) const
Accumulator< T >::Type ResultType
ResultType operator()(const unsigned char *a, const unsigned char *b, int size) const
MinkowskiDistance(int order_)
Accumulator< T >::Type ResultType
Accumulator< T >::Type ResultType
ResultType accum_dist(const U &a, const V &b, int) const
ResultType accum_dist(const U &a, const V &b, int) const
Accumulator< T >::Type ResultType
double min3(const double &a, const double &b, const double &c)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:09