Skip to content
Snippets Groups Projects
Commit 32b57692 authored by Dario Lodi Rizzini's avatar Dario Lodi Rizzini
Browse files

added project files (headers, sources, CMake, etc.)

parent 168a8526
No related branches found
No related tags found
No related merge requests found
Showing
with 4377 additions and 0 deletions
cmake_minimum_required(VERSION 2.8)
project(falkolib)
set(CMAKE_BUILD_TYPE Release)
add_definitions(-std=c++0x) # Enabling c++11
SET(falkolib_RUNTIME_OUTPUT_DIRECTORY ${falkolib_SOURCE_DIR}/bin CACHE PATH "Target for the binaries")
SET(falkolib_LIBRARY_OUTPUT_DIRECTORY ${falkolib_SOURCE_DIR}/lib CACHE PATH "Target for the libraries")
SET(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${falkolib_LIBRARY_OUTPUT_DIRECTORY})
SET(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${falkolib_LIBRARY_OUTPUT_DIRECTORY})
SET(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${falkolib_RUNTIME_OUTPUT_DIRECTORY})
LIST(APPEND CMAKE_MODULE_PATH ${falkolib_SOURCE_DIR}/cmake_modules)
message(STATUS "CMAKE_MODULE_PATH: ${CMAKE_MODULE_PATH}")
find_package(Boost)
if (${Boost_FOUND})
message(STATUS "Boost_INCLUDE_DIRS: ${Boost_INCLUDE_DIRS}")
message(STATUS "Boost_LIBRARY_DIRS: ${Boost_LIBRARY_DIRS}")
message(STATUS "Boost_LIBRARIES: ${Boost_LIBRARY_DIRS}")
include_directories(${Boost_INCLUDE_DIRS})
link_directories(${Boost_LIBRARY_DIRS})
endif(${Boost_FOUND})
find_package(Eigen3 REQUIRED)
if (${EIGEN3_FOUND})
include_directories(${EIGEN3_INCLUDE_DIR})
message(STATUS "EIGEN3_INCLUDE_DIR: ${EIGEN3_INCLUDE_DIR}")
else(${EIGEN3_FOUND})
message(WARNING "Cannot find Eigen3 Library")
endif(${EIGEN3_FOUND})
message(STATUS "include dir: ${falkolib_SOURCE_DIR}/include")
message(STATUS "include dir: ${falkolib_SOURCE_DIR}/EXTERNAL")
include_directories(${falkolib_SOURCE_DIR}/include ${falkolib_SOURCE_DIR}/EXTERNAL)
add_library(falkolib
src/Common/HoughSpectrum.cpp
src/Feature/FALKOExtractor.cpp
src/Feature/OCExtractor.cpp
src/Feature/CGH.cpp
src/Feature/BSC.cpp
)
add_executable(testKeypointFalko test/testKeypointFalko.cpp test/testData.cpp)
target_link_libraries(testKeypointFalko falkolib ${Boost_LIBRARIES})
add_executable(testFalkoAHT test/testFalkoAHT.cpp test/testData.cpp)
target_link_libraries(testFalkoAHT falkolib ${Boost_LIBRARIES})
add_executable(testFalkoCC test/testFalkoCC.cpp test/testData.cpp)
target_link_libraries(testFalkoCC falkolib ${Boost_LIBRARIES})
add_executable(testKeypointOC test/testKeypointOC.cpp test/testData.cpp)
target_link_libraries(testKeypointOC falkolib ${Boost_LIBRARIES}) # boost_iostreams boost_system boost_filesystem
# Option "make install": copy binaries
INSTALL(TARGETS falkolib
RUNTIME DESTINATION ${CMAKE_INSTALL_PREFIX}/bin
LIBRARY DESTINATION ${CMAKE_INSTALL_PREFIX}/lib
ARCHIVE DESTINATION ${CMAKE_INSTALL_PREFIX}/lib
)
# Option "make install": copy headers
FILE(GLOB headers_Common "${CMAKE_CURRENT_SOURCE_DIR}/include/falkolib/Common/*.h")
FILE(GLOB headers_Feature "${CMAKE_CURRENT_SOURCE_DIR}/include/falkolib/Feature/*.h")
FILE(GLOB headers_Matching "${CMAKE_CURRENT_SOURCE_DIR}/include/falkolib/Matching/*.h")
INSTALL(FILES ${headers_Common} DESTINATION ${CMAKE_INSTALL_PREFIX}/include/falkolib/Common)
INSTALL(FILES ${headers_Feature} DESTINATION ${CMAKE_INSTALL_PREFIX}/include/falkolib/Feature)
INSTALL(FILES ${headers_Matching} DESTINATION ${CMAKE_INSTALL_PREFIX}/include/falkolib/Matching)
# Option "make install": copy cmake script
FILE(GLOB cmake_script "${CMAKE_CURRENT_SOURCE_DIR}/cmake_modules/falkolibConfig.cmake")
message(STATUS "cmake_script " ${cmake_script})
INSTALL(FILES ${cmake_script} DESTINATION ${CMAKE_INSTALL_PREFIX}/share/falkolib/)
File moved
This diff is collapsed.
This diff is collapsed.
Compile with: g++ -O3 mcqd.cpp -o mcqd
Run with: mcqd test.clq
mcqd.cpp ... example program that shows how to use class implemented in mcqd.h
mcqd.h ... a class that contains two variants of the MCQD maximum clique algorithm
test.clq ... an example clique in DIMACS format
/*
Copyright 2007-2012 Janez Konc
If you use this program, please cite:
Janez Konc and Dusanka Janezic. An improved branch and bound algorithm for the
maximum clique problem. MATCH Commun. Math. Comput. Chem., 2007, 58, 569-590.
More information at: http://www.sicmm.org/~konc
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <fstream>
#include <iostream>
#include <set>
#include <string.h>
#include <map>
#include <assert.h>
#include <emotion/3rdparty/mcqd.h>
using namespace std;
void read_dimacs(string name, bool** &conn, int &size) {
ifstream f (name.c_str());
string buffer;
assert(f.is_open());
set<int> v;
multimap<int,int> e;
while (!getline(f, buffer).eof()) {
if (buffer[0] == 'e') {
int vi, vj;
sscanf(buffer.c_str(), "%*c %d %d", &vi, &vj);
v.insert(vi);
v.insert(vj);
e.insert(make_pair(vi, vj));
}
}
// size = v.size() + 1;
size = *v.rbegin() + 1;
conn = new bool*[size];
for (int i=0; i < size; i++) {
conn[i] = new bool[size];
memset(conn[i], 0, size * sizeof(bool));
}
for (multimap<int,int>::iterator it = e.begin(); it != e.end(); it++) {
conn[it->first][it->second] = true;
conn[it->second][it->first] = true;
}
cout << "|E| = " << e.size() << " |V| = " << v.size() << " p = " << (double) e.size() / (v.size() * (v.size() - 1) / 2) << endl;
f.close();
}
int main(int argc, char *argv[]) {
assert(argc == 2);
cout << "args = " << argv[1] << endl;
bool **conn;
int size;
read_dimacs(argv[1], conn, size);
cout << "---------- Example 1: run max clique with improved coloring ----------------"<<endl;
clock_t start1 = time(NULL);
clock_t start2 = clock();
Maxclique m(conn, size);
int *qmax;
int qsize;
m.mcq(qmax, qsize); // run max clique with improved coloring
cout << "Maximum clique: ";
for (int i = 0; i < qsize; i++)
cout << qmax[i] << " ";
cout << endl;
cout << "Size = " << qsize << endl;
cout << "Number of steps = " << m.steps() << endl;
cout << "Time = " << difftime(time(NULL), start1) << endl;
cout << "Time (precise) = " << ((double) (clock() - start2)) / CLOCKS_PER_SEC << endl << endl;
delete [] qmax;
cout << "---------- Example 2: run max clique with improved coloring and dynamic sorting of vertices ----------------"<<endl;
start1 = time(NULL);
start2 = clock();
Maxclique md(conn, size, 0.025); //(3rd parameter is optional - default is 0.025 - this heuristics parameter enables you to use dynamic resorting of vertices (time expensive)
// on the part of the search tree that is close to the root - in this case, approximately 2.5% of the search tree -
// you can probably find a more optimal value for your graphs
md.mcqdyn(qmax, qsize); // run max clique with improved coloring and dynamic sorting of vertices
cout << "Maximum clique: ";
for (int i = 0; i < qsize; i++)
cout << qmax[i] << " ";
cout << endl;
cout << "Size = " << qsize << endl;
cout << "Number of steps = " << md.steps() << endl;
cout << "Time = " << difftime(time(NULL), start1) << endl;
cout << "Time (precise) = " << ((double) (clock() - start2)) / CLOCKS_PER_SEC << endl << endl;
delete [] qmax;
for (int i=0;i<size;i++)
delete [] conn[i];
delete [] conn;
return 0;
}
/*
Copyright 2007-2012 Janez Konc
If you use this program, please cite:
Janez Konc and Dusanka Janezic. An improved branch and bound algorithm for the
maximum clique problem. MATCH Commun. Math. Comput. Chem., 2007, 58, 569-590.
More information at: http://www.sicmm.org/~konc
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#ifndef MCQD
#define MCQD
#include <iostream>
#include <algorithm>
#include <assert.h>
#ifdef DBG
using namespace std;
#endif
class Maxclique {
const bool* const* e;
int pk, level;
const float Tlimit;
class Vertices {
class Vertex {
int i, d;
public:
void set_i(const int ii) { i = ii; }
int get_i() const { return i; }
void set_degree(int dd) { d = dd; }
int get_degree() const { return d; }
};
Vertex *v;
int sz;
static bool desc_degree(const Vertex vi, const Vertex vj) { return (vi.get_degree() > vj.get_degree()); }
public:
#ifdef DBG
void dbg_v(const string msg="") const {
std::cout << msg << " Vertices: [";
for (int i=0; i < sz; i++)
std::cout << "(" << v[i].get_i() << "," << v[i].get_degree() << ") ";
std::cout << "]" << std::endl;
}
#endif
Vertices(int size) : sz(0) { v = new Vertex[size]; }
~Vertices () {}
void dispose() { if (v) delete [] v; }
void sort() { std::sort(v, v+sz, desc_degree); }
void init_colors();
void set_degrees(Maxclique&);
int size() const { return sz; }
void push(const int ii) { v[sz++].set_i(ii); };
void pop() { sz--; };
Vertex& at(const int ii) const { return v[ii]; };
Vertex& end() const { return v[sz - 1]; };
};
class ColorClass {
int *i;
int sz;
public:
#ifdef DBG
void dbg_i(const string msg="") const {
std::cout << msg << " Class: [";
for (int ii=0; ii < sz; ii++)
std::cout << i[ii] << " ";
std::cout << "]" << std::endl;
}
#endif
ColorClass() : sz(0), i(0) {}
ColorClass(const int sz) : sz(sz), i(0) { init(sz); }
~ColorClass() { if (i) delete [] i;
}
void init(const int sz) { i = new int[sz]; rewind(); }
void push(const int ii) { i[sz++] = ii; };
void pop() { sz--; };
void rewind() { sz = 0; };
int size() const { return sz; }
int& at(const int ii) const { return i[ii]; }
ColorClass& operator=(const ColorClass& dh) {
for (int j = 0; j < dh.sz; j++) i[j] = dh.i[j];
sz = dh.sz;
return *this;
}
};
Vertices V;
ColorClass *C, QMAX, Q;
class StepCount {
int i1, i2;
public:
StepCount() : i1(0), i2(0) {}
void set_i1(const int ii) { i1 = ii; }
int get_i1() const { return i1; }
void set_i2(const int ii) { i2 = ii; }
int get_i2() const { return i2; }
void inc_i1() { i1++; }
};
StepCount *S;
bool connection(const int i, const int j) const { return e[i][j]; }
bool cut1(const int, const ColorClass&);
void cut2(const Vertices&, Vertices&);
void color_sort(Vertices&);
void expand(Vertices);
void expand_dyn(Vertices);
void _mcq(int*&, int&, bool);
void degree_sort(Vertices &R) { R.set_degrees(*this); R.sort(); }
public:
#ifdef DBG
void dbg_C() const {
for (int i=0; i < V.size(); i++) {
std::cout << "C["<< i << "] : ";
C[i].dbg_i();
}
}
void dbg_conn() const {
for (int i=0; i < V.size(); i++) {
for (int j=0; j < V.size(); j++) {
std::cout <<e[i][j];
}
std::cout<< std::endl;
}
}
#endif
Maxclique(const bool* const*, const int, const float=0.025);
int steps() const { return pk; }
void mcq(int* &maxclique, int &sz) { _mcq(maxclique, sz, false); }
void mcqdyn(int* &maxclique, int &sz) { _mcq(maxclique, sz, true); }
~Maxclique() {
if (C) delete [] C;
if (S) delete [] S;
V.dispose();
};
};
Maxclique::Maxclique (const bool* const* conn, const int sz, const float tt) : pk(0), level(1), Tlimit(tt), V(sz), Q(sz), QMAX(sz) {
assert(conn!=0 && sz>0);
for (int i=0; i < sz; i++) V.push(i);
e = conn;
C = new ColorClass[sz + 1];
for (int i=0; i < sz + 1; i++) C[i].init(sz + 1);
S = new StepCount[sz + 1];
}
void Maxclique::_mcq(int* &maxclique, int &sz, bool dyn) {
V.set_degrees(*this);
V.sort();
V.init_colors();
if (dyn) {
for (int i=0; i < V.size() + 1; i++) {
S[i].set_i1(0);
S[i].set_i2(0);
}
expand_dyn(V);
}
else
expand(V);
maxclique = new int[QMAX.size()];
for (int i=0; i<QMAX.size(); i++) {
maxclique[i] = QMAX.at(i);
}
sz = QMAX.size();
}
void Maxclique::Vertices::init_colors() {
const int max_degree = v[0].get_degree();
for (int i = 0; i < max_degree; i++)
v[i].set_degree(i + 1);
for (int i = max_degree; i < sz; i++)
v[i].set_degree(max_degree + 1);
}
void Maxclique::Vertices::set_degrees(Maxclique &m) {
for (int i=0; i < sz; i++) {
int d = 0;
for (int j=0; j < sz; j++)
if (m.connection(v[i].get_i(), v[j].get_i())) d++;
v[i].set_degree(d);
}
}
bool Maxclique::cut1(const int pi, const ColorClass &A) {
for (int i = 0; i < A.size(); i++)
if (connection(pi, A.at(i)))
return true;
return false;
}
void Maxclique::cut2(const Vertices &A, Vertices &B) {
for (int i = 0; i < A.size() - 1; i++) {
if (connection(A.end().get_i(), A.at(i).get_i()))
B.push(A.at(i).get_i());
}
}
void Maxclique::color_sort(Vertices &R) {
int j = 0;
int maxno = 1;
int min_k = QMAX.size() - Q.size() + 1;
C[1].rewind();
C[2].rewind();
int k = 1;
for (int i=0; i < R.size(); i++) {
int pi = R.at(i).get_i();
k = 1;
while (cut1(pi, C[k]))
k++;
if (k > maxno) {
maxno = k;
C[maxno + 1].rewind();
}
C[k].push(pi);
if (k < min_k) {
R.at(j++).set_i(pi);
}
}
if (j > 0) R.at(j-1).set_degree(0);
if (min_k <= 0) min_k = 1;
for (k = min_k; k <= maxno; k++)
for (int i = 0; i < C[k].size(); i++) {
R.at(j).set_i(C[k].at(i));
R.at(j++).set_degree(k);
}
}
void Maxclique::expand(Vertices R) {
while (R.size()) {
if (Q.size() + R.end().get_degree() > QMAX.size()) {
Q.push(R.end().get_i());
Vertices Rp(R.size());
cut2(R, Rp);
if (Rp.size()) {
color_sort(Rp);
pk++;
expand(Rp);
}
else if (Q.size() > QMAX.size()) {
//std::cout << "step = " << pk << " current max. clique size = " << Q.size() << std::endl;
QMAX = Q;
}
Rp.dispose();
Q.pop();
}
else {
return;
}
R.pop();
}
}
void Maxclique::expand_dyn(Vertices R) {
S[level].set_i1(S[level].get_i1() + S[level - 1].get_i1() - S[level].get_i2());
S[level].set_i2(S[level - 1].get_i1());
while (R.size()) {
if (Q.size() + R.end().get_degree() > QMAX.size()) {
Q.push(R.end().get_i());
Vertices Rp(R.size());
cut2(R, Rp);
if (Rp.size()) {
if ((float)S[level].get_i1()/++pk < Tlimit) {
degree_sort(Rp);
}
color_sort(Rp);
S[level].inc_i1();
level++;
expand_dyn(Rp);
level--;
}
else if (Q.size() > QMAX.size()) {
//std::cout << "step = " << pk << " current max. clique size = " << Q.size() << std::endl;
QMAX = Q;
}
Rp.dispose();
Q.pop();
}
else {
return;
}
R.pop();
}
}
#endif
# - Try to find Eigen3 lib
#
# This module supports requiring a minimum version, e.g. you can do
# find_package(Eigen3 3.1.2)
# to require version 3.1.2 or newer of Eigen3.
#
# Once done this will define
#
# EIGEN3_FOUND - system has eigen lib with correct version
# EIGEN3_INCLUDE_DIR - the eigen include directory
# EIGEN3_VERSION - eigen version
# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>
# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr>
# Copyright (c) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>
# Redistribution and use is allowed according to the terms of the 2-clause BSD license.
if(NOT Eigen3_FIND_VERSION)
if(NOT Eigen3_FIND_VERSION_MAJOR)
set(Eigen3_FIND_VERSION_MAJOR 2)
endif(NOT Eigen3_FIND_VERSION_MAJOR)
if(NOT Eigen3_FIND_VERSION_MINOR)
set(Eigen3_FIND_VERSION_MINOR 91)
endif(NOT Eigen3_FIND_VERSION_MINOR)
if(NOT Eigen3_FIND_VERSION_PATCH)
set(Eigen3_FIND_VERSION_PATCH 0)
endif(NOT Eigen3_FIND_VERSION_PATCH)
set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}")
endif(NOT Eigen3_FIND_VERSION)
macro(_eigen3_check_version)
file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header)
string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}")
set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}")
string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}")
set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}")
string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}")
set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}")
set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION})
if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
set(EIGEN3_VERSION_OK FALSE)
else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
set(EIGEN3_VERSION_OK TRUE)
endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})
if(NOT EIGEN3_VERSION_OK)
message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, "
"but at least version ${Eigen3_FIND_VERSION} is required")
endif(NOT EIGEN3_VERSION_OK)
endmacro(_eigen3_check_version)
if (EIGEN3_INCLUDE_DIR)
# in cache already
_eigen3_check_version()
set(EIGEN3_FOUND ${EIGEN3_VERSION_OK})
else (EIGEN3_INCLUDE_DIR)
# specific additional paths for some OS
if (WIN32)
set(EIGEN_ADDITIONAL_SEARCH_PATHS ${EIGEN_ADDITIONAL_SEARCH_PATHS} "C:/Program Files/Eigen/include" "C:/Program Files (x86)/Eigen/include")
endif(WIN32)
find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library
PATHS
${CMAKE_INSTALL_PREFIX}/include
${EIGEN_ADDITIONAL_SEARCH_PATHS}
${KDE4_INCLUDE_DIR}
PATH_SUFFIXES eigen3 eigen
)
if(EIGEN3_INCLUDE_DIR)
_eigen3_check_version()
endif(EIGEN3_INCLUDE_DIR)
include(FindPackageHandleStandardArgs)
find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK)
mark_as_advanced(EIGEN3_INCLUDE_DIR)
endif(EIGEN3_INCLUDE_DIR)
# - Try to find Library falkolib
# Once done, this will define
#
# falkolib_FOUND - system has falkolib module
# falkolib_INCLUDE_DIRS - the falkolib include directories
# falkolib_LIBRARY_DIRS - the falkolib library directories
# falkolib_LIBRARIES - link these to use falkolib
# Uses directory to search mrf_segmentation directory!
set(falkolib_PREFIX_DIR /usr/local)
message(STATUS "Searching falkolib in directory ${falkolib_PREFIX_DIR}." )
# Searches include directory /usr/local/include/falkolib
find_path(falkolib_INCLUDE_DIR falkolib ${falkolib_PREFIX_DIR}/include)
message(STATUS " falkolib_INCLUDE_DIR ${falkolib_INCLUDE_DIR}." )
set(falkolib_INCLUDE_DIRS ${falkolib_INCLUDE_DIR})
# Searches library librimagraph.a in /usr/local/lib
find_path(falkolib_LIBRARY_DIR librimagraph.a ${falkolib_PREFIX_DIR}/lib)
message(STATUS " falkolib_LIBRARY_DIR ${falkolib_LIBRARY_DIR}." )
set(falkolib_LIBRARY_DIRS ${falkolib_PREFIX_DIR}/lib)
# Sets the names of library components (actually A name and A component)
find_library(falkolib_LIBRARY falkolib ${falkolib_LIBRARY_DIRS})
message(STATUS " falkolib_LIBRARY ${falkolib_LIBRARY}." )
set(falkolib_LIBRARIES ${falkolib_LIBRARY})
if(("${falkolib_INCLUDE_DIR}" STREQUAL "falkolib_INCLUDE_DIR-NOTFOUND") OR
("${falkolib_LIBRARY_DIRS}" STREQUAL "falkolib_LIBRARY_DIRS-NOTFOUND") OR
("${falkolib_LIBRARY}" STREQUAL "falkolib_LIBRARY-NOTFOUND")
)
message(STATUS "Library falkolib NOT found")
unset(falkolib_FOUND)
unset(falkolib_INCLUDE_DIR)
unset(falkolib_LIBRARY_DIR)
unset(falkolib_LIBRARY)
unset(falkolib_LIBRARIES)
endif()
mark_as_advanced(falkolib_INCLUDE_DIRS falkolib_LIBRARY_DIRS falkolib_LIBRARIES)
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
/**
* @brief Useful geometric functions
*/
#include <falkolib/Common/Point.h>
#include <Eigen/Dense>
namespace falkolib {
/**
* @brief point-to-point distance
* @param p1 point 1
* @param p2 point 2
* @return distance between p1 and p2F
*/
template <typename T>
double pointsDistance(const T& p1, const T& p2) {
return (p2 - p1).norm();
}
/**
* @brief angle between two given points
* @param p1 point 1
* @param p2 point 2
* @return angle between p1 and p2 [rad]
*/
template <typename T>
double angleBetweenPoints(const T& p1, const T& p2) {
double angle = atan2(p2[1] - p1[1], p2[0] - p1[0]);
//numeric problems..........
if (angle >= M_PI) return M_PI - 0.000001;
if (angle <= -M_PI) return -M_PI + 0.000001;
return angle;
}
/**
* @brief This function computes the inner area of a triangle defined by 3 vertices
* @param p0 triangle first vertex
* @param p1 triangle second vertex
* @param p2 triangle third vertex
* @return signed area of the inner triangle, p0-p1 as base of the triangle
*/
template <typename T>
double signedTriangleArea(const T& p0, const T& p1, const T& p2) {
return ((p2[1] - p1[1]) * p0[0] - (p2[0] - p1[0]) * p0[1] + p2[0] * p1[1] - p2[1] * p1[0]);
}
/**
* @brief Compute Affine transform between two points sets using least square regression
* @param v1 first points set
* @param v2 second points set
* @param indices matching vectors, pair.first corresponds to v1 and pair.second corresponds to v2
* @param transform resulting affine transform which move v2 in v1 frame.
* @return if false, the resulting transform is invalid
*/
template <typename T>
bool computeTransform(const std::vector<T>& v1, const std::vector<T>& v2, const std::vector<std::pair<int, int> >& indices, Eigen::Affine2d& transform) {
Eigen::Vector2d t1 = Eigen::Vector2d::Zero();
Eigen::Vector2d t2 = Eigen::Vector2d::Zero();
Eigen::Matrix2d S = Eigen::Matrix2d::Zero();
int n = 0;
for (int i = 0; i < (int) indices.size(); ++i) {
if (0 <= indices[i].first && indices[i].first < (int) v1.size() &&
0 <= indices[i].second && indices[i].second < (int) v2.size()) {
t1 += v1[indices[i].first].point;
t2 += v2[indices[i].second].point;
n++;
}
}
if (n == 0) {
return false;
}
t1 = (1.0 / n) * t1;
t2 = (1.0 / n) * t2;
for (int i = 0; i < (int) indices.size(); ++i) {
if (0 <= indices[i].first && indices[i].first < (int) v1.size() &&
0 <= indices[i].second && indices[i].second < (int) v2.size()) {
S += (v2[indices[i].second].point - t2) * ((v1[indices[i].first].point - t1).transpose());
}
}
double theta = std::atan2(S(0, 1) - S(1, 0), S(0, 0) + S(1, 1));
Eigen::Rotation2Dd rot(theta);
Eigen::Vector2d transl = t1 - (rot * t2);
transform = Eigen::Affine2d::Identity();
transform.prerotate(rot);
transform.pretranslate(transl);
return true;
}
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <iostream>
#include <Eigen/Dense>
namespace falkolib {
/** Hough transform and spectrum.
*/
class HoughSpectrum {
public:
/** Constructor with deafult parameters.
*/
HoughSpectrum();
/** Constructor with the number of theta.
*/
HoughSpectrum(double thetaStep, double rhoStep, double rhoMax);
/** Inits params.
*/
void init(double thetaStep, double rhoStep, double rhoMax);
/** Inserts the points and computes Hough Transform and Spectrum.
*/
template <typename It>
void insertPoint(It pbeg, It pend);
/** Returns the Hough Transform.
*/
const Eigen::MatrixXd& hough() const {
return hough_;
}
/** Returns the value of Hough Transform for a specific value of theta and rho.
* If the theta and rho are not in the domain, then it return 0.0.
*/
double hough(double theta, double rho) const {
int ith = thetaToIdx(theta);
int irh = rhoToIdx(theta);
if (0 <= ith && ith < hough_.rows() && 0 <= irh && irh < hough_.cols()) {
return hough_(ith, irh);
}
return 0.0;
}
/** Returns the spectrum.
*/
const Eigen::VectorXd& spectrum() const {
return spectrum_;
}
/** Returns the spectrum.
*/
const double spectrum(double theta) const {
int ith = thetaToIdx(theta);
if (0 <= ith && ith < hough_.rows()) {
return spectrum_(ith);
}
return 0.0;
}
/** Returns the spectrum.
*/
const Eigen::VectorXd& orthoSpectrum() const {
return orthoSpectrum_;
}
private:
int thetaNum_;
int rhoNum_;
double thetaStep_;
double rhoStep_;
// Hough transform and spectra should be integer types.
// However, since their value may be very large, double type is used instead.
Eigen::MatrixXd hough_;
Eigen::VectorXd spectrum_;
Eigen::VectorXd orthoSpectrum_;
Eigen::VectorXd cosLut_;
Eigen::VectorXd sinLut_;
double idxToRho(int idx) const {
return (rhoStep_ * (idx - rhoNum_));
}
int rhoToIdx(double rho) const {
return ((int) round(rho / rhoStep_) + rhoNum_ / 2);
}
int thetaToIdx(double theta) const {
int idx = (int) round(theta / thetaStep_);
int thetaNum2 = 2 * thetaNum_;
idx = ((idx % thetaNum2) + thetaNum2) % thetaNum2;
return idx;
}
};
// -------------------------------------------------------------
// TEMPLATE METHOD
// -------------------------------------------------------------
template <typename It>
void HoughSpectrum::insertPoint(It pbeg, It pend) {
double rho;
int irho;
hough_.fill(0.0);
spectrum_.fill(0.0);
// Computes Hough
for (It pit = pbeg; pit != pend; ++pit) {
for (int i = 0; i < thetaNum_; ++i) {
rho = pit->x() * cosLut_(i) + pit->y() * sinLut_(i);
irho = rhoToIdx(rho);
if (0 <= irho && irho < rhoNum_) {
hough_(i, irho) = hough_(i, irho) + 1;
}
// else {
// std::cerr << "Out-of-bound: rho " << rho << ", theta " << (180.0 / M_PI * thetaStep_ * i) << ", "
// << "point [" << pit->x() << " " << pit->y() << "]\n";
// }
}
}
spectrum_ = (hough_.array() * hough_.array()).rowwise().sum();
orthoSpectrum_ = spectrum_.segment(0, thetaNum_ / 2) + spectrum_.segment(thetaNum_ / 2, thetaNum_ / 2);
}
} // end of namespace
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <vector>
#include <falkolib/Common/Point.h>
#include <falkolib/Common/GeomUtils.h>
namespace falkolib {
/**
* @brief Laser scan container
*
* This class provides an essential interface for laser scan data
*/
class LaserScan {
public:
/**
* @brief Constructor
*/
LaserScan() {
angleMin = 0;
fov = 0;
angleInc = 0;
numBeams = 0;
timestamp = 0;
}
/**
* @brief Constructor
* @param _angleMin laser scanner start angle [rad]
* @param _fov laser scanner field of view [rad]
* @param _numBeams laser scanner number of beams
*/
LaserScan(double _angleMin, double _fov, int _numBeams) {
angleMin = _angleMin;
fov = _fov;
angleInc = _fov / _numBeams;
numBeams = _numBeams;
timestamp = 0;
}
/** @brief Set laser scanner start angle [rad] */
inline void setAngleMin(double _angleMin) {
angleMin = _angleMin;
};
/** @brief Set laser scanner field of view [rad] */
inline void setLaserFoV(double _fov) {
fov = _fov;
};
/** @brief Set laser scanner angle increment [rad] */
inline void setAngleInc(double _angleInc) {
angleInc = _angleInc;
};
/** @brief Set laser scanner number of beams */
inline void setNumBeams(int _numBeams) {
numBeams = _numBeams;
};
/** @brief Set scan beginning timestamp [s] */
inline void setTimestamp(double _timestamp) {
timestamp = _timestamp;
};
/** @brief Get laser scanner number of beams */
inline int getNumBeams() const {
return numBeams;
};
/** @brief Get laser scanner angle increment [rad] */
inline double getAngleInc() const {
return angleInc;
};
/**
* @brief Compute scan points from ranges
*
* @param _ranges plain array of double representing the scan ranges
*/
inline void fromRanges(const double* _ranges) {
fromRanges(std::vector<double>(_ranges, _ranges + numBeams));
}
/**
* @brief Compute scan points from ranges
*
* @param _ranges std::vector of double representing the scan ranges
*/
inline void fromRanges(const std::vector<double>& _ranges) {
double theta;
ranges = _ranges;
points.resize(numBeams);
for (int i = 0; i < numBeams; ++i) {
theta = i * angleInc + angleMin;
points[i][0] = ranges[i] * std::cos(theta);
points[i][1] = ranges[i] * std::sin(theta);
}
}
/**
* @brief compute neighborhood points list given a single point index and a search radius
* @param candIndex index of the central point
* @param radius search euclidean radius [m]
* @param neigh vector of the neighborhood points
* @param midIndex index representing the central point in the neigh vector
*/
void getNeighPoints(int candIndex, double radius, std::vector<Point2d>& neigh, int& midIndex) const {
const Point2d& candPoint = points[candIndex];
int alpha = std::floor(std::asin(radius / ranges[candIndex]) / angleInc);
int begIndex = std::max(0, candIndex - alpha);
int endIndex = std::min(candIndex + alpha + 1, numBeams);
for (int i = begIndex; i <= endIndex; ++i) {
if (pointsDistance(points[i], candPoint) <= radius) {
if (i == candIndex) {
midIndex = neigh.size();
}
neigh.push_back(points[i]);
}
}
}
std::vector<double> ranges;
std::vector<Point2d> points;
private:
double angleMin;
double fov;
double angleInc;
int numBeams;
double timestamp;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <Eigen/Core>
namespace falkolib {
typedef Eigen::Vector2d Point2d;
typedef Eigen::Vector2f Point2f;
typedef Eigen::Vector2i Point2i;
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Feature/Descriptor.h>
#include <falkolib/Common/Point.h>
#include <vector>
namespace falkolib {
/**
* @brief Binary Shape Context descriptor
*
* This class represents a BSC Descriptor.
*/
class BSC : public Descriptor {
public:
/**
* @brief Constructor
* @param _radius descriptor max radius
* @param _circularSectorNumber number of circular sectors
* @param _radialRingNumber number of radial rings
*
* Set the grid dimension and cells resolutions
*/
BSC(double _radius, int _circularSectorNumber, int _radialRingNumber);
/**
* @brief Compute distance between two descriptors
* @param desc descriptor to measure distance
* @return the distance between *this and desc
*
* Compute the distance between two descriptors of the same type (BSC)
*/
double distance(const Descriptor& desc) const;
/**
* @brief Rotate the descriptor grid
* @param theta angle of rotation [rad]
*
* Rotate the descriptor grid of a number of circular sector based on theta
*/
void rotate(double theta);
/**
* @brief Compute the grid descriptor
* @param neigh vector of neighborhood points
* @param centralPointIndex index of the central point in the neigh vector
*/
void compute(std::vector<Point2d>& neigh, int centralPointIndex);
private:
std::vector<std::vector<uint8_t> > grid;
int circularSectorNumber;
int radialRingNumber;
double sectorResolution;
double ringResolution;
double radius;
/** @brief compute the Hamming distance between two binary grid*/
double HammingDistance(const std::vector<std::vector<uint8_t> >& g1, const std::vector<std::vector<uint8_t> >& g2) const;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Common/LaserScan.h>
#include <falkolib/Feature/Keypoint.h>
#include <falkolib/Feature/DescriptorExtractor.h>
#include <falkolib/Feature/BSC.h>
namespace falkolib {
/**
* @brief class representing a BSC descriptor extractor engine
*/
template <typename T>
class BSCExtractor : public DescriptorExtractor<T, BSC> {
public:
/**
* @brief Constructor
* @param _circularSectorNumber number of grid circular sector
* @param _radialRingNumber number of grid radial number
* @param _useKeypointRadius if true, the selected neighborhood points search radius is keypoint one
* @param _radius neighborhood points search radius
*/
BSCExtractor(int _circularSectorNumber, int _radialRingNumber, bool _useKeypointRadius = true, double _radius = 0.1) {
circularSectorNumber = _circularSectorNumber;
radialRingNumber = _radialRingNumber;
useKeypointRadius = _useKeypointRadius;
radius = _radius;
};
/**
* @brief Extract BSC descriptor from a given scan and a list of keypoints
* @param scan input laser scan
* @param keypoints keypoints list
* @param descriptor extracted from scan and keypoints
*/
void compute(const LaserScan& scan, const std::vector<T>& keypoints, std::vector<BSC>& descriptors) {
descriptors.reserve(keypoints.size());
for (int i = 0; i < keypoints.size(); ++i) {
std::vector<Point2d> neigh;
int midIndex;
if (useKeypointRadius) {
scan.getNeighPoints(keypoints[i].index, keypoints[i].radius, neigh, midIndex);
BSC desc(keypoints[i].radius, circularSectorNumber, radialRingNumber);
desc.compute(neigh, midIndex);
descriptors.push_back(std::move(desc));
} else {
scan.getNeighPoints(keypoints[i].index, radius, neigh, midIndex);
BSC desc(radius, circularSectorNumber, radialRingNumber);
desc.compute(neigh, midIndex);
descriptors.push_back(std::move(desc));
}
}
};
private:
int circularSectorNumber;
int radialRingNumber;
bool useKeypointRadius;
double radius;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Feature/Descriptor.h>
#include <falkolib/Common/Point.h>
#include <vector>
namespace falkolib {
/**
* @brief Cumulative Gaussian Histogram descriptor
*
* This class represents a CGH Descriptor.
*/
class CGH : public Descriptor {
public:
/**
* @brief Constructor
* @param _radius descriptor max radius
* @param _circularSectorNumber number of histogram bins
*
* Set the histogram dimension and the circular sectors resolutions
*/
CGH(double _radius, int _circularSectorNumber);
/**
* @brief Compute distance between two descriptors
* @param desc descriptor to measure distance
* @return the distance between *this and desc
*
* Compute the distance between two descriptors of the same type (CGH)
*/
double distance(const Descriptor& desc) const;
/**
* @brief Rotate the descriptor grid
* @param theta angle of rotation [rad]
*
* Rotate the descriptor grid of a number of circular sector based on theta
*/
void rotate(double theta);
/**
* @brief Compute the histogram descriptor
* @param neigh vector of neighborhood points
* @param centralPointIndex index of the central point in the neigh vector
*/
void compute(std::vector<Point2d>& neigh, int centralPointIndex);
private:
std::vector<double> histogram;
int circularSectorNumber;
double sectorResolution;
double radius;
/** @brief compute the Chi-squared distance between two histograms*/
double SymmetricChiSquaredDistance(const std::vector<double>& h1, const std::vector<double>& h2) const;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Common/LaserScan.h>
#include <falkolib/Feature/Keypoint.h>
#include <falkolib/Feature/DescriptorExtractor.h>
#include <falkolib/Feature/CGH.h>
namespace falkolib {
/**
* @brief class representing a CGH descriptor extractor engine
*/
template <typename T>
class CGHExtractor : public DescriptorExtractor<T, CGH> {
public:
/**
* @brief Constructor
* @param _circularSectorNumber number of grid circular sector
* @param _useKeypointRadius if true, the selected neighborhood points search radius is keypoint one
* @param _radius neighborhood points search radius
*/
CGHExtractor(int _circularSectorNumber, bool _useKeypointRadius = true, double _radius = 0.1) {
circularSectorNumber = _circularSectorNumber;
useKeypointRadius = _useKeypointRadius;
radius = _radius;
};
/**
* @brief Extract CGH descriptor from a given scan and a list of keypoints
* @param scan input laser scan
* @param keypoints keypoints list
* @param descriptor extracted from scan and keypoints
*/
void compute(const LaserScan& scan, const std::vector<T>& keypoints, std::vector<CGH>& descriptors) {
descriptors.reserve(keypoints.size());
for (int i = 0; i < keypoints.size(); ++i) {
std::vector<Point2d> neigh;
int midIndex;
if (useKeypointRadius) {
scan.getNeighPoints(keypoints[i].index, keypoints[i].radius, neigh, midIndex);
CGH desc(keypoints[i].radius, circularSectorNumber);
desc.compute(neigh, midIndex);
descriptors.push_back(std::move(desc));
} else {
scan.getNeighPoints(keypoints[i].index, radius, neigh, midIndex);
CGH desc(radius, circularSectorNumber);
desc.compute(neigh, midIndex);
descriptors.push_back(std::move(desc));
}
}
};
private:
int circularSectorNumber;
bool useKeypointRadius;
double radius;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
namespace falkolib {
/**
* @brief class representing a generic descriptor
*
* No properties are defined for a generic descriptor
*/
class Descriptor {
protected:
/**
* @brief Compute distance between two descriptors
* @param desc descriptor to measure distance
* @return the distance between *this and desc
*/
virtual double distance(const Descriptor& desc) const = 0;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Common/LaserScan.h>
#include <falkolib/Feature/Keypoint.h>
namespace falkolib {
/**
* @brief class representing a descriptor extractor engine
*/
template <typename T, typename D>
class DescriptorExtractor {
protected:
/**
* @brief Extract descriptor from a given scan and a list of keypoints
* @param scan input laser scan
* @param keypoints keypoints list
* @param descriptor extracted from scan and keypoints
*/
virtual void compute(const LaserScan& scan, const std::vector<T>& keypoints, std::vector<D>& descriptors) = 0;
};
}
\ No newline at end of file
/**
* FALKOLib - Fast Adaptive Laser Keypoint Orientation-invariant
* Copyright (C) 2016 Fabjan Kallasi and Dario Lodi Rizzini.
*
* This file is part of FALKOLib.
*
* FALKOLib is free software: you can redistribute it and/or modify
* it under the terms of the GNU Lesser General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* FALKOLib is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU Lesser General Public License for more details.
*
* You should have received a copy of the GNU Lesser General Public License
* along with FALKOLib. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#include <falkolib/Feature/Keypoint.h>
namespace falkolib{
/**
* @brief class representing a FALKO keypoint
*
* FALKO keypoint extends simple keypoint interface.
* The index in the original scan, corner orientation and neighborhood search radius are also preserved.
*/
class FALKO : public Keypoint{
public:
int index;
double radius;
double orientation;
};
}
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment