diff --git a/.cproject b/.cproject
deleted file mode 100644
index c1053796f2138cd61b6bbff7ad266cc207e7b09a..0000000000000000000000000000000000000000
--- a/.cproject
+++ /dev/null
@@ -1,100 +0,0 @@
-<?xml version="1.0" encoding="UTF-8" standalone="no"?>
-<?fileVersion 4.0.0?><cproject storage_type_id="org.eclipse.cdt.core.XmlProjectDescriptionStorage">
-	<storageModule moduleId="org.eclipse.cdt.core.settings">
-		<cconfiguration id="cdt.managedbuild.toolchain.gnu.macosx.base.1178130951">
-			<storageModule buildSystemId="org.eclipse.cdt.managedbuilder.core.configurationDataProvider" id="cdt.managedbuild.toolchain.gnu.macosx.base.1178130951" moduleId="org.eclipse.cdt.core.settings" name="Default">
-				<externalSettings/>
-				<extensions>
-					<extension id="org.eclipse.cdt.core.MachO64" point="org.eclipse.cdt.core.BinaryParser"/>
-					<extension id="org.eclipse.cdt.core.GASErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
-					<extension id="org.eclipse.cdt.core.GmakeErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
-					<extension id="org.eclipse.cdt.core.GLDErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
-					<extension id="org.eclipse.cdt.core.CWDLocator" point="org.eclipse.cdt.core.ErrorParser"/>
-					<extension id="org.eclipse.cdt.core.GCCErrorParser" point="org.eclipse.cdt.core.ErrorParser"/>
-				</extensions>
-			</storageModule>
-			<storageModule moduleId="cdtBuildSystem" version="4.0.0">
-				<configuration buildProperties="" description="" id="cdt.managedbuild.toolchain.gnu.macosx.base.1178130951" name="Default" optionalBuildProperties="" parent="org.eclipse.cdt.build.core.emptycfg">
-					<folderInfo id="cdt.managedbuild.toolchain.gnu.macosx.base.1178130951.356003364" name="/" resourcePath="">
-						<toolChain id="cdt.managedbuild.toolchain.gnu.macosx.base.934860253" name="MacOSX GCC" superClass="cdt.managedbuild.toolchain.gnu.macosx.base">
-							<targetPlatform archList="all" binaryParser="org.eclipse.cdt.core.MachO64" id="cdt.managedbuild.target.gnu.platform.macosx.base.180403450" name="Debug Platform" osList="macosx" superClass="cdt.managedbuild.target.gnu.platform.macosx.base"/>
-							<builder buildPath="${workspace_loc:/vision_utils}/build" id="cdt.managedbuild.target.gnu.builder.macosx.base.1923371391" keepEnvironmentInBuildfile="false" managedBuildOn="false" name="Gnu Make Builder" superClass="cdt.managedbuild.target.gnu.builder.macosx.base"/>
-							<tool id="cdt.managedbuild.tool.macosx.c.linker.macosx.base.1893770995" name="MacOS X C Linker" superClass="cdt.managedbuild.tool.macosx.c.linker.macosx.base"/>
-							<tool id="cdt.managedbuild.tool.macosx.cpp.linker.macosx.base.972023983" name="MacOS X C++ Linker" superClass="cdt.managedbuild.tool.macosx.cpp.linker.macosx.base">
-								<inputType id="cdt.managedbuild.tool.macosx.cpp.linker.input.154865431" superClass="cdt.managedbuild.tool.macosx.cpp.linker.input">
-									<additionalInput kind="additionalinputdependency" paths="$(USER_OBJS)"/>
-									<additionalInput kind="additionalinput" paths="$(LIBS)"/>
-								</inputType>
-							</tool>
-							<tool id="cdt.managedbuild.tool.gnu.assembler.macosx.base.1257423770" name="GCC Assembler" superClass="cdt.managedbuild.tool.gnu.assembler.macosx.base">
-								<inputType id="cdt.managedbuild.tool.gnu.assembler.input.1541468489" superClass="cdt.managedbuild.tool.gnu.assembler.input"/>
-							</tool>
-							<tool id="cdt.managedbuild.tool.gnu.archiver.macosx.base.72102810" name="GCC Archiver" superClass="cdt.managedbuild.tool.gnu.archiver.macosx.base"/>
-							<tool id="cdt.managedbuild.tool.gnu.cpp.compiler.macosx.base.764600872" name="GCC C++ Compiler" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.macosx.base">
-								<inputType id="cdt.managedbuild.tool.gnu.cpp.compiler.input.427517208" superClass="cdt.managedbuild.tool.gnu.cpp.compiler.input"/>
-							</tool>
-							<tool id="cdt.managedbuild.tool.gnu.c.compiler.macosx.base.254554445" name="GCC C Compiler" superClass="cdt.managedbuild.tool.gnu.c.compiler.macosx.base">
-								<inputType id="cdt.managedbuild.tool.gnu.c.compiler.input.532911999" superClass="cdt.managedbuild.tool.gnu.c.compiler.input"/>
-							</tool>
-						</toolChain>
-					</folderInfo>
-				</configuration>
-			</storageModule>
-			<storageModule moduleId="org.eclipse.cdt.core.externalSettings"/>
-		</cconfiguration>
-	</storageModule>
-	<storageModule moduleId="scannerConfiguration">
-		<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1819918851;cdt.managedbuild.toolchain.gnu.base.1819918851.1318867162;cdt.managedbuild.tool.gnu.cpp.compiler.base.1649772065;cdt.managedbuild.tool.gnu.cpp.compiler.input.146329834">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.207681558;cdt.managedbuild.toolchain.gnu.base.207681558.1208625085;cdt.managedbuild.tool.gnu.c.compiler.base.1439246049;cdt.managedbuild.tool.gnu.c.compiler.input.637694474">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.727026548;cdt.managedbuild.toolchain.gnu.base.727026548.1071101131;cdt.managedbuild.tool.gnu.c.compiler.base.61708613;cdt.managedbuild.tool.gnu.c.compiler.input.166078074">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1060824152;cdt.managedbuild.toolchain.gnu.base.1060824152.880296614;cdt.managedbuild.tool.gnu.cpp.compiler.base.14005989;cdt.managedbuild.tool.gnu.cpp.compiler.input.1139568866">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.207681558;cdt.managedbuild.toolchain.gnu.base.207681558.1208625085;cdt.managedbuild.tool.gnu.cpp.compiler.base.1755527935;cdt.managedbuild.tool.gnu.cpp.compiler.input.1794914341">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.727026548;cdt.managedbuild.toolchain.gnu.base.727026548.1071101131;cdt.managedbuild.tool.gnu.cpp.compiler.base.433122623;cdt.managedbuild.tool.gnu.cpp.compiler.input.341288586">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.772018425;cdt.managedbuild.toolchain.gnu.cross.base.772018425.677700058;cdt.managedbuild.tool.gnu.cross.cpp.compiler.1552607345;cdt.managedbuild.tool.gnu.cpp.compiler.input.2062058076">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1819918851;cdt.managedbuild.toolchain.gnu.base.1819918851.1318867162;cdt.managedbuild.tool.gnu.c.compiler.base.593702953;cdt.managedbuild.tool.gnu.c.compiler.input.392834553">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1736073220;cdt.managedbuild.toolchain.gnu.base.1736073220.1390770886;cdt.managedbuild.tool.gnu.cpp.compiler.base.1526891046;cdt.managedbuild.tool.gnu.cpp.compiler.input.1116382079">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1736073220;cdt.managedbuild.toolchain.gnu.base.1736073220.1390770886;cdt.managedbuild.tool.gnu.c.compiler.base.1459107576;cdt.managedbuild.tool.gnu.c.compiler.input.1695301683">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1060824152;cdt.managedbuild.toolchain.gnu.base.1060824152.880296614;cdt.managedbuild.tool.gnu.c.compiler.base.1737626299;cdt.managedbuild.tool.gnu.c.compiler.input.715196728">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1244102678;cdt.managedbuild.toolchain.gnu.base.1244102678.1450977940;cdt.managedbuild.tool.gnu.cpp.compiler.base.1572359948;cdt.managedbuild.tool.gnu.cpp.compiler.input.466329004">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.cross.base.772018425;cdt.managedbuild.toolchain.gnu.cross.base.772018425.677700058;cdt.managedbuild.tool.gnu.cross.c.compiler.2113617585;cdt.managedbuild.tool.gnu.c.compiler.input.844027082">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-		<scannerConfigBuildInfo instanceId="cdt.managedbuild.toolchain.gnu.base.1244102678;cdt.managedbuild.toolchain.gnu.base.1244102678.1450977940;cdt.managedbuild.tool.gnu.c.compiler.base.1838202852;cdt.managedbuild.tool.gnu.c.compiler.input.964584931">
-			<autodiscovery enabled="true" problemReportingEnabled="true" selectedProfileId=""/>
-		</scannerConfigBuildInfo>
-	</storageModule>
-	<storageModule moduleId="cdtBuildSystem" version="4.0.0">
-		<project id="vision_utils.null.2081238018" name="vision_utils"/>
-	</storageModule>
-	<storageModule moduleId="org.eclipse.cdt.core.LanguageSettingsProviders"/>
-	<storageModule moduleId="refreshScope" versionNumber="2">
-		<configuration configurationName="Default">
-			<resource resourceType="PROJECT" workspacePath="/vision_utils"/>
-		</configuration>
-	</storageModule>
-</cproject>
diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml
new file mode 100644
index 0000000000000000000000000000000000000000..b2e158447a5f441967e1a459cd340a0cdd4f720e
--- /dev/null
+++ b/.gitlab-ci.yml
@@ -0,0 +1,24 @@
+############ YAML ANCHORS ############
+.build_and_test_template: &build_and_test_definition
+  - mkdir -pv build
+  - cd build
+  - cmake -DCMAKE_BUILD_TYPE=release -DBUILD_EXAMPLES=ON -DBUILD_TESTS=ON ..
+  - make -j2
+  - ctest -j2
+  - make install
+
+############ UBUNTU 16.04 TESTS ############
+build_and_test_none:xenial:
+  image: labrobotica/wolf_vision_deps:16.04
+  before_script:
+    - apt-get update
+  script:
+    - *build_and_test_definition
+
+############ UBUNTU 18.04 TESTS ############
+build_and_test_none:bionic:
+  image: labrobotica/wolf_vision_deps:18.04
+  before_script:
+    - apt-get update
+  script:
+    - *build_and_test_definition
\ No newline at end of file
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 317eca60dfa552461b62be88d98e90d8f03f917b..d6019dec18466a3dd3b1fb89d2ba84ae78d2a61a 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -12,6 +12,9 @@ if(COMMAND cmake_policy)
    
 endif(COMMAND cmake_policy)
 
+# MAC OSX RPATH
+SET(CMAKE_MACOSX_RPATH true)
+
 # The project name and the type of project
 PROJECT(vision_utils)
 
diff --git a/ReadMe.md b/ReadMe.md
index 2359ecc8db61ab57fb4f669dfe452bca8a69bd40..7d3a48769774aa3bac1bf51fc0d80257e8683344 100644
--- a/ReadMe.md
+++ b/ReadMe.md
@@ -16,46 +16,48 @@ Under MacOS most of the packages are available via [fink](http://www.finkproject
   * [doxygen](http://www.doxygen.org) and 
     [graphviz](http://www.graphviz.org) to generate the documentation
   * stdc++  
-  * [OpenCV](http://opencv.org/) Computer vision library. Installation of version 3.1 or higher is desirable. It is also included here the installation of the 'opencv_contrib' libraries. To install it run the following steps (example for version 3.3):
-
-```
-    $ wget https://github.com/opencv/opencv/archive/3.3.0.zip -O temp.zip && unzip temp.zip && rm temp.zip
-    $ cd opencv-3.3.0
-    $ git clone https://github.com/opencv/opencv_contrib.git && cd opencv_contrib && git checkout 3.3.0 && cd ..
-    $ mkdir build && cd build
-    $ cmake -D CMAKE_BUILD_TYPE=Release -D CMAKE_INSTALL_PREFIX=/usr/local -D CMAKE_CXX_FLAGS="-fPIC -std=c++11" -D OPENCV_EXTRA_MODULES_PATH=../opencv_contrib/modules ..
-    $ make -j4
-    $ sudo make install
+  * [OpenCV](http://opencv.org/) Computer vision library. Installation of version 3.1 or higher is desirable. It is also included here the installation of the 'opencv_contrib' libraries, gtk2.0 and pkg-config. To install it run the following steps (example for version 3.3):
+
+```sh
+sudo apt-get update
+sudo apt-get install libgtk2.0-dev pkg-config
+wget https://github.com/opencv/opencv/archive/3.3.0.zip -O temp.zip && unzip temp.zip && rm temp.zip
+cd opencv-3.3.0
+git clone https://github.com/opencv/opencv_contrib.git && cd opencv_contrib && git checkout 3.3.0 && cd ..
+mkdir build && cd build
+cmake -D CMAKE_BUILD_TYPE=Release -D CMAKE_INSTALL_PREFIX=/usr/local -D CMAKE_CXX_FLAGS="-fPIC -std=c++11" -D OPENCV_EXTRA_MODULES_PATH=../opencv_contrib/modules ..
+make -j4
+sudo make install
 ```
     * NOTE: Check that opencv and `opencv_contrib` versions are the same.  
     
   * [YAML cpp](https://github.com/jbeder/yaml-cpp): Used to load parameters from YAML files. To install it run the following commands:
   
 
-```
-    $ sudo apt-get update
-    $ sudo apt-get install libyaml-cpp-dev
+```sh
+sudo apt-get update
+sudo apt-get install libyaml-cpp-dev
 ```
   * [Boost](http://www.boost.org/). Free peer-reviewed portable C++ source libraries. To install it run the following commands:
   
-```
-    $ sudo apt-get update
-    $ sudo apt-get install libboost-all-dev
+```sh
+sudo apt-get update
+sudo apt-get install libboost-all-dev
 ```
 
 ### Compilation
 
   Just download this package, uncompress it, and execute  
 
-```
-    $ cd build  
-    $ cmake ..  
+```sh
+cd build  
+cmake ..  
 ```
 
 to generate the makefile and then  
 
-```
-    $ make  
+```sh
+make  
 ```
 
 to obtain the shared library and also all the example programs.  
@@ -65,8 +67,8 @@ if you modify one of the `CMakeList.txt` files).
 
 To generate this documentation type  
 
-```
-    $ make doc
+```sh
+make doc
 ```
 
 The files in the `build` directory are genetated by *cmake* and *make* 
@@ -79,8 +81,8 @@ The default build mode is RELEASE. That is, optimizing for speed.
 
 With the DEBUG build mode objects and executables include debug information. To build in this mode execute  
 
-```
-    $ cmake .. -DCMAKE_BUILD_TYPE=DEBUG
+```sh
+cmake .. -DCMAKE_BUILD_TYPE=DEBUG
 ```
 
 The release mode will be kept until next time cmake is executed.  
@@ -90,8 +92,8 @@ The release mode will be kept until next time cmake is executed.
 In order to be able to use the library, it it necessary to copy it into the system. 
 To do that, execute  
 
-```
-    $ make install
+```sh
+make install
 ```
 
 as root and the shared libraries will be copied to `/usr/local/lib/<vision_utils>` directory
@@ -100,8 +102,8 @@ this point, the library may be used by any user.
 
 To remove the library from the system, exceute  
 
-```
-    $ make uninstall
+```sh
+make uninstall
 ```
 
 as root, and all the associated files will be removed from the system.  
@@ -111,21 +113,21 @@ as root, and all the associated files will be removed from the system.
 To build a new application using these library, first it is necessary to locate if the library
 has been installed or not using the following command in your `CMakeLists.txt`  
 
-```
-    FIND_PACKAGE(vision_utils REQUIRED)
+```cmake
+FIND_PACKAGE(vision_utils REQUIRED)
 ```
 
 In the case that the package is present, it is necessary to add the header files directory to
 the include directory path by using  
 
-```
-    INCLUDE_DIRECTORIES(${vision_utils_INCLUDE_DIR})
+```cmake
+INCLUDE_DIRECTORIES(${vision_utils_INCLUDE_DIR})
 ```
 
 Finally, it is also nevessary to link with the desired libraries by using the following command  
 
-```
-    TARGET_LINK_LIBRARIES(<executable name> ${vision_utils_LIBRARY})
+```cmake
+TARGET_LINK_LIBRARIES(<executable name> ${vision_utils_LIBRARY})
 ```
 
 ## License
@@ -152,6 +154,3 @@ 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 this program.  If not, see [gnu licenses](http://www.gnu.org/licenses/)  
-
-
-
diff --git a/src/algorithms/activesearch/alg_activesearch.cpp b/src/algorithms/activesearch/alg_activesearch.cpp
index 243d15e9449458c628dfb11fa11c6b1ae34d7c77..9cd752a4cb9f7f3ae24cb420f5e413f972ae69ca 100644
--- a/src/algorithms/activesearch/alg_activesearch.cpp
+++ b/src/algorithms/activesearch/alg_activesearch.cpp
@@ -4,13 +4,13 @@ namespace vision_utils {
 
 AlgorithmACTIVESEARCH::AlgorithmACTIVESEARCH(void)
 {
-	initialized_=false;
+    initialized_=false;
 }
 
 AlgorithmACTIVESEARCH::~AlgorithmACTIVESEARCH(void)
 {
     if (params_ptr_->draw_results)
-    	cv::destroyAllWindows();
+        cv::destroyAllWindows();
 }
 
 void AlgorithmACTIVESEARCH::initAlg(const int& _img_width, const int& _img_height, const int& _margin)
@@ -20,12 +20,12 @@ void AlgorithmACTIVESEARCH::initAlg(const int& _img_width, const int& _img_heigh
 
     margin_ = _margin;
 
-	if (img_size_(0) == 0 || img_size_(1) == 0)
-		std::cerr << "[Algorithm ACTIVESEARCH]: Image size not set. Current values [" << img_size_(0) << "x" << img_size_(1) << "]" << std::endl;
-	if (params_ptr_->n_cells_h == 0 || params_ptr_->n_cells_v == 0)
-		std::cerr << "[Algorithm ACTIVESEARCH]: number of cells not set. Current values [" << params_ptr_->n_cells_h << "," << params_ptr_->n_cells_v << "]" << std::endl;
+    if (img_size_(0) == 0 || img_size_(1) == 0)
+        std::cerr << "[Algorithm ACTIVESEARCH]: Image size not set. Current values [" << img_size_(0) << "x" << img_size_(1) << "]" << std::endl;
+    if (params_ptr_->n_cells_h == 0 || params_ptr_->n_cells_v == 0)
+        std::cerr << "[Algorithm ACTIVESEARCH]: number of cells not set. Current values [" << params_ptr_->n_cells_h << "," << params_ptr_->n_cells_v << "]" << std::endl;
 
-	// Set internal variables
+    // Set internal variables
     projections_count_.resize(params_ptr_->n_cells_h + 1, params_ptr_->n_cells_v + 1);
     empty_cells_tile_tmp_.resize(2, (params_ptr_->n_cells_h + 1) * (params_ptr_->n_cells_v + 1));
     grid_size_(0) = params_ptr_->n_cells_h + 1;
@@ -37,18 +37,18 @@ void AlgorithmACTIVESEARCH::initAlg(const int& _img_width, const int& _img_heigh
     // set all ready to start clean
     this->clear();
 
-	if (params_ptr_->draw_results)
-	{
-		cv::startWindowThread();
-		cv::namedWindow(getName(), cv::WINDOW_NORMAL);
-	}
+    if (params_ptr_->draw_results)
+    {
+        cv::startWindowThread();
+        cv::namedWindow(getName(), cv::WINDOW_NORMAL);
+    }
 
     initialized_ = true;
 }
 
 void AlgorithmACTIVESEARCH::initAlg(const cv::Mat& _img, const int& _margin)
 {
-	initAlg(_img.cols, _img.rows, _margin);
+    initAlg(_img.cols, _img.rows, _margin);
 }
 
 void AlgorithmACTIVESEARCH::resizeImage(void)
@@ -60,7 +60,8 @@ void AlgorithmACTIVESEARCH::resizeImage(void)
 }
 
 // Functions to fill in cells
-bool AlgorithmACTIVESEARCH::pickEmptyCell(Eigen::Vector2i & _cell) {
+bool AlgorithmACTIVESEARCH::pickEmptyCell(Eigen::Vector2i & _cell)
+{
     int k = 0;
     Eigen::Vector2i cell0;
     for (int i = 1; i < grid_size_(0) - 1; i++) {
@@ -131,63 +132,63 @@ void AlgorithmACTIVESEARCH::blockCell(const cv::Rect & _roi)
 
 void AlgorithmACTIVESEARCH::run(Buffer<FramePtr>& _frame_buff, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr, const MatcherBasePtr& _mat_ptr)
 {
-	// Initialize vars if necessary
-	if (!initialized_)
-		initAlg(_frame_buff.back()->getImage(), _det_ptr->getPatternRadius());
-
-	switch (_frame_buff.size())
-	{
-	case 0:
-		VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
-		break;
-	case 1:
-		detectNewFeatures(_frame_buff.back(), _det_ptr, _des_ptr, params_ptr_->max_new_features);
-		break;
-	default:
-		trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr, _des_ptr, _mat_ptr);
-		break;
-	}
+    // Initialize vars if necessary
+    if (!initialized_)
+        initAlg(_frame_buff.back()->getImage(), _det_ptr->getPatternRadius());
+
+    switch (_frame_buff.size())
+    {
+        case 0:
+            VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
+            break;
+        case 1:
+            detectNewFeatures(_frame_buff.back(), _det_ptr, _des_ptr, params_ptr_->max_new_features);
+            break;
+        default:
+            trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr, _des_ptr, _mat_ptr);
+            break;
+    }
 }
 
 void AlgorithmACTIVESEARCH::detectNewFeatures(FramePtr& _frame, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr, const int& max_new_features)
 {
-	KeyPointVector kps;
-	cv::Mat desc;
-	cv::Rect roi;
+    KeyPointVector kps;
+    cv::Mat desc;
+    cv::Rect roi;
 
     if (params_ptr_->draw_results)
-    	image_draw_ = _frame->getImage().clone();
-
-	for (unsigned int n_iterations = 0; max_new_features == 0 || n_iterations < max_new_features; n_iterations++)
-	{
-		// Pick a ROI to look for a feature in it
-		if (pickEmptyRoi(roi))
-		{
-		    // draw ROI
-//            if (params_ptr_->draw_results)
-//            	drawRoi(image_draw_, roi,  getName(), cv::Scalar(255,255,255));
-
-	    	// Detect features in ROI
-	    	kps = _det_ptr->detect(_frame->getImage(), roi);
-	       	desc = _des_ptr->getDescriptor(_frame->getImage(), kps);
-
-	       	if (kps.size() > 0)
-	       	{
-	       		// Keep best in cell
-	       		KeyPointVector list_keypoints = kps;
-
-	       		// cv::KeyPointsFilter keypoint_filter;
-	       		// keypoint_filter.retainBest(kps,1);
-	       		retainBest(kps,1);
-
-	       		// Check if point exist in list
-	       		int index = existsInKPVec(kps[0], list_keypoints, 1.0);
-
-	       		if(kps[0].response > params_ptr_->min_response_new_feature)
-	            {
-	       			// Keep feature
-	       			_frame->addKeyPoint(kps[0]);
-	       			_frame->addDescriptor(desc.row(index));
+        image_draw_ = _frame->getImage().clone();
+
+    for (unsigned int n_iterations = 0; max_new_features == 0 || n_iterations < max_new_features; n_iterations++)
+    {
+        // Pick a ROI to look for a feature in it
+        if (pickEmptyRoi(roi))
+        {
+            // draw ROI
+            //            if (params_ptr_->draw_results)
+            //            	drawRoi(image_draw_, roi,  getName(), cv::Scalar(255,255,255));
+
+            // Detect features in ROI
+            kps = _det_ptr->detect(_frame->getImage(), roi);
+            desc = _des_ptr->getDescriptor(_frame->getImage(), kps);
+
+            if (kps.size() > 0)
+            {
+                // Keep best in cell
+                KeyPointVector list_keypoints = kps;
+
+                // cv::KeyPointsFilter keypoint_filter;
+                // keypoint_filter.retainBest(kps,1);
+                retainBest(kps,1);
+
+                // Check if point exist in list
+                int index = existsInKPVec(kps[0], list_keypoints, 1.0);
+
+                if(kps[0].response > params_ptr_->min_response_new_feature)
+                {
+                    // Keep feature
+                    _frame->addKeyPoint(kps[0]);
+                    _frame->addDescriptor(desc.row(index));
 
                     // Hit cell
                     hitCell(kps[0]);
@@ -195,64 +196,64 @@ void AlgorithmACTIVESEARCH::detectNewFeatures(FramePtr& _frame, const DetectorBa
                     // Debug
                     if (params_ptr_->draw_results)
                     {
-                    	drawRoi(image_draw_, roi, getName(), cv::Scalar(50,255,0), 1, 0.1);
-                    	cv::circle(image_draw_, kps[0].pt, 5, cv::Scalar(255, 0, 100), -1, 8, 0);
+                        drawRoi(image_draw_, roi, getName(), cv::Scalar(50,255,0), 1, 0.1);
+                        cv::circle(image_draw_, kps[0].pt, 5, cv::Scalar(255, 0, 100), -1, 8, 0);
                     }
-	            }
-	        }
-	        else
-	        {
-            	// Block cell
-            	blockCell(roi);
-
-            	// Debug
+                }
+            }
+            else
+            {
+                // Block cell
+                blockCell(roi);
+
+                // Debug
                 if (params_ptr_->draw_results)
-                	drawRoi(image_draw_, roi, getName(), cv::Scalar(255,0,0), 1, 0.1);
-	        }
-	    }
+                    drawRoi(image_draw_, roi, getName(), cv::Scalar(255,0,0), 1, 0.1);
+            }
+        }
         else
             break;
-	}
+    }
 
     if (params_ptr_->draw_results)
     {
-    	cv::imshow(getName(), image_draw_);
-    	cv::waitKey(1);
+        cv::imshow(getName(), image_draw_);
+        cv::waitKey(1);
     }
 }
 
 void AlgorithmACTIVESEARCH::trackFrame(const FramePtr& _frame_old, FramePtr& _tracked_frame, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr, const MatcherBasePtr& _mat_ptr)
 {
-	// Start timer
-	clock_t tStart = clock();
+    // Start timer
+    clock_t tStart = clock();
 
     if (params_ptr_->draw_results)
-    	image_draw_ = _tracked_frame->getImage().clone();
+        image_draw_ = _tracked_frame->getImage().clone();
 
-	// Renew active ROI
-	renew();
+    // Renew active ROI
+    renew();
 
-	KeyPointVector target_feature = _frame_old->getKeyPoints();
-	cv::Mat target_desc = _frame_old->getDescriptors();
+    KeyPointVector target_feature = _frame_old->getKeyPoints();
+    cv::Mat target_desc = _frame_old->getDescriptors();
 
-	// Try to track all previous features
-	for(int ii=0; ii<target_feature.size(); ++ii)
+    // Try to track all previous features
+    for(int ii=0; ii<target_feature.size(); ++ii)
     {
-		// Hit cell in the position of the targeted kp
-		hitCell(target_feature[ii]);
+        // Hit cell in the position of the targeted kp
+        hitCell(target_feature[ii]);
 
-		// Set ROI
-		cv::Rect roi = setRoi(target_feature[ii].pt.x,target_feature[ii].pt.y, cell_size_(0), cell_size_(1));
+        // Set ROI
+        cv::Rect roi = setRoi(target_feature[ii].pt.x,target_feature[ii].pt.y, cell_size_(0), cell_size_(1));
 
-//        // draw ROI
-//		if (params_ptr_->draw_results)
-//			drawRoi(image_draw_, roi,  getName(), cv::Scalar(0,255,255));
+        //        // draw ROI
+        //		if (params_ptr_->draw_results)
+        //			drawRoi(image_draw_, roi,  getName(), cv::Scalar(0,255,255));
 
         // Detect features in ROI
-		KeyPointVector kps = _det_ptr->detect(_tracked_frame->getImage(), roi);
-		cv::Mat desc = _des_ptr->getDescriptor(_tracked_frame->getImage(), kps);
+        KeyPointVector kps = _det_ptr->detect(_tracked_frame->getImage(), roi);
+        cv::Mat desc = _des_ptr->getDescriptor(_tracked_frame->getImage(), kps);
 
-       	// If there are keypoints around the candidate ROI
+        // If there are keypoints around the candidate ROI
         if(kps.size() > 0)
         {
             // Match
@@ -262,8 +263,8 @@ void AlgorithmACTIVESEARCH::trackFrame(const FramePtr& _frame_old, FramePtr& _tr
             // If good match, keep feature
             if (normalized_score > _mat_ptr->getParams()->min_norm_score)
             {
-            	// introduce in list of tracked features
-            	cv::KeyPoint tracked_kp = kps[match_data.trainIdx];
+                // introduce in list of tracked features
+                cv::KeyPoint tracked_kp = kps[match_data.trainIdx];
                 cv::Mat tracked_desc = desc(cv::Rect(0,match_data.trainIdx,desc.cols,1));
                 _tracked_frame->addKeyPoint(tracked_kp);
                 _tracked_frame->addDescriptor(tracked_desc);
@@ -271,28 +272,28 @@ void AlgorithmACTIVESEARCH::trackFrame(const FramePtr& _frame_old, FramePtr& _tr
                 // Draw
                 if (params_ptr_->draw_results)
                 {
-                	cv::line(image_draw_, tracked_kp.pt, target_feature[ii].pt, cv::Scalar(0, 0, 255), 3);
-                	cv::circle(image_draw_, tracked_kp.pt, 5, cv::Scalar(255.0, 255.0, 0.0), -1, 8, 0);
-                	cv::putText(image_draw_, std::to_string(ii), tracked_kp.pt, cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
+                    cv::line(image_draw_, tracked_kp.pt, target_feature[ii].pt, cv::Scalar(0, 0, 255), 3);
+                    cv::circle(image_draw_, tracked_kp.pt, 5, cv::Scalar(255.0, 255.0, 0.0), -1, 8, 0);
+                    cv::putText(image_draw_, std::to_string(ii), tracked_kp.pt, cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
                 }
             }
         }
     }
 
-	// If not enough tracked features, add new ones
-	if (_tracked_frame->getNumFeatures() < params_ptr_->min_feat_track)
-		detectNewFeatures(_tracked_frame, _det_ptr, _des_ptr, params_ptr_->max_new_features - _tracked_frame->getNumFeatures());
-	else
-	{
-		if (params_ptr_->draw_results)
-		{
-			cv::imshow(getName(), image_draw_);
-			cv::waitKey(1);
-		}
-	}
-
-	// Get computation time
-	comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
+    // If not enough tracked features, add new ones
+    if (_tracked_frame->getNumFeatures() < params_ptr_->min_feat_track)
+        detectNewFeatures(_tracked_frame, _det_ptr, _des_ptr, params_ptr_->max_new_features - _tracked_frame->getNumFeatures());
+    else
+    {
+        if (params_ptr_->draw_results)
+        {
+            cv::imshow(getName(), image_draw_);
+            cv::waitKey(1);
+        }
+    }
+
+    // Get computation time
+    comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
 }
 
 
diff --git a/src/algorithms/anms/anms.cpp b/src/algorithms/anms/anms.cpp
index bcd28d40dad592936f2abce10800480eddd0c34b..0bf1c59124d234ecd342853bd2d9aa2588996085 100644
--- a/src/algorithms/anms/anms.cpp
+++ b/src/algorithms/anms/anms.cpp
@@ -197,17 +197,20 @@ vector<cv::KeyPoint> RangeTree(vector<cv::KeyPoint> keyPoints, int numRetPoints,
                 result.push_back(i);
                 int minx = keyPoints[i].pt.x-width; int maxx = keyPoints[i].pt.x+width; //defining square boundaries around the point
                 int miny= keyPoints[i].pt.y-width; int maxy= keyPoints[i].pt.y+width;
-                if (minx<0) minx = 0; if (miny<0) miny = 0;
+                if (minx<0) minx = 0;
+                if (miny<0) miny = 0;
 
                 std::vector<u16 *> *he = treeANMS.search(minx, maxx, miny, maxy);
-                for (unsigned int j=0; j<he->size();j++) if (Included[(u64) (*he)[j]]) Included[(u64) (*he)[j]] = false;
+                for (unsigned int j=0; j<he->size();j++)
+                    if (Included[(u64) (*he)[j]])
+                        Included[(u64) (*he)[j]] = false;
                 delete he;
                 he = NULL;
             }
         }
         if (result.size()>=Kmin && result.size()<=Kmax){ //solution found
-                ResultVec = result;
-                complete = true;
+            ResultVec = result;
+            complete = true;
         }
         else if (result.size()<Kmin) high = width-1; //update binary search range
         else low = width+1;
@@ -215,7 +218,8 @@ vector<cv::KeyPoint> RangeTree(vector<cv::KeyPoint> keyPoints, int numRetPoints,
     }
     // retrieve final keypoints
     vector<cv::KeyPoint> kp;
-    for (unsigned int i = 0; i<ResultVec.size(); i++) kp.push_back(keyPoints[ResultVec[i]]);
+    for (unsigned int i = 0; i<ResultVec.size(); i++)
+        kp.push_back(keyPoints[ResultVec[i]]);
 
     return kp;
 }
@@ -260,7 +264,7 @@ vector<int> Ssc(const vector<cv::KeyPoint>& keyPoints, const int& numRetPoints,
 
         for (unsigned int i=0;i<keyPoints.size();++i){
 
-        	int row = floor(keyPoints[i].pt.y/c); //get position of the cell current point is located at
+            int row = floor(keyPoints[i].pt.y/c); //get position of the cell current point is located at
             int col = floor(keyPoints[i].pt.x/c);
             if (coveredVec[row][col]==false){ // if the cell is not covered
                 result.push_back(i);
@@ -316,7 +320,6 @@ void Ssc(const vector<cv::KeyPoint>& keyPoints, vector<cv::KeyPoint>& keyPointsS
     }
 }
 
-
 void VisualizeAll(cv::Mat Image, vector<cv::KeyPoint> keyPoints, string figureTitle)
 {
     cv::Mat resultImg;
diff --git a/src/algorithms/opticalflowpyrlk/alg_opticalflowpyrlk.cpp b/src/algorithms/opticalflowpyrlk/alg_opticalflowpyrlk.cpp
index 7b0885e21190629151d634349f35a3d4615c8805..bcb7ee3adc1408ed843e033282a18c93558a6a61 100644
--- a/src/algorithms/opticalflowpyrlk/alg_opticalflowpyrlk.cpp
+++ b/src/algorithms/opticalflowpyrlk/alg_opticalflowpyrlk.cpp
@@ -7,49 +7,49 @@ namespace vision_utils {
 
 AlgorithmOPTFLOWPYRLK::AlgorithmOPTFLOWPYRLK(void)
 {
-	initialized_ = false;
+    initialized_ = false;
 }
 
 AlgorithmOPTFLOWPYRLK::~AlgorithmOPTFLOWPYRLK(void)
 {
     if (params_ptr_->draw_results)
-    	cv::destroyAllWindows();
+        cv::destroyAllWindows();
 }
 
 void AlgorithmOPTFLOWPYRLK::initAlg(void)
 {
-	if (params_ptr_->draw_results)
-	{
-		cv::startWindowThread();
-		cv::namedWindow(getName(), cv::WINDOW_NORMAL);
-	}
+    if (params_ptr_->draw_results)
+    {
+        cv::startWindowThread();
+        cv::namedWindow(getName(), cv::WINDOW_NORMAL);
+    }
 
     initialized_ = true;
 }
 void AlgorithmOPTFLOWPYRLK::run(Buffer<FramePtr>& _frame_buff, const DetectorBasePtr& _det_ptr)
 {
-	// Initialize vars if necessary
-	if (!initialized_)
-		initAlg();
-
-	switch (_frame_buff.size())
-	{
-	case 0:
-		VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
-		break;
-	case 1:
-		detectNewFeatures(_frame_buff.back(), _det_ptr);
-		break;
-	default:
-		trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr);
-		break;
-	}
+    // Initialize vars if necessary
+    if (!initialized_)
+        initAlg();
+
+    switch (_frame_buff.size())
+    {
+    case 0:
+        VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
+        break;
+    case 1:
+        detectNewFeatures(_frame_buff.back(), _det_ptr);
+        break;
+    default:
+        trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr);
+        break;
+    }
 }
 
 void AlgorithmOPTFLOWPYRLK::detectNewFeatures(FramePtr& _frame, const DetectorBasePtr& _det_ptr)
 {
     if (params_ptr_->draw_results)
-    	image_draw_ = _frame->getImage().clone();
+        image_draw_ = _frame->getImage().clone();
 
     // Convert to gray scale if necessary
     cv::Mat img_gray;
@@ -58,44 +58,44 @@ void AlgorithmOPTFLOWPYRLK::detectNewFeatures(FramePtr& _frame, const DetectorBa
     else
         img_gray = _frame->getImage().clone();
 
-	KeyPointVector kps_new;
-	cv::Mat desc_new;
-
-	if (_frame->getNumFeatures() > 0)
-	{
-		// Get features again
-		KeyPointVector kps = _det_ptr->detect(img_gray);
-
-		// Keep only new features
-		KeyPointVector tracked_kps = _frame->getKeyPoints();
-		std::vector<int> kps_idxs;
-		kps_new = differenceKPVec(tracked_kps, kps, kps_idxs);
-	}
-	else
-	{
-	    // Get full frame detections
-		kps_new = _det_ptr->detect(img_gray);
-	}
-	_frame->setKeyPoints(kps_new);
+    KeyPointVector kps_new;
+    cv::Mat desc_new;
+
+    if (_frame->getNumFeatures() > 0)
+    {
+        // Get features again
+        KeyPointVector kps = _det_ptr->detect(img_gray);
+
+        // Keep only new features
+        KeyPointVector tracked_kps = _frame->getKeyPoints();
+        std::vector<int> kps_idxs;
+        kps_new = differenceKPVec(tracked_kps, kps, kps_idxs);
+    }
+    else
+    {
+        // Get full frame detections
+        kps_new = _det_ptr->detect(img_gray);
+    }
+    _frame->setKeyPoints(kps_new);
 
     if (params_ptr_->draw_results)
     {
-    	drawKeyPoints(image_draw_, kps_new, 5, cv::Scalar(255,0,100), -1);
-    	cv::imshow(getName(), image_draw_);
-    	cv::waitKey(1);
+        drawKeyPoints(image_draw_, kps_new, 5, cv::Scalar(255,0,100), -1);
+        cv::imshow(getName(), image_draw_);
+        cv::waitKey(1);
     }
     frame_gray_prev_ = img_gray.clone();
 }
 
 void AlgorithmOPTFLOWPYRLK::trackFrame(const FramePtr& _frame_old, FramePtr& _tracked_frame, const DetectorBasePtr& _det_ptr)
 {
-	// Start timer
-	clock_t tStart = clock();
+    // Start timer
+    clock_t tStart = clock();
 
     if (params_ptr_->draw_results)
-    	image_draw_ = _tracked_frame->getImage().clone();
+        image_draw_ = _tracked_frame->getImage().clone();
 
-	// Convert to gray scale if necessary
+    // Convert to gray scale if necessary
     cv::Mat img_gray;
     if (_tracked_frame->getImage().channels() == 3)
         cv::cvtColor(_tracked_frame->getImage(), img_gray, CV_RGB2GRAY);
@@ -109,41 +109,41 @@ void AlgorithmOPTFLOWPYRLK::trackFrame(const FramePtr& _frame_old, FramePtr& _tr
 
     // Compute optical flow
     if (pts_prev.size() > 0)
-    	cv::calcOpticalFlowPyrLK(frame_gray_prev_, img_gray, pts_prev, pts_matched_in_frame, kpt_is_found, err, params_ptr_->win_size, params_ptr_->max_level, params_ptr_->criteria, params_ptr_->flags, params_ptr_->min_eig_threshold);
+        cv::calcOpticalFlowPyrLK(frame_gray_prev_, img_gray, pts_prev, pts_matched_in_frame, kpt_is_found, err, params_ptr_->win_size, params_ptr_->max_level, params_ptr_->criteria, params_ptr_->flags, params_ptr_->min_eig_threshold);
 
     //Draw lines connecting previous position and current position
     KeyPointVector good_kpts;
     for(size_t ii=0; ii<pts_matched_in_frame.size(); ii++)
     {
-    	if(kpt_is_found[ii] && err[ii] < params_ptr_->min_err_kpt_match)
-    	{
-    		cv::KeyPoint kp(pts_matched_in_frame[ii], CV_32F);
-    		good_kpts.push_back(kp);
-    		cv::circle(image_draw_, pts_matched_in_frame[ii], 5, cv::Scalar(255.0, 255.0, 0.0), -1);
-    		cv::line(image_draw_, pts_prev[ii], pts_matched_in_frame[ii], cv::Scalar(0, 0, 255), 3);
-        	cv::putText(image_draw_, std::to_string(ii), pts_matched_in_frame[ii], cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
-    	}
+        if(kpt_is_found[ii] && err[ii] < params_ptr_->min_err_kpt_match)
+        {
+            cv::KeyPoint kp(pts_matched_in_frame[ii], CV_32F);
+            good_kpts.push_back(kp);
+            cv::circle(image_draw_, pts_matched_in_frame[ii], 5, cv::Scalar(255.0, 255.0, 0.0), -1);
+            cv::line(image_draw_, pts_prev[ii], pts_matched_in_frame[ii], cv::Scalar(0, 0, 255), 3);
+            cv::putText(image_draw_, std::to_string(ii), pts_matched_in_frame[ii], cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
+        }
     }
     // Update
     _tracked_frame->setKeyPoints(good_kpts);
 
-	// If not enough tracked features, add new ones
+    // If not enough tracked features, add new ones
     if (_tracked_frame->getNumFeatures() < params_ptr_->min_feat_track)
-		detectNewFeatures(_tracked_frame, _det_ptr);
+        detectNewFeatures(_tracked_frame, _det_ptr);
     else
     {
-    	// Draw
-    	if (params_ptr_->draw_results)
-    	{
-    		cv::imshow(getName(), image_draw_);
-    		cv::waitKey(1);
-    	}
+        // Draw
+        if (params_ptr_->draw_results)
+        {
+            cv::imshow(getName(), image_draw_);
+            cv::waitKey(1);
+        }
     }
 
-	frame_gray_prev_ = img_gray.clone();
+    frame_gray_prev_ = img_gray.clone();
 
-	// Get computation time
-	comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
+    // Get computation time
+    comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
 }
 
 } /* namespace vision_utils */
diff --git a/src/algorithms/trackfeatures/alg_trackfeatures.cpp b/src/algorithms/trackfeatures/alg_trackfeatures.cpp
index add44d85cc6250eaa71224daabb283821a9c5234..37078abb7c641869f03e5686e600b86aa7f3362f 100644
--- a/src/algorithms/trackfeatures/alg_trackfeatures.cpp
+++ b/src/algorithms/trackfeatures/alg_trackfeatures.cpp
@@ -4,109 +4,109 @@ namespace vision_utils {
 
 AlgorithmTRACKFEATURES::AlgorithmTRACKFEATURES(void)
 {
-	initialized_ = false;
+    initialized_ = false;
 }
 
 AlgorithmTRACKFEATURES::~AlgorithmTRACKFEATURES(void)
 {
     if (params_ptr_->draw_results)
-    	cv::destroyAllWindows();
+        cv::destroyAllWindows();
 }
 
 void AlgorithmTRACKFEATURES::initAlg(void)
 {
-	if (params_ptr_->draw_results)
-	{
-		cv::startWindowThread();
-		cv::namedWindow(getName(), cv::WINDOW_NORMAL);
-	}
+    if (params_ptr_->draw_results)
+    {
+        cv::startWindowThread();
+        cv::namedWindow(getName(), cv::WINDOW_NORMAL);
+    }
 
     initialized_ = true;
 }
 
 void AlgorithmTRACKFEATURES::run(Buffer<FramePtr>& _frame_buff, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr, const MatcherBasePtr& _mat_ptr)
 {
-	// Initialize vars if necessary
-	if (!initialized_)
-		initAlg();
-
-	switch (_frame_buff.size())
-	{
-	case 0:
-		VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
-		break;
-	case 1:
-		detectNewFeatures(_frame_buff.back(), _det_ptr, _des_ptr);
-		break;
-	default:
-		trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr, _des_ptr, _mat_ptr);
-		break;
-	}
+    // Initialize vars if necessary
+    if (!initialized_)
+        initAlg();
+
+    switch (_frame_buff.size())
+    {
+    case 0:
+        VU_ERROR("Trying to track an empty buffer. Please, at least insert one image in the buffer.");
+        break;
+    case 1:
+        detectNewFeatures(_frame_buff.back(), _det_ptr, _des_ptr);
+        break;
+    default:
+        trackFrame(_frame_buff[_frame_buff.size()-2], _frame_buff.back(), _det_ptr, _des_ptr, _mat_ptr);
+        break;
+    }
 }
 
 void AlgorithmTRACKFEATURES::detectNewFeatures(FramePtr& _frame, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr)
 {
     if (params_ptr_->draw_results)
-    	image_draw_ = _frame->getImage().clone();
-
-	KeyPointVector kps_new;
-	cv::Mat desc_new;
-
-	if (_frame->getNumFeatures() > 0)
-	{
-		// Get features again
-		KeyPointVector kps = _det_ptr->detect(_frame->getImage());
-		cv::Mat desc = _des_ptr->getDescriptor( _frame->getImage(), kps);
-
-		// Keep only new features
-		std::vector<int> idxs_new;
-		KeyPointVector tracked_kps = _frame->getKeyPoints();
-		kps_new = differenceKPVec(tracked_kps, kps, idxs_new);
-		for (int ii=0;ii<idxs_new.size();++ii)
-			desc_new.push_back( desc.row(idxs_new[ii]) );
-	}
-	else
-	{
-	    // Get full frame detections and descriptors
-		kps_new = _det_ptr->detect(_frame->getImage());
-		desc_new = _des_ptr->getDescriptor( _frame->getImage(), kps_new);
-	}
-	_frame->addKeyPoints(kps_new);
-	_frame->addDescriptors(desc_new);
+        image_draw_ = _frame->getImage().clone();
+
+    KeyPointVector kps_new;
+    cv::Mat desc_new;
+
+    if (_frame->getNumFeatures() > 0)
+    {
+        // Get features again
+        KeyPointVector kps = _det_ptr->detect(_frame->getImage());
+        cv::Mat desc = _des_ptr->getDescriptor( _frame->getImage(), kps);
+
+        // Keep only new features
+        std::vector<int> idxs_new;
+        KeyPointVector tracked_kps = _frame->getKeyPoints();
+        kps_new = differenceKPVec(tracked_kps, kps, idxs_new);
+        for (int ii=0;ii<idxs_new.size();++ii)
+            desc_new.push_back( desc.row(idxs_new[ii]) );
+    }
+    else
+    {
+        // Get full frame detections and descriptors
+        kps_new = _det_ptr->detect(_frame->getImage());
+        desc_new = _des_ptr->getDescriptor( _frame->getImage(), kps_new);
+    }
+    _frame->addKeyPoints(kps_new);
+    _frame->addDescriptors(desc_new);
 
     if (params_ptr_->draw_results)
     {
-    	drawKeyPoints(image_draw_, kps_new, 5, cv::Scalar(255,0,100), -1);
-    	cv::imshow(getName(), image_draw_);
-    	cv::waitKey(1);
+        drawKeyPoints(image_draw_, kps_new, 5, cv::Scalar(255,0,100), -1);
+        cv::imshow(getName(), image_draw_);
+        cv::waitKey(1);
     }
 }
 
 void AlgorithmTRACKFEATURES::trackFrame(const FramePtr& _frame_old, FramePtr& _tracked_frame, const DetectorBasePtr& _det_ptr, const DescriptorBasePtr& _des_ptr, const MatcherBasePtr& _mat_ptr)
 {
-	// Start timer
-	clock_t tStart = clock();
+    // Start timer
+    clock_t tStart = clock();
 
     if (params_ptr_->draw_results)
-    	image_draw_ = _tracked_frame->getImage().clone();
+        image_draw_ = _tracked_frame->getImage().clone();
 
     KeyPointVector target_kps = _frame_old->getKeyPoints();
     cv::Mat target_desc = _frame_old->getDescriptors();
 
-	for(int ii = 1; ii < target_kps.size(); ++ii)
+    for(int ii = 1; ii < target_kps.size(); ++ii)
     {
         // Set a candidate ROI around the target feature
-		cv::Rect roi = setRoi(target_kps[ii].pt.x, target_kps[ii].pt.y, params_ptr_->target_roi_height, params_ptr_->target_roi_width);
+        cv::Rect roi = setRoi(target_kps[ii].pt.x, target_kps[ii].pt.y, params_ptr_->target_roi_height, params_ptr_->target_roi_width);
 
 //        // draw ROI
-//       	if (params_ptr_->draw_results)
-//       		drawRoi(image_draw_, roi, getName(), cv::Scalar(0,255,255));
+//           if (params_ptr_->draw_results)
+//               drawRoi(image_draw_, roi, getName(), cv::Scalar(0,255,255));
 
-    	// Detect features in ROI
-       	KeyPointVector kps = _det_ptr->detect(_tracked_frame->getImage(), roi);
-       	cv::Mat desc = _des_ptr->getDescriptor(_tracked_frame->getImage(), kps);
+        // Detect features in ROI
+           KeyPointVector kps = _det_ptr->detect(_tracked_frame->getImage(), roi);
+           cv::Mat desc = _des_ptr->getDescriptor(_tracked_frame->getImage(), kps);
 
-       	// If there are keypoints aroud the candidate ROI
+           // If there are keypoints aroud the candidate ROI
         if(kps.size() > 0)
         {
             // Match
@@ -116,36 +116,36 @@ void AlgorithmTRACKFEATURES::trackFrame(const FramePtr& _frame_old, FramePtr& _t
             // If good match, keep feature
             if (normalized_score > _mat_ptr->getParams()->min_norm_score)
             {
-            	// introduce in list of tracked features
-            	cv::KeyPoint tracked_kp = kps[match_data.trainIdx];
+                // introduce in list of tracked features
+                cv::KeyPoint tracked_kp = kps[match_data.trainIdx];
                 cv::Mat tracked_desc = desc(cv::Rect(0,match_data.trainIdx,desc.cols,1));
                 _tracked_frame->addKeyPoint(tracked_kp);
                 _tracked_frame->addDescriptor(tracked_desc);
                 // Draw
                 if (params_ptr_->draw_results)
                 {
-                	cv::line(image_draw_, tracked_kp.pt, target_kps[ii].pt, cv::Scalar(0, 0, 255), 3);
-                	cv::circle(image_draw_, tracked_kp.pt, 5, cv::Scalar(255.0, 255.0, 0.0), -1, 8, 0);
-                	cv::putText(image_draw_, std::to_string(ii), tracked_kp.pt, cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
+                    cv::line(image_draw_, tracked_kp.pt, target_kps[ii].pt, cv::Scalar(0, 0, 255), 3);
+                    cv::circle(image_draw_, tracked_kp.pt, 5, cv::Scalar(255.0, 255.0, 0.0), -1, 8, 0);
+                    cv::putText(image_draw_, std::to_string(ii), tracked_kp.pt, cv:: FONT_HERSHEY_SIMPLEX, 0.4, cv::Scalar(0, 0, 0));
                 }
             }
         }
     }
 
-	// If not enough tracked features, add new ones
-	if (_tracked_frame->getNumFeatures() < params_ptr_->min_feat_track)
-		detectNewFeatures(_tracked_frame, _det_ptr, _des_ptr);
-	else
-	{
-		if (params_ptr_->draw_results)
-		{
-			cv::imshow(getName(), image_draw_);
-			cv::waitKey(1);
-		}
-	}
-
-	// Get computation time
-	comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
+    // If not enough tracked features, add new ones
+    if (_tracked_frame->getNumFeatures() < params_ptr_->min_feat_track)
+        detectNewFeatures(_tracked_frame, _det_ptr, _des_ptr);
+    else
+    {
+        if (params_ptr_->draw_results)
+        {
+            cv::imshow(getName(), image_draw_);
+            cv::waitKey(1);
+        }
+    }
+
+    // Get computation time
+    comp_time_ = (double)(clock() - tStart) / CLOCKS_PER_SEC;
 }
 
 } /* namespace vision_utils */