diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index fee4770bdba203fb9a05226d54c9de23e30e96ce..71ab644dfb0e7f3c29e65558446aff7a62847a5f 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -67,7 +67,6 @@ SET(HDRS
 
   IF(falkolib_FOUND)
     SET(HDRS ${HDRS}
-      corner_falko_2d.h
       loop_closure_falko.h
       scene_falko.h
       match_loop_closure_scene.h)
@@ -96,10 +95,6 @@ SET(SRCS
       icp.cpp)
   ENDIF(csm_FOUND)
 
-  IF(falkolib_FOUND)
-    SET(SRCS ${SRCS}
-      corner_falko_2d.cpp)
-  ENDIF(falkolib_FOUND)
 
 
   
diff --git a/src/corner_falko_2d.cpp b/src/corner_falko_2d.cpp
deleted file mode 100644
index edce4b95f518ede523c5a6278a4d5c78a1f8683f..0000000000000000000000000000000000000000
--- a/src/corner_falko_2d.cpp
+++ /dev/null
@@ -1,121 +0,0 @@
-/**
- * \file corner_falko_2d.cpp
- *
- *  Created on: Jan 26, 2021
- *      \author: spujol
- */
-
-#include "corner_falko_2d.h"
-
-namespace laserscanutils {
-
-CornerFalko2d::CornerFalko2d(int _circularSectorNumber, int _radialRingNumber,
-                             bool _useKeypointRadius, double _radius)
-  : BSCExtractor(_circularSectorNumber, _radialRingNumber, _useKeypointRadius,
-                 _radius) {
-  // FALKO Extractor Parameters
-  setMinExtractionRange(0.1);
-  setMaxExtractionRange(25);
-  enableSubbeam(true);
-  setNMSRadius(0.1);
-  setNeighB(0.01);
-  setBRatio(4);
-  setGridSectors(16);
-
-  // Matcher Extractor Parameters
-  setDistanceThreshold(0.1);
-}
-
-CornerFalko2d::~CornerFalko2d() {}
-
-void CornerFalko2d::AddNewReferenceScene(falkolib::LaserScan scanFALKO) {
-
-  // Extract keypoints
-  lastKeypointSet.clear();
-  extract(scanFALKO, lastKeypointSet);
-
-  // Compute descriptors
-  lastDescriptorSet.clear();
-  compute(scanFALKO, lastKeypointSet, lastDescriptorSet);
-
-  keypointSets.push_back(lastKeypointSet);
-  descriptorSets.push_back(lastDescriptorSet);
-
-  scansExtracted = scansExtracted + 1;
-}
-
-void CornerFalko2d::findLoopClosure(LaserScan scan,
-                                    LaserScanParams scanParams) {
-
-  falkolib::LaserScan scanFALKO = convert2LaserScanFALKO(scan, scanParams);
-
-  // Compute descriptors
-  std::vector<falkolib::FALKO> keypointSet2;
-  extract(scanFALKO, keypointSet2);
-
-  // Compute descriptors
-  std::vector<falkolib::BSC> descriptorSet2;
-  compute(scanFALKO, keypointSet2, descriptorSet2);
-
-  // Matching
-  int rows = keypointSets.size();
-
-  numberKeypointsMatch = 0;
-  numberSceneMatch = 0;
-  matchingPosition = -1;
-  for (int i = 0; i < rows; i++) {
-    std::vector<std::pair<int, int>> assoNN;
-
-    int NewMatchingNumber = match(keypointSets[i], keypointSet2, assoNN);
-
-    if (NewMatchingNumber > numberKeypointsMatch &&
-        NewMatchingNumber > keypointsNumberTh) {
-      numberKeypointsMatch = NewMatchingNumber;
-      matchingPosition = i;
-      numberSceneMatch = numberSceneMatch + 1;
-    }
-  }
-  if (numberSceneMatch > 1) {
-    numberSceneMatch = 0;
-    matchingPosition = -1;
-  }
-}
-
-falkolib::LaserScan
-CornerFalko2d::convert2LaserScanFALKO(LaserScan scan,
-                                      LaserScanParams scanParams) {
-
-  falkolib::LaserScan scanFALKO(scanParams.angle_min_, scanParams.angle_max_,
-                                scan.ranges_raw_.size());
-  std::vector<double> doubleRanges(scan.ranges_raw_.begin(),
-                                   scan.ranges_raw_.end());
-  scanFALKO.fromRanges(doubleRanges);
-  return scanFALKO;
-}
-
-int CornerFalko2d::evaluateNewReferenceScene(LaserScan scan,
-                                             LaserScanParams scanParams,
-                                             int scanInterval) {
-
-  scanNumber = scanNumber + 1;
-
-  int NewSceneAdded = 0;
-
-  if (scanNumber % scanInterval == 0 || scanNumber == 1) {
-
-    findLoopClosure(scan, scanParams);
-
-    if (numberKeypointsMatch < refSceneAddingTh) {
-
-      falkolib::LaserScan scanFALKO = convert2LaserScanFALKO(scan, scanParams);
-
-      AddNewReferenceScene(scanFALKO);
-
-      NewSceneAdded = 1;
-    }
-  }
-
-  return NewSceneAdded;
-}
-
-} // laserscanutils namespace
diff --git a/src/corner_falko_2d.h b/src/corner_falko_2d.h
deleted file mode 100644
index 89513e679a909bf1fbd75726e608aae446b3fa6f..0000000000000000000000000000000000000000
--- a/src/corner_falko_2d.h
+++ /dev/null
@@ -1,119 +0,0 @@
-/**
- * \file corner_falko_2d.h
- *
- *  Created on: Jan 26, 2021
- *      \author: spujol
- */
-
-#ifndef CORNER_FALKO_2D_H_
-#define CORNER_FALKO_2D_H_
-
-#include <fstream>
-#include <iostream>
-
-/**************************
- *      laser_scan_utils includes     *
- **************************/
-#include "laser_scan.h"
-
-/**************************
- *      WOLF includes     *
- **************************/
-//#include "core/landmark/landmark_base.h"
-
-/**************************
- *      Falko includes      *
- **************************/
-#include <falkolib/Feature/BSC.h>
-#include <falkolib/Feature/CGH.h>
-#include <falkolib/Feature/FALKO.h>
-#include <falkolib/Feature/FALKOExtractor.h>
-
-#include <falkolib/Feature/BSCExtractor.h>
-#include <falkolib/Feature/CGHExtractor.h>
-
-#include <falkolib/Matching/AHTMatcher.h>
-#include <falkolib/Matching/NNMatcher.h>
-
-namespace laserscanutils {
-
-/** \brief A 2D corner extractor and loop closure computing class
-**/
-
-class CornerFalko2d : public falkolib::FALKOExtractor,
-                      public falkolib::BSCExtractor<falkolib::FALKO>,
-                      public falkolib::NNMatcher<falkolib::FALKO> {
-private:
-  /** \brief Get and stores a scene to use as trained/Reference set of
-    *keypoints.
-   **/
-  void AddNewReferenceScene(falkolib::LaserScan scanFALKO);
-
-public:
-  /**
-   * @brief Constructor
-   * @param _circularSectorNumber number of grid circular sector (BSCExtractor)
-   * @param _radialRingNumber number of grid radial number (BSCExtractor)
-   * @param _useKeypointRadius if true, the selected neighborhood points search
-   * radius is keypoint one (BSCExtractor)
-   * @param _radius neighborhood points search radius (BSCExtractor)
-   */
-  CornerFalko2d(int _circularSectorNumber = 16, int _radialRingNumber = 8,
-                bool _useKeypointRadius = true, double _radius = 0.1);
-
-  /** \brief Destructor
-   **/
-  ~CornerFalko2d();
-
-  /** \brief compare new scans against the training set in order to find loop
-    *closures
-   **/
-  void findLoopClosure(LaserScan scan, LaserScanParams scanParams);
-
-  /** @brief set a threshold for the minimum number of matched keypoints to
-   * consider a matching correct*/
-  void setKeypointsNumberTh(int _th) { keypointsNumberTh = _th; }
-
-  /** \brief Convert scans from laserscanutils::LaserScan to falkolib::LaserScan
-    *object
-   **/
-  falkolib::LaserScan convert2LaserScanFALKO(LaserScan scan,
-                                             LaserScanParams scanParams);
-
-  /** \brief Evaluates if New scene is a good candidate to be a Reference Scene.
-   *If it is detected as good,
-   * the scene is added and the functions returns 1. If it is not a good
-   *candidate, the function returns 0
-   * and the scene is not added.
-   **/
-  int evaluateNewReferenceScene(LaserScan scan, LaserScanParams scanParams,
-                                int scanInterval);
-
-  std::vector<std::vector<falkolib::FALKO>> keypointSets;
-  std::vector<falkolib::FALKO> lastKeypointSet;
-  std::vector<std::vector<falkolib::BSC>> descriptorSets;
-  std::vector<falkolib::BSC> lastDescriptorSet;
-
-  // Number of Scene matched when performing the loop closure
-  int numberKeypointsMatch = 0;
-
-  // Number of keypoints that are matched between 2 scenes when performing the
-  // loop closure
-  int numberSceneMatch = 0;
-
-  int scanNumber = 0;
-
-  int scansExtracted = 0;
-
-  int matchingPosition = -1;
-
-  int keypointsNumberTh = 2;
-
-  // Max number of matched keypoints between 2 scenes for the candidate scene be
-  // considered a good New reference scene
-  int refSceneAddingTh = 4;
-};
-
-} /* namespace laserscanutils */
-
-#endif /* LANDMARK_POLYLINE_2d_H_ */
diff --git a/src/examples/CMakeLists.txt b/src/examples/CMakeLists.txt
index 40bd1f1b53cfa80b9bc0ab06105a203c3b06e6b5..63e4efbb4ef743ab976b5a505826cb99099c0058 100644
--- a/src/examples/CMakeLists.txt
+++ b/src/examples/CMakeLists.txt
@@ -3,7 +3,3 @@ INCLUDE_DIRECTORIES(../src)
 # polylines demo
 ADD_EXECUTABLE(demo_polylines polyline_demo.cpp)
 TARGET_LINK_LIBRARIES(demo_polylines ${PROJECT_NAME})
-
-# falkocorners demo
-ADD_EXECUTABLE(demo_corner_falko corner_falko_demo.cpp testData.cpp)
-TARGET_LINK_LIBRARIES(demo_corner_falko ${PROJECT_NAME})
diff --git a/src/examples/corner_falko_demo.cpp b/src/examples/corner_falko_demo.cpp
deleted file mode 100644
index 8baa3569e993b76788dfa5636ecf0386dc33ff26..0000000000000000000000000000000000000000
--- a/src/examples/corner_falko_demo.cpp
+++ /dev/null
@@ -1,49 +0,0 @@
-/**
- * \file corner_falko_2d_test.cpp
- *
- *  Created on: Jan 26, 2021
- *      \author: spujol
- */
-
-//LaserScanUtils includes
-#include "../line_finder_iterative.h"
-#include "../corner_falko_2d.h"
-#include "../laser_scan.h"
-#include "testData.h"
-
-
-//std includes
-#include <ctime>
-#include <iostream>
-using namespace laserscanutils;
-
-int main(int argc, char** argv)
-{
-
-    int scanSize = 1440;
-    int scanInterval =1;
-
-    LaserScan scan;
-    LaserScanParams laserParams;
-
-    laserParams.angle_min_=0;
-    laserParams.angle_max_=2.0 * M_PI;
-
-    for (int i=0; i<scanSize; i++) {
-     scan.ranges_raw_.push_back(testRanges1[i]);
-    }
-
-    CornerFalko2d cornerMatching;
-
-    int sceneAdded = cornerMatching.evaluateNewReferenceScene(scan, laserParams, scanInterval);
-
-    std::cout << "num keypoints1 extracted: " << cornerMatching.lastKeypointSet.size() << std::endl;
-
-    if (sceneAdded==1){
-        std::cout << "NewRefSceneAdded!!! " << std::endl;
-    }
-
-    cornerMatching.findLoopClosure(scan, laserParams);
-
-    std::cout << "matching number : " << cornerMatching.numberKeypointsMatch << std::endl;
-}
diff --git a/src/examples/testData.cpp b/src/examples/testData.cpp
deleted file mode 100644
index f71191cf88bd0b475550dd857bb7524abd7d856c..0000000000000000000000000000000000000000
--- a/src/examples/testData.cpp
+++ /dev/null
@@ -1,23 +0,0 @@
-/**
- * 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/>.
- */
-
-    double testRanges1[]= {250, 250, 250, 250, 250, 17.263999938964844, 17.263999938964844, 17.263999938964844, 17.263999938964844, 13.552000045776367, 13.552000045776367, 13.552000045776367, 12.95199966430664, 12.95199966430664, 12.95199966430664, 12.95199966430664, 12.51200008392334, 11.567999839782715, 11.567999839782715, 10.720000267028809, 10.720000267028809, 10.720000267028809, 10.359999656677246, 10.336000442504883, 10.343999862670898, 10.35200023651123, 10.35200023651123, 10.32800006866455, 10.319999694824219, 10.383999824523926, 10.407999992370605, 10.432000160217285, 10.432000160217285, 10.447999954223633, 10.46399974822998, 10.46399974822998, 10.503999710083008, 10.503999710083008, 10.527999877929688, 10.592000007629395, 10.62399959564209, 8.368000030517578, 8.343999862670898, 8.343999862670898, 8.031999588012695, 7.831999778747559, 7.6479997634887695, 7.552000045776367, 7.415999889373779, 7.415999889373779, 7.263999938964844, 7.144000053405762, 7.0320000648498535, 6.920000076293945, 6.776000022888184, 6.776000022888184, 6.671999931335449, 6.576000213623047, 6.440000057220459, 6.328000068664551, 6.271999835968018, 6.271999835968018, 6.263999938964844, 6.271999835968018, 6.296000003814697, 6.320000171661377, 6.328000068664551, 6.328000068664551, 6.335999965667725, 6.320000171661377, 3.187999963760376, 3.187999963760376, 4.495999813079834, 4.495999813079834, 4.495999813079834, 4.495999813079834, 4.504000186920166, 4.504000186920166, 4.504000186920166, 4.544000148773193, 4.544000148773193, 4.544000148773193, 4.544000148773193, 4.51200008392334, 4.51200008392334, 4.51200008392334, 4.51200008392334, 4.599999904632568, 4.576000213623047, 4.495999813079834, 4.455999851226807, 4.455999851226807, 4.455999851226807, 4.455999851226807, 4.4079999923706055, 4.368000030517578, 4.320000171661377, 4.271999835968018, 4.271999835968018, 4.223999977111816, 4.184000015258789, 4.168000221252441, 4.159999847412109, 4.168000221252441, 4.176000118255615, 4.176000118255615, 4.184000015258789, 4.199999809265137, 4.199999809265137, 4.208000183105469, 4.216000080108643, 4.216000080108643, 4.223999977111816, 4.23199987411499, 4.23199987411499, 4.176000118255615, 250, 250, 4.111999988555908, 4.111999988555908, 4.111999988555908, 4.111999988555908, 4.099999904632568, 4.099999904632568, 4.099999904632568, 4.079999923706055, 4.0320000648498535, 3.98799991607666, 3.9719998836517334, 3.9719998836517334, 3.9560000896453857, 3.9240000247955322, 3.888000011444092, 3.859999895095825, 3.8320000171661377, 3.8320000171661377, 3.803999900817871, 3.7880001068115234, 3.259999990463257, 3.240000009536743, 3.2200000286102295, 3.2200000286102295, 3.200000047683716, 3.1760001182556152, 3.1559998989105225, 3.1440000534057617, 3.128000020980835, 3.128000020980835, 3.119999885559082, 2.5959999561309814, 2.5959999561309814, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 2.4839999675750732, 2.4839999675750732, 2.4839999675750732, 2.4839999675750732, 2.496000051498413, 2.5320000648498535, 250, 2.624000072479248, 2.624000072479248, 2.624000072479248, 2.624000072479248, 250, 250, 250, 250, 250, 250, 250, 2.6679999828338623, 2.6679999828338623, 2.6679999828338623, 2.6679999828338623, 2.640000104904175, 2.640000104904175, 2.640000104904175, 2.628000020980835, 2.615999937057495, 2.615999937057495, 2.6080000400543213, 2.5959999561309814, 2.5880000591278076, 2.5759999752044678, 2.563999891281128, 2.563999891281128, 2.555999994277954, 2.5439999103546143, 2.5320000648498535, 2.5199999809265137, 2.51200008392334, 2.51200008392334, 2.503999948501587, 2.492000102996826, 2.4839999675750732, 2.4719998836517334, 2.4639999866485596, 2.4639999866485596, 2.4600000381469727, 2.4519999027252197, 2.440000057220459, 2.431999921798706, 2.4200000762939453, 2.4200000762939453, 2.4159998893737793, 2.4079999923706055, 2.4079999923706055, 2.427999973297119, 2.444000005722046, 2.444000005722046, 2.4600000381469727, 2.4719998836517334, 2.48799991607666, 2.5, 2.5160000324249268, 2.5160000324249268, 2.5280001163482666, 2.5399999618530273, 2.559999942779541, 2.5799999237060547, 2.5840001106262207, 2.5840001106262207, 3.0480000972747803, 3.0480000972747803, 2.631999969482422, 2.631999969482422, 2.631999969482422, 2.624000072479248, 2.624000072479248, 2.624000072479248, 2.624000072479248, 2.615999937057495, 2.611999988555908, 2.6040000915527344, 2.6040000915527344, 2.5959999561309814, 2.5920000076293945, 2.5840001106262207, 2.5759999752044678, 2.572000026702881, 2.572000026702881, 2.563999891281128, 2.555999994277954, 2.5480000972747803, 2.5439999103546143, 2.5399999618530273, 2.5399999618530273, 2.5360000133514404, 2.5320000648498535, 2.5239999294281006, 2.5199999809265137, 2.507999897003174, 2.507999897003174, 2.503999948501587, 2.5, 2.496000051498413, 2.492000102996826, 2.48799991607666, 2.48799991607666, 2.4800000190734863, 2.4760000705718994, 2.4719998836517334, 2.4679999351501465, 2.4639999866485596, 2.4560000896453857, 2.4560000896453857, 2.4519999027252197, 2.447999954223633, 2.447999954223633, 2.444000005722046, 2.436000108718872, 2.436000108718872, 2.431999921798706, 2.427999973297119, 2.4240000247955322, 2.4240000247955322, 2.4200000762939453, 2.4200000762939453, 2.4159998893737793, 2.4079999923706055, 2.4040000438690186, 2.4040000438690186, 2.4000000953674316, 2.4000000953674316, 2.3959999084472656, 2.3919999599456787, 2.3919999599456787, 2.388000011444092, 2.384000062942505, 2.384000062942505, 2.380000114440918, 2.375999927520752, 2.371999979019165, 2.371999979019165, 2.368000030517578, 2.364000082015991, 2.364000082015991, 2.364000082015991, 2.364000082015991, 2.359999895095825, 2.3559999465942383, 2.3559999465942383, 2.3559999465942383, 2.6600000858306885, 2.6600000858306885, 2.6600000858306885, 2.003999948501587, 2.003999948501587, 2.003999948501587, 2.003999948501587, 2.003999948501587, 2.003999948501587, 2.003999948501587, 2.0, 2.0, 2.0, 2.0, 1.9980000257492065, 1.9980000257492065, 1.9980000257492065, 1.9980000257492065, 1.996000051498413, 1.996000051498413, 1.996000051498413, 1.99399995803833, 1.9919999837875366, 1.996000051498413, 1.996000051498413, 1.996000051498413, 1.996000051498413, 1.996000051498413, 1.99399995803833, 2.0, 2.0, 2.009999990463257, 2.0220000743865967, 2.0460000038146973, 2.0460000038146973, 2.0260000228881836, 2.0260000228881836, 2.00600004196167, 1.996000051498413, 1.99399995803833, 1.9900000095367432, 1.9919999837875366, 1.9919999837875366, 1.996000051498413, 1.9980000257492065, 1.99399995803833, 1.9919999837875366, 1.9919999837875366, 1.9919999837875366, 1.99399995803833, 1.99399995803833, 1.996000051498413, 1.9980000257492065, 1.9980000257492065, 1.9980000257492065, 1.9980000257492065, 2.0, 2.0, 1.9980000257492065, 1.9980000257492065, 1.9919999837875366, 1.9520000219345093, 2.0320000648498535, 2.0999999046325684, 2.1040000915527344, 2.1040000915527344, 2.0280001163482666, 1.9040000438690186, 1.9279999732971191, 1.9520000219345093, 1.9559999704360962, 1.9559999704360962, 1.9600000381469727, 1.9579999446868896, 1.9600000381469727, 1.9620000123977661, 1.9639999866485596, 1.9639999866485596, 1.965999960899353, 1.965999960899353, 1.968000054359436, 1.972000002861023, 1.9759999513626099, 1.9759999513626099, 1.9759999513626099, 1.9759999513626099, 1.9800000190734863, 1.9839999675750732, 1.9800000190734863, 1.9800000190734863, 1.9819999933242798, 1.9880000352859497, 1.996000051498413, 2.009999990463257, 2.00600004196167, 2.00600004196167, 1.99399995803833, 2.687999963760376, 2.687999963760376, 2.687999963760376, 1.74399995803833, 1.74399995803833, 2.063999891281128, 2.115999937057495, 2.196000099182129, 2.191999912261963, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 2.5280001163482666, 2.5280001163482666, 2.5280001163482666, 2.5280001163482666, 2.5199999809265137, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5280001163482666, 2.5280001163482666, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5239999294281006, 2.5280001163482666, 2.5239999294281006, 2.5280001163482666, 2.5280001163482666, 2.5280001163482666, 2.5280001163482666, 2.5280001163482666, 2.5320000648498535, 2.5320000648498535, 2.5320000648498535, 2.5320000648498535, 2.5320000648498535, 2.5320000648498535, 2.5360000133514404, 2.5399999618530273, 2.5480000972747803, 2.5480000972747803, 2.5480000972747803, 2.5399999618530273, 2.5439999103546143, 2.552000045776367, 2.555999994277954, 2.555999994277954, 2.552000045776367, 2.5480000972747803, 250, 1.3179999589920044, 1.3179999589920044, 1.3179999589920044, 1.3179999589920044, 1.3079999685287476, 1.2999999523162842, 1.2940000295639038, 1.2940000295639038, 1.2879999876022339, 1.2860000133514404, 1.2940000295639038, 1.3040000200271606, 1.3040000200271606, 1.3040000200271606, 1.2999999523162842, 1.2979999780654907, 1.3020000457763672, 1.309999942779541, 1.3140000104904175, 1.3140000104904175, 1.3140000104904175, 1.3240000009536743, 1.3359999656677246, 1.3420000076293945, 1.343999981880188, 1.343999981880188, 1.2200000286102295, 250, 250, 250, 250, 250, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.090000033378601, 1.090000033378601, 1.0920000076293945, 1.0980000495910645, 1.0980000495910645, 1.100000023841858, 1.100000023841858, 1.100000023841858, 1.100000023841858, 1.0980000495910645, 1.0980000495910645, 1.0980000495910645, 1.0959999561309814, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.0920000076293945, 1.093999981880188, 1.093999981880188, 1.093999981880188, 1.1019999980926514, 1.1119999885559082, 1.121999979019165, 1.1260000467300415, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 5.791999816894531, 5.791999816894531, 5.791999816894531, 5.791999816894531, 5.776000022888184, 5.776000022888184, 5.776000022888184, 5.751999855041504, 5.751999855041504, 5.751999855041504, 5.751999855041504, 5.751999855041504, 5.736000061035156, 5.679999828338623, 5.671999931335449, 5.671999931335449, 5.631999969482422, 5.631999969482422, 5.552000045776367, 5.552000045776367, 5.552000045776367, 5.552000045776367, 5.559999942779541, 5.584000110626221, 6.104000091552734, 6.783999919891357, 6.831999778747559, 6.831999778747559, 6.831999778747559, 6.760000228881836, 6.616000175476074, 6.455999851226807, 6.343999862670898, 6.343999862670898, 6.320000171661377, 6.311999797821045, 9.192000389099121, 9.175999641418457, 9.15999984741211, 9.15999984741211, 9.128000259399414, 9.119999885559082, 7.992000102996826, 7.9120001792907715, 7.8480000495910645, 7.8480000495910645, 7.800000190734863, 7.74399995803833, 7.71999979019165, 7.711999893188477, 7.711999893188477, 7.711999893188477, 7.711999893188477, 7.71999979019165, 7.71999979019165, 7.711999893188477, 7.703999996185303, 7.703999996185303, 7.703999996185303, 7.688000202178955, 7.688000202178955, 7.688000202178955, 7.688000202178955, 7.671999931335449, 8.67199993133545, 8.640000343322754, 8.607999801635742, 8.583999633789062, 8.583999633789062, 8.5600004196167, 8.552000045776367, 8.53600025177002, 8.520000457763672, 8.503999710083008, 8.503999710083008, 8.472000122070312, 8.447999954223633, 8.416000366210938, 8.383999824523926, 8.383999824523926, 8.383999824523926, 8.368000030517578, 8.35200023651123, 8.35200023651123, 8.336000442504883, 8.303999900817871, 8.303999900817871, 8.263999938964844, 8.239999771118164, 8.279999732971191, 8.392000198364258, 8.496000289916992, 8.496000289916992, 8.656000137329102, 8.807999610900879, 8.928000450134277, 9.015999794006348, 11.767999649047852, 11.767999649047852, 12.071999549865723, 12.175999641418457, 12.567999839782715, 12.663999557495117, 13.064000129699707, 13.064000129699707, 13.168000221252441, 13.607999801635742, 13.640000343322754, 13.53600025177002, 13.968000411987305, 13.968000411987305, 14.008000373840332, 14.104000091552734, 14.175999641418457, 14.104000091552734, 15.4399995803833, 15.4399995803833, 15.543999671936035, 15.48799991607666, 15.48799991607666, 15.503999710083008, 15.479999542236328, 15.479999542236328, 15.447999954223633, 15.399999618530273, 15.37600040435791, 15.35200023651123, 15.319999694824219, 15.319999694824219, 15.272000312805176, 15.272000312805176, 15.336000442504883, 15.303999900817871, 15.248000144958496, 15.248000144958496, 14.744000434875488, 15.303999900817871, 15.272000312805176, 15.248000144958496, 15.215999603271484, 15.223999977111816, 15.223999977111816, 15.248000144958496, 16.784000396728516, 16.719999313354492, 16.719999313354492, 16.719999313354492, 16.719999313354492, 16.672000885009766, 16.687999725341797, 16.719999313354492, 16.70400047302246, 16.607999801635742, 16.607999801635742, 16.624000549316406, 16.6560001373291, 16.23200035095215, 16.143999099731445, 16.06399917602539, 16.06399917602539, 16.016000747680664, 17.472000122070312, 19.007999420166016, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250};
-
-
diff --git a/src/examples/testData.h b/src/examples/testData.h
deleted file mode 100644
index d0e07f09dfadae8a1b9f587b01e8322bf750294b..0000000000000000000000000000000000000000
--- a/src/examples/testData.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/**
- * 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
-
-extern double testRanges1[];
-
-extern double testRanges2[];
-
-extern double testRangesOrtho1[];
-
-extern double testRangesOrtho2[];