diff --git a/README.md b/README.md
index 0e8f78685129c3523cd49bc33a308d6c83b76aa3..b9bebbcb9c3ee4a29d1328777631137c15564681 100644
--- a/README.md
+++ b/README.md
@@ -4,22 +4,22 @@ A C++ Toolbox with utilities for 2D laser scan processing, made at IRI (www.iri.
 
 Clone the repository in your chosen directory. In a terminal:
 
-```
+```sh
 cd <your/path>
 git clone <repo-link>
 ```
 
 Create a directory to build all the source files:
-```
-$ mkdir build
-$ cd build
+```sh
+mkdir build
+cd build
 ```
 
 Compile the source files:
 
-```
-$ cmake ..
-$ make
+```sh
+cmake ..
+make
 ```
 
 ## Optional dependencies
@@ -27,7 +27,7 @@ $ make
 **Canonical Scan Matching - CSM**
 
 To enable the compilation of iterative closest point algorithms, [CSM](https://github.com/AndreaCensi/csm) should be installed. Clone, compile and install:
-```
+```sh
 cd <your/path>
 git clone https://github.com/AndreaCensi/csm.git
 cd csm
@@ -37,6 +37,27 @@ sudo make install
 ```
 
 CSM depends on GSL that you probably have installed already. To install it: 
-```
+```sh
 sudo apt install libgsl-dev
-```
\ No newline at end of file
+```
+
+**FALKO Library - falkolib**
+
+Loop closure search is implemented using [FALKO Library](https://gitlab.iri.upc.edu/mobile_robotics/falkolib). In order to download, compile and install it:
+```sh
+cd <your/path>
+git clone https://gitlab.iri.upc.edu/mobile_robotics/falkolib.git
+cd falkolib
+mkdir build
+cd build
+cmake ..
+make
+sudo make install
+```
+
+To change the install directory you must set cmake environment
+variable `${CMAKE_INSTALL_PREFIX}` (e.g. using command `ccmake ..`
+before calling `cmake ..`). 
+Its default value on UNIX-like/Linux systems is "/usr/local".
+The `sudo` is required only if `${CMAKE_INSTALL_PREFIX}`
+is a system diretory managed by administrator user root.
diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt
index 5a9977bbaa8efa7dc7562350ae99b61200b54f8a..d7d87c33825737b1bead260c87758fb7950dea16 100644
--- a/src/CMakeLists.txt
+++ b/src/CMakeLists.txt
@@ -12,6 +12,7 @@ ENDIF(faramotics_FOUND)
 
 FIND_PACKAGE(Eigen3 3.3 REQUIRED)
 FIND_PACKAGE(csm QUIET)
+FIND_PACKAGE(falkolib QUIET)
 
 #include directories
 INCLUDE_DIRECTORIES(. /usr/local/include)
@@ -22,6 +23,15 @@ ENDIF(csm_FOUND)
 IF(faramotics_FOUND)
     INCLUDE_DIRECTORIES(${faramotics_INCLUDE_DIRS})
 ENDIF(faramotics_FOUND)
+IF(falkolib_FOUND)
+  MESSAGE(STATUS "FALKO lib found:")
+  MESSAGE(STATUS "  falkolib_INCLUDE_DIRS ${falkolib_INCLUDE_DIRS}")
+  MESSAGE(STATUS "  falkolib_LIBRARY_DIRS ${falkolib_LIBRARY_DIRS}")
+  MESSAGE(STATUS "  falkolib_LIBRARIES ${falkolib_LIBRARIES}")
+  add_definitions(-DEIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT)
+  INCLUDE_DIRECTORIES(${falkolib_INCLUDE_DIRS})
+  LINK_DIRECTORIES(${falkolib_LIBRARY_DIRS})
+ENDIF(falkolib_FOUND)
 
 #headers
 SET(HDRS_BASE
@@ -43,12 +53,23 @@ SET(HDRS
     point_set.h
     polyline.h
     scan_segment.h
+    loop_closure_base.h
+    scene_base.h
+    
     )
   IF(csm_FOUND)
     SET(HDRS ${HDRS}
       icp.h)
   ENDIF(csm_FOUND)
 
+  IF(falkolib_FOUND)
+    SET(HDRS ${HDRS}
+      corner_falko_2d.h
+      loop_closure_falko.h
+      scene_falko.h
+      match_loop_closure_scene.h)
+  ENDIF(falkolib_FOUND)
+
 #sources
 SET(SRCS
     corner_finder.cpp
@@ -71,6 +92,13 @@ SET(SRCS
     SET(SRCS ${SRCS}
       icp.cpp)
   ENDIF(csm_FOUND)
+
+  IF(falkolib_FOUND)
+    SET(SRCS ${SRCS}
+      corner_falko_2d.cpp)
+  ENDIF(falkolib_FOUND)
+
+
   
 # create the shared library
 ADD_LIBRARY(${PROJECT_NAME} SHARED ${SRCS})
@@ -78,6 +106,10 @@ IF(csm_FOUND)
   target_link_libraries(${PROJECT_NAME} ${csm_LIBRARY})
 ENDIF(csm_FOUND)
 
+IF(falkolib_FOUND)
+  target_link_libraries(${PROJECT_NAME} ${falkolib_LIBRARY})
+ENDIF(falkolib_FOUND)
+
 # Examples
 IF(BUILD_DEMOS)
   MESSAGE("Building examples.")
diff --git a/src/corner_falko_2d.cpp b/src/corner_falko_2d.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..edce4b95f518ede523c5a6278a4d5c78a1f8683f
--- /dev/null
+++ b/src/corner_falko_2d.cpp
@@ -0,0 +1,121 @@
+/**
+ * \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
new file mode 100644
index 0000000000000000000000000000000000000000..89513e679a909bf1fbd75726e608aae446b3fa6f
--- /dev/null
+++ b/src/corner_falko_2d.h
@@ -0,0 +1,119 @@
+/**
+ * \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 005644f61512355f277bb90bb567f45a8acf60d1..63e4efbb4ef743ab976b5a505826cb99099c0058 100644
--- a/src/examples/CMakeLists.txt
+++ b/src/examples/CMakeLists.txt
@@ -2,4 +2,4 @@ INCLUDE_DIRECTORIES(../src)
 
 # polylines demo
 ADD_EXECUTABLE(demo_polylines polyline_demo.cpp)
-TARGET_LINK_LIBRARIES(demo_polylines ${PROJECT_NAME})
\ No newline at end of file
+TARGET_LINK_LIBRARIES(demo_polylines ${PROJECT_NAME})
diff --git a/src/laser_scan.cpp b/src/laser_scan.cpp
index 3747de309ea2c1b26b6f7fbe8894217fb2d26991..398e859f9437d3244c48bf3817eb115836dc7f88 100644
--- a/src/laser_scan.cpp
+++ b/src/laser_scan.cpp
@@ -102,14 +102,13 @@ void LaserScan::ranges2xy(const LaserScanParams& _scan_params, Eigen::Matrix4s _
     {
         //check raw range integrity
 		//invalid range
-        if (!isValidRange(ranges_raw_[ii], _scan_params))
+        if (isValidRange(ranges_raw_[ii], _scan_params))
         {
             //set as valid range
             ranges_[ii] = ranges_raw_[ii];
 
             //transform the laser hit from polar to 3D euclidean homogeneous
             point_laser << ranges_[ii] * cos(azimuth), ranges_[ii] * sin(azimuth), 0, 1;
-
             //apply device mounting point calibration (p_r = T * p_l)
             point_ref = _device_T * point_laser;
 
diff --git a/src/loop_closure_base.cpp b/src/loop_closure_base.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..687cefdf826db8ee6cf6c27c7380c0379358b5a4
--- /dev/null
+++ b/src/loop_closure_base.cpp
@@ -0,0 +1,26 @@
+/**
+ * \file loop_closure_base_2d.h
+ *
+ *  Created on: Feb 9, 2021
+ *      \author: spujol
+ */
+
+#include "loop_closure_base.h"
+
+namespace laserscanutils {
+
+loopClosureBase2d::loopClosureBase2d() {}
+loopClosureBase2d::~loopClosureBase2d() {}
+/*
+    std::shared_ptr<cornerScene> loopClosureBase2d::extractScene(LaserScan
+   &scan,LaserScanParams &scanParams){
+
+        auto NewScene=std::make_shared<cornerScene>();
+
+        return NewScene;
+    }
+*/
+
+// void findLoopClosure(std::list<cornerScene>& scenes, const cornerScene
+// newScene){}
+}
diff --git a/src/loop_closure_base.h b/src/loop_closure_base.h
new file mode 100644
index 0000000000000000000000000000000000000000..b9fcd991852aac7d21d984de1963ad6206600f23
--- /dev/null
+++ b/src/loop_closure_base.h
@@ -0,0 +1,68 @@
+/**
+ * \file loop_closure_base_2d.h
+ *
+ *  Created on: Feb 9, 2021
+ *      \author: spujol
+ */
+
+#ifndef LOOP_CLOSURE_BASE_2D_H_
+#define LOOP_CLOSURE_BASE_2D_H_
+
+#include <fstream>
+#include <iostream>
+#include <memory>
+
+/**************************
+ *      laser_scan_utils includes     *
+ **************************/
+#include "laser_scan.h"
+#include "match_loop_closure_scene.h"
+#include "scene_base.h"
+
+namespace laserscanutils {
+
+/** \brief A 2base class for loop closure using falko library
+ */
+class LoopClosureBase2d
+{
+  private:
+  public:
+    /** \brief Constructor
+     **/
+    LoopClosureBase2d(){};
+
+    /** \brief Destructor
+     **/
+    ~LoopClosureBase2d(){};
+
+    /** \brief update the scene struct with keypoints and descriptors
+     **/
+    virtual sceneBasePtr extractScene(const LaserScan &scan, const LaserScanParams &scanParams) = 0;
+
+    /** \brief Create and update a matchLoopClosure struct with the info that is
+     *produced when matching two given scenes
+     **/
+    virtual MatchLoopClosureScenePtr matchScene(sceneBasePtr _scene1, sceneBasePtr _scene2) = 0;
+
+    /** \brief It matches a target scene against a list of references scenes in order to find loop
+     * closures
+     **/
+    virtual std::map<double, MatchLoopClosureScenePtr> findLoopClosure(std::list<std::shared_ptr<SceneBase>> _l_scenes,
+                                                                       const sceneBasePtr                    _new_scene)
+    {
+        std::map<double, MatchLoopClosureScenePtr> matchings;
+        for (auto ref_scene : _l_scenes)
+            {
+                auto match = matchScene(ref_scene, _new_scene);
+                
+                while (matchings.find(match->score)!=matchings.end())
+                    match->score+=0.001;
+
+                matchings.emplace(match->score, match);
+            }
+        return matchings;
+    }
+};
+} /* namespace laserscanutils */
+
+#endif /* LOOP_CLOSURE_BASE_2D_H_ */
diff --git a/src/loop_closure_falko.h b/src/loop_closure_falko.h
new file mode 100644
index 0000000000000000000000000000000000000000..23a5def98a07998a078f93673e58b559c91b02ba
--- /dev/null
+++ b/src/loop_closure_falko.h
@@ -0,0 +1,523 @@
+/**
+ * \file loop_closure_base_2d.h
+ *
+ *  Created on: Feb 9, 2021
+ *      \author: spujol
+ */
+
+#ifndef LOOP_CLOSURE_FALKO_H_
+#define LOOP_CLOSURE_FALKO_H_
+
+#include <fstream>
+#include <iostream>
+#include <iterator>
+#include <list>
+#include <math.h>
+#include <memory>
+
+/**************************
+ *      laser_scan_utils includes     *
+ **************************/
+#include "laser_scan.h"
+#include "loop_closure_base.h"
+#include "match_loop_closure_scene.h"
+#include "scene_falko.h"
+
+/**************************
+ *      Falko includes      *
+ **************************/
+
+#include <falkolib/Matching/AHTMatcher.h>
+#include <falkolib/Matching/NNMatcher.h>
+
+namespace laserscanutils {
+
+typedef falkolib::BSCExtractor<falkolib::FALKO> bscExtractor;
+typedef falkolib::CGHExtractor<falkolib::FALKO> cghExtractor;
+
+template <typename T, typename D> using nn_matcher  = falkolib::NNMatcher<T, D>;
+template <typename T, typename D> using aht_matcher = falkolib::AHTMatcher<T, D>;
+
+/** \brief Struct class that store falkolib parameters
+ **/
+struct ParameterLoopClosureFalko
+{
+    // Keypoints extractor Default
+    double min_extraction_range_ = 0;
+    double max_extraction_range_ = 30;
+    bool   enable_subbeam_       = false;
+    double nms_radius_           = 0.1;
+    double neigh_b_              = 0.01;
+    double b_ratio_              = 4;
+    int    grid_sectors_         = 16;
+
+    // Descriptors parameters Default
+    int circularSectorNumber_ = 16;
+    int radialRingNumber_     = 8;
+
+    // matcher threshold Default
+    double matcher_distance_th_ = 0.2;
+    int    keypoints_number_th_ = 5;
+    bool   use_descriptors_     = 1; // match_type=1-> uses keypoints and descriptors
+                                     // match_type=0-> uses only keypoints
+
+    // matching
+    double matcher_ddesc_th_ = 0.2;
+    // aht matcher
+    double xRes_        = 0.15;
+    double yRes_        = 0.15;
+    double thetaRes_    = 0.1;
+    double xAbsMax_     = 3;
+    double yAbsMax_     = 3;
+    double thetaAbsMax_ = 3;
+};
+
+/** \brief A class for loop closure using falko library
+ *
+ * The class is a wrapper of the falkolib that is designed to be used for loop closures in the wolf problem
+ *
+ * It extracts scenes from a laserscanutils::LaserScan. The scenes contain keypoints and descriptors
+ *
+ * It matches a target scene against a list of reference scenes.
+ *
+ * The reference scenes are found from a search of the previous captures
+ *
+ * Diferent types of descriptors can be used, and are specified as template parameters.
+ *
+ * \tparam D Descriptor type. <bsc> or <cgh>
+ * \tparam Extr descriptor extractor type <bscExtractor> or <cghExtractor>
+ * \tparam M Matcher type <nn_matcher> or <aht_matcher>
+ * \param _param parameter struct with falko lib parameters
+ **/
+
+template <typename D, typename Extr, template <typename, typename> typename M>
+class LoopClosureFalko : public LoopClosureBase2d, public falkolib::FALKOExtractor
+{
+  public:
+    typedef std::shared_ptr<SceneFalko<D>>       sceneFalkoBSCPtr;
+    typedef std::shared_ptr<falkolib::LaserScan> laserScanPtr;
+
+    Extr                  extractor_;
+    M<falkolib::FALKO, D> matcher_;
+
+    /** \brief Constructor
+     * \param _param parameter struct with falko lib parameters
+     **/
+    LoopClosureFalko(ParameterLoopClosureFalko _param, const M<falkolib::FALKO, D> &_matcher)
+        : LoopClosureBase2d()
+        , falkolib::FALKOExtractor()
+        , extractor_(_param.circularSectorNumber_, _param.radialRingNumber_)
+        , matcher_(_matcher)
+    {
+        // FALKO Extractor Parameters
+        setMinExtractionRange(_param.min_extraction_range_);
+        setMaxExtractionRange(_param.max_extraction_range_);
+        enableSubbeam(_param.enable_subbeam_);
+        setNMSRadius(_param.nms_radius_);
+        setNeighB(_param.neigh_b_);
+        setBRatio(_param.b_ratio_);
+        setGridSectors(_param.grid_sectors_);
+
+        // Matcher Extractor Parameters
+        matcher_.setDistanceThreshold(_param.matcher_distance_th_);
+        matcher_.setDescriptorThreshold(_param.matcher_ddesc_th_);
+        keypoints_number_th_ = _param.keypoints_number_th_;
+        use_descriptors_     = _param.use_descriptors_;
+    };
+
+    /** \brief Destructor
+     **/
+    ~LoopClosureFalko() {}
+
+    /** \brief Create and update the scene struct with keypoints and descriptors
+     **/
+    sceneBasePtr extractScene(const LaserScan &_scan, const LaserScanParams &_scan_params) override
+    {
+        auto new_scene  = std::make_shared<SceneFalko<D>>();
+        auto scan_falko = convert2LaserScanFALKO(_scan, _scan_params);
+        // Extract KEYPOINTS
+        std::vector<falkolib::FALKO> keypoints_list;
+        extract(*scan_falko, keypoints_list);
+
+        double angle_min  = _scan_params.angle_min_;
+        double angle_step = _scan_params.angle_step_;
+
+        // Compute KEYPOINTS max_dist
+        new_scene->max_distance_ = 0;
+        for (int i = 0; i < keypoints_list.size(); i++)
+            for (int j = 0; j < keypoints_list.size(); j++)
+                {
+                    double X_dist   = fabs(keypoints_list[i].point[0] - keypoints_list[j].point[0]);
+                    double Y_dist   = fabs(keypoints_list[i].point[1] - keypoints_list[j].point[1]);
+                    double distance = sqrt((X_dist * X_dist) + (Y_dist * Y_dist));
+                    if (distance > new_scene->max_distance_)
+                        new_scene->max_distance_ = distance;
+                }
+
+        // discard too close by KEYPOINTS
+        for (int i = 0; i < keypoints_list.size(); i++)
+            {
+                int repeated = 0;
+                for (int j = i + 1; j < keypoints_list.size(); j++)
+                    {
+                        double X_dist   = fabs(keypoints_list[i].point[0] - keypoints_list[j].point[0]);
+                        double Y_dist   = fabs(keypoints_list[i].point[1] - keypoints_list[j].point[1]);
+                        double distance = sqrt((X_dist * X_dist) + (Y_dist * Y_dist));
+                        if (distance < 0.03)
+                            {
+                                repeated = 1;
+                            }
+                    }
+                if (repeated == 0)
+                    {
+                        new_scene->keypoints_list_.push_back(keypoints_list[i]);
+                    }
+            }
+
+        // Compute DESCRIPTORS
+        extractor_.compute(*scan_falko, new_scene->keypoints_list_, new_scene->descriptors_list_);
+        std::vector<D> descriptors_list_rotated;
+        extractor_.compute(*scan_falko, new_scene->keypoints_list_, descriptors_list_rotated);
+
+        // Compute KEYPOINTS Scene mid point, angle for each keypoint and rotate descriptors
+        Eigen::Vector2d     mid_point(0, 0);
+        std::vector<double> angle_rotation;
+        for (int i = 0; i < new_scene->keypoints_list_.size(); i++)
+            {
+                mid_point[0] = mid_point[0] + new_scene->keypoints_list_[i].point[0];
+                mid_point[1] = mid_point[1] + new_scene->keypoints_list_[i].point[1];
+                angle_rotation.push_back(angle_min + angle_step * new_scene->keypoints_list_[i].index);
+                double orientation = angle_rotation[i];
+                descriptors_list_rotated[i].rotate(orientation);
+                new_scene->descriptors_list_rotated.push_back(descriptors_list_rotated[i]);
+            }
+
+        new_scene->mid_point_ = mid_point / new_scene->keypoints_list_.size();
+        // Compute KEYPOINTS Area and Perimeter
+        int    n = 3;
+        double X[n];
+        double Y[n];
+        new_scene->perimeter_ = 0.0;
+        new_scene->area_      = 0.0;
+        Eigen::Vector2d dist_between_two_kp;
+
+        if (new_scene->keypoints_list_.size() < 3)
+            return new_scene;
+
+        if (new_scene->keypoints_list_.size() < 4)
+            {
+                X[0] = new_scene->keypoints_list_[0].point[0];
+                Y[0] = new_scene->keypoints_list_[0].point[1];
+
+                X[1] = new_scene->keypoints_list_[1].point[0];
+                Y[1] = new_scene->keypoints_list_[1].point[1];
+
+                X[2] = new_scene->keypoints_list_[2].point[0];
+                Y[2] = new_scene->keypoints_list_[2].point[1];
+
+                new_scene->area_ = new_scene->area_ + triangleArea(X, Y, n);
+                return new_scene;
+            }
+
+        for (int i = 0; i < new_scene->keypoints_list_.size(); i++)
+            {
+                X[0] = new_scene->mid_point_[0];
+                Y[0] = new_scene->mid_point_[1];
+
+                X[1] = new_scene->keypoints_list_[i].point[0];
+                Y[1] = new_scene->keypoints_list_[i].point[1];
+
+                if (i < new_scene->keypoints_list_.size() - 1) // Proceed until final keypoint
+                    {
+                        X[2] = new_scene->keypoints_list_[i + 1].point[0];
+                        Y[2] = new_scene->keypoints_list_[i + 1].point[1];
+
+                        dist_between_two_kp =
+                            new_scene->keypoints_list_[i].point - new_scene->keypoints_list_[i + 1].point;
+                    }
+                else // if you arrived to the final keypoint then use inital keypoint
+                    {
+                        X[2] = new_scene->keypoints_list_[0].point[0];
+                        Y[2] = new_scene->keypoints_list_[0].point[1];
+
+                        dist_between_two_kp = new_scene->keypoints_list_[i].point - new_scene->keypoints_list_[0].point;
+                    }
+                new_scene->area_      = new_scene->area_ + (double)triangleArea(X, Y, n);
+                new_scene->perimeter_ = new_scene->perimeter_ + hypot(dist_between_two_kp[0], dist_between_two_kp[1]);
+            }
+
+        // Compue KEYPOINTS Scene linear regresion and initial angle
+        double ss_xy = 0;
+        double ss_xx = 0;
+        for (int i = 0; i <= new_scene->keypoints_list_.size(); i++)
+            {
+                ss_xy += (new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0]) *
+                         (new_scene->keypoints_list_[i].point[1] - new_scene->mid_point_[1]);
+                ss_xx += (new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0]) *
+                         (new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0]);
+            }
+        double b_1 = ss_xy / ss_xx;
+
+        double initial_angle = -atan(b_1);
+
+        // rotate KEYPOINTS
+        for (int i = 0; i < new_scene->keypoints_list_.size(); i++)
+            {
+                falkolib::FALKO keypoint_mid;
+                keypoint_mid = new_scene->keypoints_list_[i];
+
+                keypoint_mid.point[0] = new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0];
+                keypoint_mid.point[1] = new_scene->keypoints_list_[i].point[1] - new_scene->mid_point_[1];
+                new_scene->keypoints_list_mid_point_.push_back(keypoint_mid);
+
+                falkolib::FALKO keypoint_rotated;
+                keypoint_rotated          = new_scene->keypoints_list_[i];
+                keypoint_rotated.point[0] = new_scene->keypoints_list_[i].point[0] * cos(initial_angle) -
+                                            new_scene->keypoints_list_[i].point[1] * sin(initial_angle);
+                keypoint_rotated.point[1] = new_scene->keypoints_list_[i].point[0] * sin(initial_angle) +
+                                            new_scene->keypoints_list_[i].point[1] * cos(initial_angle);
+                new_scene->keypoints_list_rotated_.push_back(keypoint_rotated);
+
+                falkolib::FALKO keypoint_rot_trans;
+                keypoint_rot_trans = new_scene->keypoints_list_[i];
+                keypoint_rot_trans.point[0] =
+                    (new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0]) * cos(initial_angle) -
+                    (new_scene->keypoints_list_[i].point[1] - new_scene->mid_point_[1]) * sin(initial_angle);
+
+                keypoint_rot_trans.point[1] =
+                    (new_scene->keypoints_list_[i].point[0] - new_scene->mid_point_[0]) * sin(initial_angle) +
+                    (new_scene->keypoints_list_[i].point[1] - new_scene->mid_point_[1]) * cos(initial_angle);
+
+                new_scene->keypoints_list_transl_rot_.push_back(keypoint_rot_trans);
+            }
+
+        // Compute KEYPOINTS covariance matrix
+
+        float sumXX = 0;
+        float sumXY = 0;
+        float sumYY = 0;
+
+        n         = new_scene->keypoints_list_.size();
+        auto mean = new_scene->mid_point_;
+        for (int i = 0; i < n; i++)
+            {
+                sumXX += (new_scene->keypoints_list_[i].point[0] - mean[0]) *
+                         (new_scene->keypoints_list_[i].point[0] - mean[0]);
+                sumXY += (new_scene->keypoints_list_[i].point[0] - mean[0]) *
+                         (new_scene->keypoints_list_[i].point[1] - mean[1]);
+                sumYY += (new_scene->keypoints_list_[i].point[1] - mean[1]) *
+                         (new_scene->keypoints_list_[i].point[1] - mean[1]);
+            }
+        double covXX = sumXX / n;
+        double covXY = sumXY / n;
+        double covYY = sumYY / n;
+
+        Eigen::Matrix<double, 2, 2> A;
+        A << covXX, covXY, covXY, covYY;
+
+        // Compute KEYPOINTS eigenvalues
+        Eigen::EigenSolver<Eigen::Matrix<double, 2, 2>> s(A);
+        double                                          eig1 = s.eigenvalues()(0).real();
+        double                                          eig2 = s.eigenvalues()(1).real();
+        // The greater eigenvalue will be the first one
+        if (eig1 > eig2)
+            {
+                new_scene->eigenvalues_kp_.push_back(eig1);
+                new_scene->eigenvalues_kp_.push_back(eig2);
+            }
+        else
+            {
+                new_scene->eigenvalues_kp_.push_back(eig2);
+                new_scene->eigenvalues_kp_.push_back(eig1);
+            }
+
+        // Compute SCAN mid point
+        LaserScan scan = _scan;
+        scan.ranges2xy(_scan_params);
+        Eigen::Vector2d mid_point_scan(0, 0);
+
+        for (int i = 0; i < scan.points_.size() / 3; i++)
+            {
+                mid_point_scan[0] = mid_point_scan[0] + scan.points_(0, i);
+                mid_point_scan[1] = mid_point_scan[1] + scan.points_(1, i);
+            }
+        new_scene->mid_point_scan_ = mid_point_scan / (double)scan.points_.size() / 3;
+
+        // Compute SCAN Area
+        n                     = 3;
+        new_scene->area_scan_ = 0.0;
+
+        int points_size = scan.points_.size() / 3;
+        for (int i = 0; i < points_size; i++)
+            {
+                X[0] = 0.0;
+                Y[0] = 0.0;
+
+                X[1] = scan.points_(0, i);
+                Y[1] = scan.points_(1, i);
+
+                if (i < points_size - 1) // Proceed until final keypoint
+                    {
+                        X[2] = scan.points_(0, i + 1);
+                        Y[2] = scan.points_(1, i + 1);
+                    }
+                else // if you arrived to the final keypoint then use inital keypoint
+                    {
+                        X[2] = scan.points_(0, 0);
+                        Y[2] = scan.points_(1, 0);
+                    }
+                new_scene->area_scan_ = new_scene->area_scan_ + (double)triangleArea(X, Y, n);
+            }
+        // Compute SCAN covariance matrix
+
+        sumXX = 0;
+        sumXY = 0;
+        sumYY = 0;
+
+        mean = new_scene->mid_point_scan_;
+        for (int i = 0; i < points_size; i++)
+            {
+                sumXX += (scan.points_(0, i) - mean[0]) * (scan.points_(0, i) - mean[0]);
+                sumXY += (scan.points_(0, i) - mean[0]) * (scan.points_(1, i) - mean[1]);
+                sumYY += (scan.points_(1, i) - mean[1]) * (scan.points_(1, i) - mean[1]);
+            }
+        covXX = sumXX / points_size;
+        covXY = sumXY / points_size;
+        covYY = sumYY / points_size;
+
+        Eigen::Matrix<double, 2, 2> A_scan;
+        A_scan << covXX, covXY, covXY, covYY;
+
+        // Compute SCAN eigenvalues
+        Eigen::EigenSolver<Eigen::Matrix<double, 2, 2>> s_scan(A_scan);
+        eig1 = s_scan.eigenvalues()(0).real();
+        eig2 = s_scan.eigenvalues()(1).real();
+
+        // The greater eigenvalue will be the first one
+        if (eig1 > eig2)
+            {
+                new_scene->eigenvalues_scan_.push_back(eig1);
+                new_scene->eigenvalues_scan_.push_back(eig2);
+            }
+        else
+            {
+                new_scene->eigenvalues_scan_.push_back(eig2);
+                new_scene->eigenvalues_scan_.push_back(eig1);
+            }
+
+        return new_scene;
+    }
+
+    /** \brief Convert scans from laserscanutils::LaserScan to
+     *falkolib::LaserScan object
+     **/
+    laserScanPtr convert2LaserScanFALKO(const LaserScan &_scan, const LaserScanParams &_scan_params)
+    {
+        double field_of_view = _scan_params.angle_max_ - _scan_params.angle_min_;
+        auto   scan_falko =
+            std::make_shared<falkolib::LaserScan>(_scan_params.angle_min_, field_of_view, _scan.ranges_raw_.size());
+
+        std::vector<double> double_ranges(_scan.ranges_raw_.begin(), _scan.ranges_raw_.end());
+
+        for (int i = 0; i < double_ranges.size(); i++)
+            {
+                if (std::to_string(double_ranges[i]) == "inf")
+                    {
+                        double_ranges[i] = 250;
+                    }
+            }
+
+        scan_falko->fromRanges(double_ranges);
+        return scan_falko;
+    }
+
+    /** \brief Create and update a matchLoopClosure struct with the info that is produced when matching two given scenes
+     * \param _scene_1 reference scene struct
+     * \param _scene_2 target scene struct
+     **/
+    MatchLoopClosureScenePtr matchScene(sceneBasePtr _scene_1, sceneBasePtr _scene_2) override
+    {
+        std::vector<std::pair<int, int>> asso_nn;
+        auto                             scene_1_falko = std::static_pointer_cast<SceneFalko<D>>(_scene_1);
+        auto                             scene_2_falko = std::static_pointer_cast<SceneFalko<D>>(_scene_2);
+
+        int matching_number = 0;
+
+        if (use_descriptors_ == 0)
+            {
+                matching_number =
+                    matcher_.match(scene_1_falko->keypoints_list_, scene_2_falko->keypoints_list_, asso_nn);
+            }
+        else if (use_descriptors_ == 1)
+            {
+                matching_number =
+                    matcher_.match(scene_1_falko->keypoints_list_, scene_1_falko->descriptors_list_rotated,
+                                   scene_2_falko->keypoints_list_, scene_2_falko->descriptors_list_rotated, asso_nn);
+            }
+
+        auto new_match                    = std::make_shared<MatchLoopClosureScene>();
+        new_match->keypoints_number_match = matching_number;
+
+        new_match->match = computeTransform(scene_1_falko->keypoints_list_, scene_2_falko->keypoints_list_, asso_nn,
+                                            new_match->transform);
+
+        new_match->associations = asso_nn;
+        new_match->scene_1      = _scene_1;
+        new_match->scene_2      = _scene_2;
+
+        new_match->transform_vector.head(2) = new_match->transform.translation();
+        new_match->transform_vector(2)      = Eigen::Rotation2Dd(new_match->transform.rotation()).angle();
+
+        std::cout << "laserscanutils::matching_number : " << matching_number << std::endl;
+
+        new_match->score = (double)matching_number;
+
+        return new_match;
+    }
+
+    int  keypoints_number_th_;
+    bool use_descriptors_;
+
+    // (X[i], Y[i]) are coordinates of i'th point.
+    double triangleArea(double X[], double Y[], int n)
+    {
+        // Initialize area
+        double area = 0.0;
+
+        // Calculate value of shoelace formula
+        int j = n - 1;
+        for (int i = 0; i < n; i++)
+            {
+                area += (X[j] + X[i]) * (Y[j] - Y[i]);
+                j = i; // j is previous vertex to i
+            }
+
+        // Return absolute value
+        return fabs((double)area / 2.0);
+    }
+};
+
+// Partial template specialization
+
+template <typename D, typename Extr> class LoopClosureFalkoAht : public LoopClosureFalko<D, Extr, falkolib::AHTMatcher>
+{
+  public:
+    LoopClosureFalkoAht(ParameterLoopClosureFalko _param)
+        : LoopClosureFalko<D, Extr, falkolib::AHTMatcher>(
+              _param,
+              falkolib::AHTMatcher<falkolib::FALKO, D>(_param.xRes_, _param.yRes_, _param.thetaRes_, _param.xAbsMax_,
+                                                       _param.yAbsMax_, _param.thetaAbsMax_)){};
+};
+
+template <typename D, typename Extr> class LoopClosureFalkoNn : public LoopClosureFalko<D, Extr, falkolib::NNMatcher>
+{
+  public:
+    LoopClosureFalkoNn(ParameterLoopClosureFalko _param)
+        : LoopClosureFalko<D, Extr, falkolib::NNMatcher>(_param, falkolib::NNMatcher<falkolib::FALKO, D>()){
+
+          };
+};
+
+} /* namespace laserscanutils */
+
+#endif /* LOOP_CLOSURE_FALKO_H_ */
diff --git a/src/match_loop_closure_scene.h b/src/match_loop_closure_scene.h
new file mode 100644
index 0000000000000000000000000000000000000000..a99dc0045e3304ca433526452590a3e102d06e68
--- /dev/null
+++ b/src/match_loop_closure_scene.h
@@ -0,0 +1,36 @@
+/**
+ * \file match_loop_closure.h
+ *
+ *  Created on: Feb 15, 2021
+ *      \author: spujol
+ */
+
+#ifndef MATCH_LOOP_CLOSURE_SCENE_H_
+#define MATCH_LOOP_CLOSURE_SCENE_H_
+
+#include <fstream>
+#include <iostream>
+#include <memory>
+#include <tuple>
+
+#include "scene_base.h"
+
+namespace laserscanutils {
+
+struct MatchLoopClosureScene {
+
+  sceneBasePtr scene_1; //ref_scene
+  sceneBasePtr scene_2; //new_scene
+  bool match;
+  int keypoints_number_match;
+  double score;
+  std::vector<std::pair<int, int>> associations;
+  Eigen::Affine2d transform;
+  Eigen::Vector3d transform_vector;
+};
+
+typedef std::shared_ptr<MatchLoopClosureScene> MatchLoopClosureScenePtr;
+
+} /* namespace laserscanutils */
+
+#endif /* MATCH_LOOP_CLOSURE_SCENE_H_ */
diff --git a/src/scene_base.h b/src/scene_base.h
new file mode 100644
index 0000000000000000000000000000000000000000..40651e4f9146e19c52791a0069eb08a8cefedc70
--- /dev/null
+++ b/src/scene_base.h
@@ -0,0 +1,34 @@
+/**
+ * \file scene_base.h
+ *
+ *  Created on: Feb 9, 2021
+ *      \author: spujol
+ */
+
+#ifndef SCENE_BASE_H_
+#define SCENE_BASE_H_
+
+#include <fstream>
+#include <iostream>
+
+namespace laserscanutils {
+
+struct SceneBase
+{
+    int                 id;
+    double              area_;
+    double              area_scan_;
+    double              perimeter_;
+    double              max_distance_;
+    double              mean_distance_;
+    Eigen::Vector2d     mid_point_;
+    Eigen::Vector2d     mid_point_scan_;
+    std::vector<double> regressor_coefs;
+    std::vector<double> eigenvalues_kp_;
+    std::vector<double> eigenvalues_scan_;
+};
+typedef std::shared_ptr<SceneBase> sceneBasePtr;
+
+} /* namespace laserscanutils */
+
+#endif /* SCENE_BASE_H_ */
diff --git a/src/scene_falko.h b/src/scene_falko.h
new file mode 100644
index 0000000000000000000000000000000000000000..9dbd1f8f4c07a92b1f4eb34225e2861789290ba3
--- /dev/null
+++ b/src/scene_falko.h
@@ -0,0 +1,49 @@
+/**
+ * \file scene_falko.h
+ *
+ *  Created on: Feb 9, 2021
+ *      \author: spujol
+ */
+
+#ifndef SCENE_FALKO_H_
+#define SCENE_FALKO_H_
+
+#include <fstream>
+#include <iostream>
+#include <iterator>
+#include <list>
+#include <memory>
+
+/**************************
+ *      LaserScanUtils includes      *
+ **************************/
+#include "scene_base.h"
+
+/**************************
+ *      Falko includes      *
+ **************************/
+
+#include <falkolib/Feature/FALKOExtractor.h>
+#include <falkolib/Feature/BSCExtractor.h>
+#include <falkolib/Feature/CGHExtractor.h>
+
+namespace laserscanutils {
+
+typedef falkolib::BSC bsc;
+typedef falkolib::CGH cgh;
+
+template <typename D> struct SceneFalko : public SceneBase
+{
+    std::vector<falkolib::FALKO> keypoints_list_;
+    std::vector<falkolib::FALKO> keypoints_list_mid_point_;
+    std::vector<falkolib::FALKO> keypoints_list_transl_rot_;
+    std::vector<falkolib::FALKO> keypoints_list_rotated_;
+    std::vector<falkolib::FALKO> keypoints_list_rotated_reverse_;
+    std::vector<D>               descriptors_list_;
+    std::vector<D>               descriptors_list_rotated;
+    std::vector<double>          angle_rotation_;
+};
+
+} /* namespace laserscanutils */
+
+#endif /* SCENE_FALKO_H_ */
diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt
index 6cd8581ea6483c152ff1562ce6670a2066448522..aa60e80a7077af966717dde72ce6a3ffedb64691 100644
--- a/test/CMakeLists.txt
+++ b/test/CMakeLists.txt
@@ -4,6 +4,13 @@ add_subdirectory(gtest)
 # Include gtest directory.
 include_directories(${GTEST_INCLUDE_DIRS})
 
+#Include directories
+INCLUDE_DIRECTORIES(../src)
+INCLUDE_DIRECTORIES(/data)
+FIND_PACKAGE(Eigen3 3.3 REQUIRED)
+find_package(PythonLibs 2.7)
+INCLUDE_DIRECTORIES(${EIGEN3_INCLUDE_DIRS})
+
 ############# USE THIS TEST AS AN EXAMPLE ####################
 #                                                            #
 # Create a specific test executable for gtest_example        #
@@ -14,4 +21,8 @@ include_directories(${GTEST_INCLUDE_DIRS})
 
 # gtest example
 gnss_utils_add_gtest(gtest_example gtest_example.cpp)
-target_link_libraries(gtest_example ${PROJECT_NAME})  
\ No newline at end of file
+target_link_libraries(gtest_example ${PROJECT_NAME})  
+
+gnss_utils_add_gtest(gtest_loop_closure_falko gtest_loop_closure_falko.cpp ${PROJECT_SOURCE_DIR}/test/data)
+target_link_libraries(gtest_loop_closure_falko ${PROJECT_NAME} ${PYTHON_LIBRARIES})
+target_include_directories(gtest_loop_closure_falko PRIVATE ${PYTHON_INCLUDE_DIRS})
diff --git a/test/data/scan_data.h b/test/data/scan_data.h
new file mode 100644
index 0000000000000000000000000000000000000000..7728475cebae0255448ef14237e24b8578b6d3ee
--- /dev/null
+++ b/test/data/scan_data.h
@@ -0,0 +1,2906 @@
+/**
+ * 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/>.
+ */
+std::vector<float> 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};
+
+std::vector<float> testRanges2 = {250,
+                        250,
+                        250,
+                        250,
+                        16.799999237060547,
+                        16.799999237060547,
+                        16.799999237060547,
+                        16.799999237060547,
+                        14.095999717712402,
+                        14.095999717712402,
+                        14.095999717712402,
+                        14.095999717712402,
+                        13.255999565124512,
+                        13.255999565124512,
+                        13.255999565124512,
+                        12.767999649047852,
+                        12.175999641418457,
+                        12.175999641418457,
+                        10.911999702453613,
+                        10.4399995803833,
+                        10.4399995803833,
+                        10.4399995803833,
+                        10.32800006866455,
+                        10.32800006866455,
+                        10.32800006866455,
+                        10.343999862670898,
+                        10.336000442504883,
+                        10.312000274658203,
+                        10.368000030517578,
+                        10.368000030517578,
+                        10.407999992370605,
+                        10.472000122070312,
+                        10.48799991607666,
+                        10.520000457763672,
+                        10.48799991607666,
+                        10.48799991607666,
+                        10.472000122070312,
+                        10.503999710083008,
+                        10.51200008392334,
+                        10.51200008392334,
+                        10.520000457763672,
+                        10.520000457763672,
+                        8.295999526977539,
+                        8.13599967956543,
+                        7.984000205993652,
+                        7.791999816894531,
+                        7.624000072479248,
+                        7.624000072479248,
+                        7.5279998779296875,
+                        7.4079999923706055,
+                        7.263999938964844,
+                        7.119999885559082,
+                        7.007999897003174,
+                        7.007999897003174,
+                        6.9120001792907715,
+                        6.760000228881836,
+                        6.639999866485596,
+                        6.544000148773193,
+                        6.415999889373779,
+                        6.415999889373779,
+                        6.311999797821045,
+                        6.271999835968018,
+                        6.263999938964844,
+                        6.288000106811523,
+                        6.303999900817871,
+                        6.303999900817871,
+                        6.320000171661377,
+                        6.335999965667725,
+                        6.343999862670898,
+                        6.335999965667725,
+                        6.303999900817871,
+                        6.303999900817871,
+                        6.271999835968018,
+                        4.5920000076293945,
+                        250,
+                        4.480000019073486,
+                        4.480000019073486,
+                        4.480000019073486,
+                        4.480000019073486,
+                        4.4720001220703125,
+                        4.504000186920166,
+                        4.519999980926514,
+                        4.5279998779296875,
+                        4.5279998779296875,
+                        4.5279998779296875,
+                        4.5279998779296875,
+                        4.567999839782715,
+                        4.559999942779541,
+                        250,
+                        4.48799991607666,
+                        4.48799991607666,
+                        4.48799991607666,
+                        4.48799991607666,
+                        4.440000057220459,
+                        4.392000198364258,
+                        4.360000133514404,
+                        4.360000133514404,
+                        4.320000171661377,
+                        4.263999938964844,
+                        4.223999977111816,
+                        4.191999912261963,
+                        4.168000221252441,
+                        4.168000221252441,
+                        4.168000221252441,
+                        4.176000118255615,
+                        4.176000118255615,
+                        4.191999912261963,
+                        4.208000183105469,
+                        4.208000183105469,
+                        4.208000183105469,
+                        4.216000080108643,
+                        4.216000080108643,
+                        4.216000080108643,
+                        4.23199987411499,
+                        4.23199987411499,
+                        4.223999977111816,
+                        4.184000015258789,
+                        250,
+                        4.136000156402588,
+                        4.136000156402588,
+                        4.136000156402588,
+                        4.136000156402588,
+                        4.111999988555908,
+                        4.111999988555908,
+                        4.0960001945495605,
+                        4.064000129699707,
+                        4.015999794006348,
+                        4.015999794006348,
+                        3.9839999675750732,
+                        3.9679999351501465,
+                        3.947999954223633,
+                        3.9119999408721924,
+                        3.875999927520752,
+                        3.875999927520752,
+                        3.8480000495910645,
+                        3.8239998817443848,
+                        3.7039999961853027,
+                        3.5920000076293945,
+                        3.259999990463257,
+                        3.259999990463257,
+                        3.240000009536743,
+                        3.2160000801086426,
+                        3.196000099182129,
+                        3.171999931335449,
+                        3.1519999504089355,
+                        3.1519999504089355,
+                        3.140000104904175,
+                        3.124000072479248,
+                        3.115999937057495,
+                        2.5959999561309814,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        2.51200008392334,
+                        2.51200008392334,
+                        2.51200008392334,
+                        2.51200008392334,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.6040000915527344,
+                        2.6040000915527344,
+                        2.6040000915527344,
+                        2.6040000915527344,
+                        250,
+                        250,
+                        250,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        250,
+                        250,
+                        250,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        2.6480000019073486,
+                        2.635999917984009,
+                        2.628000020980835,
+                        2.619999885559082,
+                        2.619999885559082,
+                        2.6080000400543213,
+                        2.5959999561309814,
+                        2.5880000591278076,
+                        2.5759999752044678,
+                        2.563999891281128,
+                        2.563999891281128,
+                        2.552000045776367,
+                        2.5399999618530273,
+                        2.5280001163482666,
+                        2.5199999809265137,
+                        2.51200008392334,
+                        2.51200008392334,
+                        2.5,
+                        2.48799991607666,
+                        2.4839999675750732,
+                        2.4719998836517334,
+                        2.4639999866485596,
+                        2.4639999866485596,
+                        2.4560000896453857,
+                        2.444000005722046,
+                        2.436000108718872,
+                        2.431999921798706,
+                        2.4200000762939453,
+                        2.4200000762939453,
+                        2.4159998893737793,
+                        2.4159998893737793,
+                        2.4200000762939453,
+                        2.431999921798706,
+                        2.444000005722046,
+                        2.4600000381469727,
+                        2.4600000381469727,
+                        2.4760000705718994,
+                        2.48799991607666,
+                        2.5,
+                        2.5160000324249268,
+                        2.5360000133514404,
+                        2.5360000133514404,
+                        2.5480000972747803,
+                        2.563999891281128,
+                        2.5840001106262207,
+                        2.7079999446868896,
+                        2.684000015258789,
+                        2.684000015258789,
+                        2.5880000591278076,
+                        2.5880000591278076,
+                        2.5880000591278076,
+                        2.631999969482422,
+                        2.631999969482422,
+                        2.631999969482422,
+                        2.631999969482422,
+                        2.624000072479248,
+                        2.615999937057495,
+                        2.611999988555908,
+                        2.6040000915527344,
+                        2.6040000915527344,
+                        2.5920000076293945,
+                        2.5880000591278076,
+                        2.5840001106262207,
+                        2.5759999752044678,
+                        2.572000026702881,
+                        2.559999942779541,
+                        2.559999942779541,
+                        2.552000045776367,
+                        2.5480000972747803,
+                        2.5439999103546143,
+                        2.5399999618530273,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5280001163482666,
+                        2.5239999294281006,
+                        2.5160000324249268,
+                        2.507999897003174,
+                        2.503999948501587,
+                        2.503999948501587,
+                        2.5,
+                        2.492000102996826,
+                        2.492000102996826,
+                        2.4839999675750732,
+                        2.4800000190734863,
+                        2.4800000190734863,
+                        2.4760000705718994,
+                        2.4719998836517334,
+                        2.4679999351501465,
+                        2.4600000381469727,
+                        2.4600000381469727,
+                        2.4519999027252197,
+                        2.447999954223633,
+                        2.447999954223633,
+                        2.447999954223633,
+                        2.440000057220459,
+                        2.440000057220459,
+                        2.431999921798706,
+                        2.427999973297119,
+                        2.427999973297119,
+                        2.4240000247955322,
+                        2.4200000762939453,
+                        2.4200000762939453,
+                        2.4159998893737793,
+                        2.4119999408721924,
+                        2.4079999923706055,
+                        2.4040000438690186,
+                        2.4000000953674316,
+                        2.4000000953674316,
+                        2.4000000953674316,
+                        2.3959999084472656,
+                        2.3919999599456787,
+                        2.388000011444092,
+                        2.384000062942505,
+                        2.384000062942505,
+                        2.384000062942505,
+                        2.380000114440918,
+                        2.375999927520752,
+                        2.371999979019165,
+                        2.371999979019165,
+                        2.371999979019165,
+                        2.368000030517578,
+                        2.364000082015991,
+                        2.364000082015991,
+                        2.364000082015991,
+                        2.364000082015991,
+                        2.364000082015991,
+                        2.359999895095825,
+                        2.371999979019165,
+                        2.388000011444092,
+                        2.388000011444092,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.002000093460083,
+                        2.002000093460083,
+                        2.002000093460083,
+                        2.002000093460083,
+                        2.002000093460083,
+                        1.9980000257492065,
+                        1.9980000257492065,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.9980000257492065,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.99399995803833,
+                        1.9919999837875366,
+                        1.99399995803833,
+                        1.9919999837875366,
+                        1.9919999837875366,
+                        1.9919999837875366,
+                        1.996000051498413,
+                        1.996000051498413,
+                        2.0,
+                        2.009999990463257,
+                        2.009999990463257,
+                        2.0320000648498535,
+                        2.0480000972747803,
+                        2.0320000648498535,
+                        2.0179998874664307,
+                        2.007999897003174,
+                        2.007999897003174,
+                        1.996000051498413,
+                        1.9919999837875366,
+                        1.9900000095367432,
+                        1.9880000352859497,
+                        1.99399995803833,
+                        1.99399995803833,
+                        1.99399995803833,
+                        1.99399995803833,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.996000051498413,
+                        1.99399995803833,
+                        1.99399995803833,
+                        1.9980000257492065,
+                        1.9980000257492065,
+                        2.0,
+                        2.002000093460083,
+                        2.0,
+                        2.002000093460083,
+                        1.9759999513626099,
+                        1.9759999513626099,
+                        1.9359999895095825,
+                        2.0360000133514404,
+                        2.0859999656677246,
+                        2.0439999103546143,
+                        1.9819999933242798,
+                        1.9819999933242798,
+                        1.9279999732971191,
+                        1.9559999704360962,
+                        1.9559999704360962,
+                        1.9600000381469727,
+                        1.9579999446868896,
+                        1.9559999704360962,
+                        1.9559999704360962,
+                        1.9579999446868896,
+                        1.9620000123977661,
+                        1.9639999866485596,
+                        1.968000054359436,
+                        1.9700000286102295,
+                        1.9700000286102295,
+                        1.972000002861023,
+                        1.9739999771118164,
+                        1.9739999771118164,
+                        1.9739999771118164,
+                        1.9780000448226929,
+                        1.9780000448226929,
+                        1.9839999675750732,
+                        1.9859999418258667,
+                        1.9859999418258667,
+                        1.9900000095367432,
+                        1.99399995803833,
+                        1.99399995803833,
+                        1.996000051498413,
+                        1.99399995803833,
+                        1.9980000257492065,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.003999948501587,
+                        2.5999999046325684,
+                        1.6720000505447388,
+                        2.0480000972747803,
+                        2.115999937057495,
+                        2.115999937057495,
+                        2.191999912261963,
+                        2.196000099182129,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        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.5160000324249268,
+                        2.5160000324249268,
+                        2.5160000324249268,
+                        2.5160000324249268,
+                        2.5160000324249268,
+                        2.5160000324249268,
+                        2.5160000324249268,
+                        2.5239999294281006,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5280001163482666,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5280001163482666,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5239999294281006,
+                        2.5239999294281006,
+                        2.5280001163482666,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5320000648498535,
+                        2.5360000133514404,
+                        2.5360000133514404,
+                        2.5360000133514404,
+                        2.5360000133514404,
+                        2.5399999618530273,
+                        2.5439999103546143,
+                        2.5439999103546143,
+                        2.5439999103546143,
+                        2.5439999103546143,
+                        2.5439999103546143,
+                        2.5480000972747803,
+                        2.555999994277954,
+                        2.559999942779541,
+                        1.315999984741211,
+                        1.315999984741211,
+                        1.315999984741211,
+                        1.315999984741211,
+                        1.3040000200271606,
+                        1.3040000200271606,
+                        1.2979999780654907,
+                        1.2920000553131104,
+                        1.2920000553131104,
+                        1.2860000133514404,
+                        1.2899999618530273,
+                        1.2999999523162842,
+                        1.3020000457763672,
+                        1.3020000457763672,
+                        1.3020000457763672,
+                        1.2999999523162842,
+                        1.2960000038146973,
+                        1.3020000457763672,
+                        1.312000036239624,
+                        1.315999984741211,
+                        1.315999984741211,
+                        1.3179999589920044,
+                        1.3279999494552612,
+                        1.3359999656677246,
+                        1.3420000076293945,
+                        1.2200000286102295,
+                        1.2200000286102295,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        1.090000033378601,
+                        1.090000033378601,
+                        1.090000033378601,
+                        1.090000033378601,
+                        1.0880000591278076,
+                        1.0880000591278076,
+                        1.0880000591278076,
+                        1.0920000076293945,
+                        1.0959999561309814,
+                        1.0980000495910645,
+                        1.0980000495910645,
+                        1.0980000495910645,
+                        1.0980000495910645,
+                        1.0980000495910645,
+                        1.0980000495910645,
+                        1.0959999561309814,
+                        1.0959999561309814,
+                        1.0959999561309814,
+                        1.0959999561309814,
+                        1.093999981880188,
+                        1.093999981880188,
+                        1.093999981880188,
+                        1.0920000076293945,
+                        1.0920000076293945,
+                        1.0920000076293945,
+                        1.0920000076293945,
+                        1.093999981880188,
+                        1.1019999980926514,
+                        1.1139999628067017,
+                        1.1239999532699585,
+                        1.1239999532699585,
+                        1.1299999952316284,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        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.888000011444092,
+                        5.888000011444092,
+                        5.888000011444092,
+                        5.888000011444092,
+                        5.863999843597412,
+                        5.863999843597412,
+                        5.808000087738037,
+                        5.751999855041504,
+                        5.751999855041504,
+                        5.74399995803833,
+                        5.74399995803833,
+                        5.656000137329102,
+                        5.656000137329102,
+                        5.656000137329102,
+                        5.584000110626221,
+                        5.584000110626221,
+                        5.584000110626221,
+                        5.584000110626221,
+                        5.552000045776367,
+                        5.559999942779541,
+                        5.599999904632568,
+                        5.599999904632568,
+                        6.71999979019165,
+                        6.783999919891357,
+                        6.831999778747559,
+                        6.815999984741211,
+                        6.696000099182129,
+                        6.552000045776367,
+                        6.552000045776367,
+                        6.423999786376953,
+                        6.343999862670898,
+                        6.328000068664551,
+                        9.232000350952148,
+                        9.192000389099121,
+                        9.192000389099121,
+                        9.175999641418457,
+                        9.144000053405762,
+                        9.039999961853027,
+                        8.960000038146973,
+                        7.943999767303467,
+                        7.943999767303467,
+                        7.863999843597412,
+                        7.8480000495910645,
+                        7.791999816894531,
+                        7.751999855041504,
+                        7.736000061035156,
+                        7.736000061035156,
+                        7.71999979019165,
+                        7.728000164031982,
+                        7.728000164031982,
+                        7.711999893188477,
+                        7.696000099182129,
+                        7.696000099182129,
+                        7.688000202178955,
+                        7.696000099182129,
+                        7.696000099182129,
+                        7.688000202178955,
+                        7.688000202178955,
+                        7.688000202178955,
+                        7.736000061035156,
+                        7.800000190734863,
+                        8.616000175476074,
+                        8.600000381469727,
+                        8.600000381469727,
+                        8.576000213623047,
+                        8.543999671936035,
+                        8.520000457763672,
+                        8.51200008392334,
+                        8.496000289916992,
+                        8.496000289916992,
+                        8.472000122070312,
+                        8.456000328063965,
+                        8.4399995803833,
+                        8.4399995803833,
+                        8.423999786376953,
+                        8.423999786376953,
+                        8.383999824523926,
+                        8.37600040435791,
+                        8.37600040435791,
+                        8.368000030517578,
+                        8.35200023651123,
+                        8.35200023651123,
+                        8.35200023651123,
+                        8.312000274658203,
+                        8.248000144958496,
+                        8.223999977111816,
+                        8.288000106811523,
+                        8.288000106811523,
+                        8.4399995803833,
+                        8.607999801635742,
+                        8.776000022888184,
+                        8.895999908447266,
+                        9.064000129699707,
+                        9.064000129699707,
+                        9.168000221252441,
+                        11.84000015258789,
+                        12.175999641418457,
+                        12.312000274658203,
+                        12.656000137329102,
+                        12.656000137329102,
+                        12.767999649047852,
+                        13.208000183105469,
+                        13.35200023651123,
+                        13.656000137329102,
+                        13.64799976348877,
+                        13.64799976348877,
+                        13.527999877929688,
+                        14.015999794006348,
+                        13.960000038146973,
+                        14.119999885559082,
+                        14.255999565124512,
+                        14.255999565124512,
+                        13.784000396728516,
+                        15.407999992370605,
+                        15.496000289916992,
+                        15.53600025177002,
+                        15.423999786376953,
+                        15.423999786376953,
+                        15.37600040435791,
+                        15.416000366210938,
+                        15.423999786376953,
+                        15.383999824523926,
+                        15.343999862670898,
+                        15.343999862670898,
+                        15.368000030517578,
+                        15.32800006866455,
+                        15.255999565124512,
+                        15.272000312805176,
+                        15.272000312805176,
+                        15.272000312805176,
+                        15.215999603271484,
+                        15.272000312805176,
+                        15.295999526977539,
+                        15.208000183105469,
+                        15.215999603271484,
+                        15.215999603271484,
+                        15.208000183105469,
+                        15.208000183105469,
+                        15.192000389099121,
+                        15.168000221252441,
+                        15.168000221252441,
+                        16.719999313354492,
+                        16.719999313354492,
+                        16.639999389648438,
+                        16.6560001373291,
+                        16.719999313354492,
+                        16.719999313354492,
+                        16.639999389648438,
+                        16.672000885009766,
+                        16.687999725341797,
+                        16.54400062561035,
+                        16.576000213623047,
+                        16.6560001373291,
+                        16.6560001373291,
+                        16.27199935913086,
+                        16.583999633789062,
+                        16.079999923706055,
+                        16.399999618530273,
+                        16.736000061035156,
+                        16.736000061035156,
+                        16.143999099731445,
+                        250,
+                        20.304000854492188,
+                        20.304000854492188,
+                        20.304000854492188,
+                        20.304000854492188,
+                        250,
+                        250,
+                        250,
+                        20.20800018310547,
+                        20.20800018310547,
+                        20.20800018310547,
+                        20.20800018310547,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250,
+                        250};
+
+// std::vector<float> target_scan_1 = {2.03169,1.9677,2.02369,2.01969,1.9517,1.93171,1.93171,1.89171,1.92771,1.92771,1.89171,1.85172,1.83172,1.85972,1.85172,1.79173,1.55576,1.54376,1.53577,1.49577,1.49577,1.49577,1.45178,1.47977,1.47977,1.45578,1.59576,250,250,250,1.59576,1.59576,1.59576,1.59576,1.54776,1.55176,1.53577,1.53577,1.51977,1.50377,1.49577,1.48377,1.47977,1.44378,1.47178,1.47578,1.44378,1.42378,1.41978,1.42778,1.42378,1.41179,1.3198,1.26781,1.22781,1.24781,1.21981,1.20782,1.23581,1.19582,1.22781,1.19982,1.17982,1.20382,1.17582,1.17982,1.16782,1.16382,1.15582,1.15182,1.15982,1.14783,1.13183,1.14783,1.12383,1.15182,1.14383,1.13583,1.24781,1.24781,1.19582,1.2958,1.3118,1.3038,1.2958,1.2998,1.2998,1.3038,1.2978,1.2858,1.2818,1.27581,1.2838,1.2878,1.27981,1.3078,1.2898,1.27781,1.2878,1.27981,1.3018,1.2998,1.2938,1.2958,250,250,1.19582,1.21182,1.20382,1.18382,1.23581,1.19582,250,250,250,1.9777,1.9837,1.9777,1.9857,1.9917,2.09168,250,4.49132,4.48732,4.48332,4.48532,4.47732,4.47132,4.48532,4.47332,4.47532,4.46332,4.47332,4.47132,4.46332,4.49931,4.96124,5.04323,6.571,6.567,6.579,6.579,6.64299,7.55685,7.52685,7.56485,7.93079,250,250,8.70467,8.69668,8.69268,8.72067,8.72067,8.72067,8.73267,8.73667,8.76467,8.76267,8.76467,5.01924,5.01524,5.02723,5.02723,5.03123,5.05523,5.04323,5.07123,5.07123,5.07123,5.09722,5.01924,4.92325,4.68529,4.64729,4.66929,4.66529,4.68929,4.68729,4.70128,4.71728,4.70928,4.73928,4.74928,4.75128,4.76927,4.76327,4.79527,4.79527,4.80927,4.82926,4.83526,4.85326,4.86926,4.86726,4.88926,4.90725,4.92325,4.94325,4.95125,4.97124,5.00524,3.13952,3.11753,3.06953,3.03754,2.99154,2.96555,2.91156,2.87756,2.83757,2.22366,2.18967,2.16167,2.15367,2.15167,2.14167,2.17367,2.16767,2.16367,2.18567,2.32765,2.37964,2.44363,2.43163,2.41763,2.38564,2.37364,2.34164,2.30165,2.27565,2.26965,2.30565,2.31765,2.33764,2.34364,2.36164,2.37364,2.38364,2.40563,2.41163,2.41963,2.44163,2.45363,2.47362,2.48362,2.49162,2.51162,2.52961,2.55961,2.56561,2.57361,2.5996,2.6136,2.6396,2.6576,2.66959,2.69559,250,2.71959,7.15891,7.17491,7.2469,7.27889,7.37888,9.08662,9.06062,8.99063,8.90664,8.84865,8.76266,8.68668,8.67868,8.66668,8.66268,8.73067,8.81066,8.91064,9.01063,9.11461,9.2106,9.28259,9.43456,9.49056,9.62653,9.73252,9.8625,9.96848,10.0825,10.2244,10.3484,10.4724,10.6244,10.7524,10.9003,11.0623,11.2203,11.4623,11.6362,11.8122,11.9922,3.79342,3.78142,3.77343,3.76743,3.75143,3.73943,3.73743,3.71743,3.71143,3.70544,3.69144,3.68544,3.67344,3.67544,3.66144,3.63945,3.64145,3.62945,3.63345,3.61745,3.61345,3.61145,3.60345,3.60345,3.58545,3.58545,3.57746,3.55746,3.56946,3.56946,3.54746,3.55546,3.53346,3.54146,3.53346,3.52746,3.52146,3.50947,3.51547,3.50547,3.48947,3.50347,3.49947,3.50147,3.48547,3.47747,3.49147,3.47947,1.90571,1.90571,2.38764,2.37764,2.36764,3.47747,3.47747,3.45947,3.46147,3.46547,3.47747,3.45747,3.46747,3.48147,3.46747,3.47947,3.48147,3.46147,3.47947,3.47347,3.48147,3.47347,3.47147,2.38764,2.36364,1.90171,1.88771,1.88771,3.48547,3.59145,5.19121,4.08338,3.88341,3.69544,3.58345,4.18136,4.17536,3.2915,2.89156,2.83157,2.77958,2.79157,2.82357,2.81957,2.82557,2.84357,250,250,1.9677,2.0037,250,250,2.87956,2.86156,2.85956,2.87756,2.87356,2.89956,2.89956,2.89356,2.91356,2.90756,2.92955,4.41933,4.42333,4.44332,4.44332,4.47132,4.47532,1.43178,1.42778,1.37579,1.35979,1.3418,1.3298,1.3098,1.2858,1.2938,1.2818,1.25581,1.34779,1.44978,1.46778,1.47178,1.48177,1.49377,1.49177,1.51777,1.51377,1.49977,1.51977,1.52377,1.54376,1.54976,1.54376,1.55976,1.55976,1.57176,1.57576,1.57576,1.59176,1.59376,1.60975,1.61575,1.61975,1.62775,1.63775,1.65375,1.65175,1.66575,1.68174,1.68174,1.69774,1.70574,1.70574,1.73174,1.72774,1.75173,1.74973,1.76573,1.77573,1.78573,1.80573,1.81372,1.81372,1.83372,1.84572,1.86772,1.87571,1.88771,1.91171,1.92571,1.93371,1.9597,1.9637,1.9917,1.9857,2.01969,2.03169,2.03569,2.05969,2.07168,2.09368,2.11768,2.13168,2.15967,2.16967,2.19967,2.21566,2.23166,2.25966,2.28365,2.27765,2.25766,2.23566,2.23166,2.21166,2.21966,2.20766,2.19767,2.21566,2.24766,4.41933,4.39133,4.38333,4.37533,4.35134,4.32334,4.30334,4.29935,4.28335,4.29135,4.25935,4.24335,4.21536,4.21136,4.19536,4.19536,4.17137,4.15137,4.15137,4.11537,4.12737,4.09538,3.79542,3.79142,3.87541,3.9314,4.03139,4.45332,4.44332,3.04754,3.03554,3.05353,3.08753,2.98755,2.98755,3.21951,3.2715,3.07753,3.03954,3.03554,2.85357,2.86556,2.91156,2.90956,3.01554,3.03754,3.01754,3.00754,2.89556,2.90156,2.88556,3.02154,3.37349,3.33949,2.95155,2.92156,2.91956,2.91156,2.91156,2.91956,2.95155,2.99954,3.2595,3.65944,4.18736,4.18336,4.19536,4.19536,2.79557,2.93355,2.97955,3.01954,3.03554,3.05554,3.08753,3.08753,3.12552,3.12552,3.12952,3.15352,3.13952,3.17352,3.69944,3.82142,3.89141,250,2.19167,2.17967,2.13567,2.08368,2.04369,2.04369,1.9837,1.9677,1.92371,1.69174,1.64975,1.63375,1.62775,1.62775,1.62375,1.63375,1.63775,1.64175,1.65775,1.67774,1.68774,1.90371,1.9477,1.9837,1.9797,1.9877,1.9757,1.93171,1.9557,1.9437,1.9637,1.89171,1.78173,1.76173,1.75173,1.76573,1.74573,1.73974,1.76373,1.75973,1.77973,1.77373,1.75373,1.79573,4.64729,4.6193,4.63129,4.63929,4.65529,4.67529,4.70328,4.71928,4.70328,4.33934,250,4.11537,4.09938,4.07538,4.01739,3.98539,3.98339,3.9614,3.97539,4.01539,1.70574,1.67774,1.65975,1.66575,1.64775,1.63975,1.62175,1.59976,1.65175,1.68974,1.69974,1.69774,1.63975,1.64575,1.63175,1.63575,1.64975,1.62775,1.63975,1.64575,1.64375,1.65375,1.64975,1.65175,1.65575,1.65775,1.67574,1.67175,1.68974,1.68974,1.69974,1.70574,1.71774,1.72974,1.73574,1.76173,1.76973,1.78373,1.81972,1.89171,250,250,250,250,5.05923,5.16521,5.15122,5.10922,5.09722,5.05923,5.03123,5.00924,4.97724,4.95525,4.92925,4.90325,4.89126,4.85326,4.85126,4.81727,4.52731,4.51531,4.49132,4.48332,4.45932,4.43532,4.42333,4.39533,4.39333,4.37533,4.35734,4.33134,4.31334,4.30534,4.28735,4.32134,4.38733,4.43732,4.47332,4.44732,4.43332,4.42533,4.26935,3.82742,3.81542,3.79942,3.80142,3.77942,3.77543,3.76943,3.74143,3.73943,3.72143,3.71543,3.69544,3.67544,3.65944,3.64345,3.63945,3.65744,3.63945,3.63345,3.61545,3.62345,3.60345,3.60545,3.58145,3.57146,2.75158,2.77758,2.77158,2.74758,2.71159,2.70559,2.68359,2.69559,2.71359,2.73358,2.75958,2.75758,2.81357,2.82957,3.00354,3.18152,3.2755,3.2735,3.2635,3.2615,3.2595,3.23951,3.24951,3.24351,3.23151,3.23951,3.22351,2.99754,2.98355,2.98555,2.99154,2.97555,2.99954,2.99154,2.98155,2.99354,2.97155,2.97755,2.97355,2.97755,2.98355,2.98155,2.98954,2.98755,2.97555,2.98555,2.96555,2.99154,4.01739,4.02139,4.02339,3.72943,3.57946,3.44348,3.2695,3.2555,3.2695,3.2755,3.2695,3.2735,3.2915,3.2815,3.3015,3.3075,3.3095,3.31949,3.3155,3.33749,3.32749,3.32749,4.04538,4.04738,4.12537,3.9674,3.82942,3.69744,3.51147,3.46547,3.48147,3.41148,3.46947,4.21136,4.21936,4.21936,4.23136,4.24935,4.25135,4.26135,3.56346,3.50347,3.45147,3.40548,3.40348,3.38348,3.38748,3.38149,3.37749,3.39948,3.39948,3.43748,3.47347,3.49947,3.59145,3.85141,3.84541,4.47132,4.52331,4.54331,3.9334,4.5813,4.17736,4.5953,4.62929,2.25366,2.19966,2.18567,2.17967,2.19967,2.23166,250,3.41948,2.06369,2.09168,2.07168,2.06369,2.07168,1.9917,1.9917};
+// std::vector<float> reference_scan_1 = {3.64145,3.66544,3.62545,3.62945,3.61945,3.61545,2.81157,2.77558,2.77758,2.74958,2.73158,2.72159,2.73358,2.75158,2.78158,2.78558,2.80757,2.83557,2.87756,3.2835,3.2935,3.2995,3.2955,3.2915,3.2915,3.2775,3.2835,3.2635,3.2755,3.2655,3.2535,3.2595,3.20351,3.04754,3.04354,4.01539,3.08353,3.07153,3.07753,3.06953,3.06553,3.06753,3.05553,3.06353,3.04354,3.03154,3.00954,3.00554,3.02954,250,2.99354,2.99554,4.01739,4.03539,4.03339,3.84741,3.61545,3.56346,3.35149,3.2675,3.2695,3.2815,3.2795,3.2955,3.2995,3.2955,3.3155,3.3155,3.33149,3.32349,3.32349,3.35149,3.33549,3.36549,4.08338,4.07138,4.10937,4.01539,3.86741,3.71343,3.47947,3.48547,3.48747,3.43148,3.48547,3.48147,4.22736,4.22936,4.25335,4.24735,4.24735,4.26935,4.27135,3.51946,4.27735,3.43148,3.40348,3.39148,3.39548,3.38948,3.38548,3.39748,3.40148,3.41148,3.45347,3.47147,3.51946,250,3.84541,4.37333,4.51931,4.53131,4.54331,3.9414,2.94555,2.91956,2.93555,2.21166,2.17767,2.18167,2.16767,2.17767,2.04769,1.91971,1.85572,1.9917,250,250,250,250,1.9917,1.9917,1.9917,1.9917,2.03169,1.9917,1.9517,1.9597,1.90771,1.86772,1.87971,1.87971,1.85972,1.85172,1.82772,1.79173,1.53977,1.52777,1.50777,1.50777,1.47977,1.47977,1.47977,1.45178,1.43978,1.46778,1.46778,1.42378,250,250,1.59576,250,1.59576,250,1.59576,1.52377,1.51577,1.48377,1.49577,1.47977,1.48377,1.48377,1.46778,1.44778,1.44378,1.41978,1.44778,1.41978,1.41179,1.43978,1.39579,1.40379,1.26781,1.21581,1.22381,1.20382,1.23181,1.19582,1.20382,1.18382,1.16382,1.16982,1.15582,1.16182,1.16782,1.14583,1.13983,1.13983,1.14183,1.14183,1.13183,1.12383,1.13583,1.11583,1.12383,1.13983,1.09983,1.09583,1.09983,1.09583,1.13183,1.19582,250,250,1.3158,1.27181,1.2838,1.27181,1.27181,1.27981,1.25181,1.27581,1.27781,1.26381,1.26781,1.25781,1.25781,1.25781,1.25781,1.26781,1.26781,1.25181,1.27781,1.27581,1.2958,250,250,250,1.23581,1.17982,1.16582,1.19582,1.23581,250,250,250,1.9617,1.9537,1.9397,1.9657,1.9617,1.9517,1.9597,250,4.47732,4.45932,4.45532,4.45732,4.45332,4.45532,4.45332,4.44732,4.45532,4.44332,4.44932,4.43932,4.43932,4.43932,4.43532,4.86526,4.95725,6.575,6.551,6.543,6.555,6.559,250,250,250,250,250,7.58685,8.64468,8.64468,8.65868,8.66468,8.66268,8.68068,8.69068,8.70467,8.70867,8.71067,8.73867,8.73067,4.98324,4.99124,4.98724,5.01124,5.00324,5.00924,5.01524,5.01724,5.04323,5.03923,5.04323,4.99924,4.88326,4.67129,4.6093,4.6213,4.6313,4.63329,4.64729,4.66729,4.65929,4.68129,4.69129,4.71128,4.72328,4.72928,4.75328,4.74928,4.77127,4.77527,4.78727,4.81127,4.81527,4.82726,4.84726,4.85326,4.88326,4.88126,4.90925,4.91725,4.92725,4.96124,3.09553,3.10153,3.04554,2.98755,2.94555,2.91556,2.87756,2.83157,2.79557,2.77558,2.43763,2.13767,2.13368,2.10168,2.11168,2.10368,2.13567,2.13168,2.14567,2.28165,2.31565,2.39164,2.40163,2.38564,2.36164,2.32165,2.30965,2.26566,2.22366,2.23366,2.24166,2.27765,2.29165,2.30165,2.31965,2.32165,2.33964,2.36564,2.36564,2.38764,2.39763,2.40963,2.41763,2.42563,2.44963,2.45563,2.47162,2.48962,2.50562,2.54361,2.54561,2.56361,2.58561,2.59361,2.6296,2.6456,2.6576,2.67759,2.67359,7.15891,7.17091,7.2349,7.29889,7.35888,9.08062,8.99263,8.91664,8.85065,8.76867,8.71067,8.64268,8.74867,8.58669,8.65868,8.75467,8.84265,8.91464,9.04262,9.10661,9.23859,9.33058,9.44656,9.55455,9.65853,9.77851,9.88649,10.0185,10.1425,10.2704,10.4224,10.5384,10.6944,10.8423,10.9863,11.1423,11.3983,11.5582,11.7342,11.9262,12.0302,3.76743,3.74743,3.74543,3.72543,3.73343,3.70944,3.70744,3.68944,3.68144,3.68744,3.67544,3.66144,3.66544,3.64944,3.63745,3.63545,3.61745,3.62145,3.60945,3.59745,3.59345,3.58145,3.58545,3.56746,3.57146,3.55346,3.54546,3.55746,3.53746,3.53546,3.53746,3.52546,3.52746,3.51546,3.50747,3.50747,3.48947,3.49547,3.49147,3.47547,3.48347,3.48147,3.48147,3.47747,3.46147,3.47147,3.46347,3.47147,3.45947,1.86972,1.87771,2.33164,2.37564,3.44548,3.44548,3.46347,3.45147,3.46547,3.46547,3.44148,3.45747,3.43148,3.45947,3.45747,3.44947,3.46147,3.44947,3.46547,3.45147,3.45347,3.46347,2.36564,2.37564,2.34364,1.87771,1.87971,1.87371,250,4.19936,4.01939,3.83942,3.63945,3.58545,4.16936,4.16337,3.32349,2.99154,2.82357,2.75958,2.75558,2.78558,2.80357,2.80757,2.81757,2.79957,250,250,250,2.01169,250,250,250,2.87356,2.87156,2.86556,2.88756,2.88156,2.88156,2.89556,2.90356,2.91756,2.92355,4.41333,4.43532,4.43532,4.45932,4.46932,4.46932,4.50331,4.50731,1.42378,1.40379,1.36379,1.37179,1.3378,1.3318,1.3018,1.2978,1.2858,1.26781,1.2998,1.43978,1.45178,1.48177,1.47178,1.49977,1.49377,1.50577,1.51177,1.50977,1.53177,1.53177,1.52377,1.55376,1.55176,1.56976,1.57176,1.57176,1.59576,1.59176,1.60376,1.61375,1.61175,1.62575,1.62975,1.64575,1.65175,1.64975,1.66775,1.67375,1.69374,1.70974,1.70374,1.71974,1.71774,1.72374,1.74973,1.75173,1.77573,1.77373,1.78773,1.80972,1.80972,1.82972,1.83772,1.84772,1.86572,1.86972,1.89771,1.91371,1.92171,1.9457,1.9557,1.9777,1.9917,2.00569,2.01969,2.02769,2.06769,2.07968,2.08768,2.11568,2.13168,2.16367,2.17167,2.17967,2.22366,2.23566,2.26765,2.27565,2.29565,2.28965,2.25566,2.26765,2.24366,2.23366,2.21966,2.22366,2.22566,2.22166,4.43133,4.41933,4.39133,4.35934,4.35534,4.32734,4.33134,4.29135,4.29935,4.29135,4.27535,4.27935,4.24335,4.23935,4.20336,4.19136,4.18336,4.16337,4.16737,4.13537,4.11537,4.08738,3.83142,3.86741,3.89141,4.04338,4.11137,4.47332,4.45732,4.45332,4.43532,4.43932,4.42133,4.40933,4.40333,4.38333,3.10353,3.09153,3.07153,3.08353,3.09553,3.09753,3.02154,2.98755,3.15552,3.39148,3.10553,3.09753,2.93955,2.87156,2.87156,2.89156,2.95155,3.02354,3.06753,3.04954,3.06353,3.04354,3.03954,2.97955,2.94955,3.2835,4.21536,3.00354,2.99954,2.96755,2.97155,2.96755,2.97955,2.98555,3.03154,3.57546,4.21136,4.21536,4.22336,4.21136,4.23535,2.86356,2.92755,2.99354,3.03154,3.06753,3.08553,3.09553,3.12752,3.13552,3.15752,3.16152,3.15752,3.18152,3.17152,3.85341,3.86341,3.87941,250,2.20766,2.12768,2.07168,2.05969,2.04369,1.9877,1.9557,1.85372,1.77973,1.72174,1.68174,1.65975,1.65175,1.65375,1.66375,1.65975,1.66575,1.68374,1.67574,1.71174,1.76373,1.82372,1.84372,1.84372,1.84972,1.85572,1.86372,1.87971,1.87371,1.88571,1.90171,1.86972,1.80572,1.78173,1.79373,1.78573,1.78173,1.79373,1.78373,1.79773,1.79773,1.79773,1.81172,1.86372,4.67129,4.67529,4.69129,4.71528,4.71928,4.75928,4.76727,4.36733,4.46732,4.46732,4.09938,4.06338,4.03738,4.03339,4.01339,4.00139,1.75373,1.70974,1.70774,1.68174,1.67175,1.66975,1.65375,1.66775,1.65575,1.63975,1.64775,1.62975,1.64175,1.63975,1.64775,1.64175,1.64175,1.65175,1.65375,1.66375,1.66775,1.66775,1.68974,1.68974,1.69974,1.71774,1.72574,1.73574,1.73774,1.78173,1.79573,1.81172,1.85572,1.88971,250,250,250,250,5.19121,5.2252,5.20121,5.16921,5.14122,5.09522,5.07923,5.07123,5.02723,5.01724,4.98524,4.96524,4.94725,4.90725,4.90125,4.86126,4.84526,4.82127,4.79527,4.77927,4.76327,4.73528,4.72928,4.69129,4.64329,4.48532,4.47732,4.6153,4.5973,4.5893,4.5633,4.54531,4.53731,4.51131,4.50731,4.48932,4.46932,4.45932,3.99139,3.85941,3.84341,3.82742,3.82742,3.80342,3.81142,3.78742,3.77742,3.76543,3.74343,3.74743,3.72143,3.70544,3.69744,3.67344,3.66744,3.67744,3.66344,3.67144};
+
+std::vector<float> reference_scan_1 ={3.64145,3.66544,3.62545,3.62945,3.61945,3.61545,2.81157,2.77558,2.77758,2.74958,2.73158,2.72159,2.73358,2.75158,2.78158,2.78558,2.80757,2.83557,2.87756,3.2835,3.2935,3.2995,3.2955,3.2915,3.2915,3.2775,3.2835,3.2635,3.2755,3.2655,3.2535,3.2595,3.20351,3.04754,3.04354,4.01539,3.08353,3.07153,3.07753,3.06953,3.06553,3.06753,3.05553,3.06353,3.04354,3.03154,3.00954,3.00554,3.02954,250,2.99354,2.99554,4.01739,4.03539,4.03339,3.84741,3.61545,3.56346,3.35149,3.2675,3.2695,3.2815,3.2795,3.2955,3.2995,3.2955,3.3155,3.3155,3.33149,3.32349,3.32349,3.35149,3.33549,3.36549,4.08338,4.07138,4.10937,4.01539,3.86741,3.71343,3.47947,3.48547,3.48747,3.43148,3.48547,3.48147,4.22736,4.22936,4.25335,4.24735,4.24735,4.26935,4.27135,3.51946,4.27735,3.43148,3.40348,3.39148,3.39548,3.38948,3.38548,3.39748,3.40148,3.41148,3.45347,3.47147,3.51946,250,3.84541,4.37333,4.51931,4.53131,4.54331,3.9414,2.94555,2.91956,2.93555,2.21166,2.17767,2.18167,2.16767,2.17767,2.04769,1.91971,1.85572,1.9917,250,250,250,250,1.9917,1.9917,1.9917,1.9917,2.03169,1.9917,1.9517,1.9597,1.90771,1.86772,1.87971,1.87971,1.85972,1.85172,1.82772,1.79173,1.53977,1.52777,1.50777,1.50777,1.47977,1.47977,1.47977,1.45178,1.43978,1.46778,1.46778,1.42378,250,250,1.59576,250,1.59576,250,1.59576,1.52377,1.51577,1.48377,1.49577,1.47977,1.48377,1.48377,1.46778,1.44778,1.44378,1.41978,1.44778,1.41978,1.41179,1.43978,1.39579,1.40379,1.26781,1.21581,1.22381,1.20382,1.23181,1.19582,1.20382,1.18382,1.16382,1.16982,1.15582,1.16182,1.16782,1.14583,1.13983,1.13983,1.14183,1.14183,1.13183,1.12383,1.13583,1.11583,1.12383,1.13983,1.09983,1.09583,1.09983,1.09583,1.13183,1.19582,250,250,1.3158,1.27181,1.2838,1.27181,1.27181,1.27981,1.25181,1.27581,1.27781,1.26381,1.26781,1.25781,1.25781,1.25781,1.25781,1.26781,1.26781,1.25181,1.27781,1.27581,1.2958,250,250,250,1.23581,1.17982,1.16582,1.19582,1.23581,250,250,250,1.9617,1.9537,1.9397,1.9657,1.9617,1.9517,1.9597,250,4.47732,4.45932,4.45532,4.45732,4.45332,4.45532,4.45332,4.44732,4.45532,4.44332,4.44932,4.43932,4.43932,4.43932,4.43532,4.86526,4.95725,6.575,6.551,6.543,6.555,6.559,250,250,250,250,250,7.58685,8.64468,8.64468,8.65868,8.66468,8.66268,8.68068,8.69068,8.70467,8.70867,8.71067,8.73867,8.73067,4.98324,4.99124,4.98724,5.01124,5.00324,5.00924,5.01524,5.01724,5.04323,5.03923,5.04323,4.99924,4.88326,4.67129,4.6093,4.6213,4.6313,4.63329,4.64729,4.66729,4.65929,4.68129,4.69129,4.71128,4.72328,4.72928,4.75328,4.74928,4.77127,4.77527,4.78727,4.81127,4.81527,4.82726,4.84726,4.85326,4.88326,4.88126,4.90925,4.91725,4.92725,4.96124,3.09553,3.10153,3.04554,2.98755,2.94555,2.91556,2.87756,2.83157,2.79557,2.77558,2.43763,2.13767,2.13368,2.10168,2.11168,2.10368,2.13567,2.13168,2.14567,2.28165,2.31565,2.39164,2.40163,2.38564,2.36164,2.32165,2.30965,2.26566,2.22366,2.23366,2.24166,2.27765,2.29165,2.30165,2.31965,2.32165,2.33964,2.36564,2.36564,2.38764,2.39763,2.40963,2.41763,2.42563,2.44963,2.45563,2.47162,2.48962,2.50562,2.54361,2.54561,2.56361,2.58561,2.59361,2.6296,2.6456,2.6576,2.67759,2.67359,7.15891,7.17091,7.2349,7.29889,7.35888,9.08062,8.99263,8.91664,8.85065,8.76867,8.71067,8.64268,8.74867,8.58669,8.65868,8.75467,8.84265,8.91464,9.04262,9.10661,9.23859,9.33058,9.44656,9.55455,9.65853,9.77851,9.88649,10.0185,10.1425,10.2704,10.4224,10.5384,10.6944,10.8423,10.9863,11.1423,11.3983,11.5582,11.7342,11.9262,12.0302,3.76743,3.74743,3.74543,3.72543,3.73343,3.70944,3.70744,3.68944,3.68144,3.68744,3.67544,3.66144,3.66544,3.64944,3.63745,3.63545,3.61745,3.62145,3.60945,3.59745,3.59345,3.58145,3.58545,3.56746,3.57146,3.55346,3.54546,3.55746,3.53746,3.53546,3.53746,3.52546,3.52746,3.51546,3.50747,3.50747,3.48947,3.49547,3.49147,3.47547,3.48347,3.48147,3.48147,3.47747,3.46147,3.47147,3.46347,3.47147,3.45947,1.86972,1.87771,2.33164,2.37564,3.44548,3.44548,3.46347,3.45147,3.46547,3.46547,3.44148,3.45747,3.43148,3.45947,3.45747,3.44947,3.46147,3.44947,3.46547,3.45147,3.45347,3.46347,2.36564,2.37564,2.34364,1.87771,1.87971,1.87371,250,4.19936,4.01939,3.83942,3.63945,3.58545,4.16936,4.16337,3.32349,2.99154,2.82357,2.75958,2.75558,2.78558,2.80357,2.80757,2.81757,2.79957,250,250,250,2.01169,250,250,250,2.87356,2.87156,2.86556,2.88756,2.88156,2.88156,2.89556,2.90356,2.91756,2.92355,4.41333,4.43532,4.43532,4.45932,4.46932,4.46932,4.50331,4.50731,1.42378,1.40379,1.36379,1.37179,1.3378,1.3318,1.3018,1.2978,1.2858,1.26781,1.2998,1.43978,1.45178,1.48177,1.47178,1.49977,1.49377,1.50577,1.51177,1.50977,1.53177,1.53177,1.52377,1.55376,1.55176,1.56976,1.57176,1.57176,1.59576,1.59176,1.60376,1.61375,1.61175,1.62575,1.62975,1.64575,1.65175,1.64975,1.66775,1.67375,1.69374,1.70974,1.70374,1.71974,1.71774,1.72374,1.74973,1.75173,1.77573,1.77373,1.78773,1.80972,1.80972,1.82972,1.83772,1.84772,1.86572,1.86972,1.89771,1.91371,1.92171,1.9457,1.9557,1.9777,1.9917,2.00569,2.01969,2.02769,2.06769,2.07968,2.08768,2.11568,2.13168,2.16367,2.17167,2.17967,2.22366,2.23566,2.26765,2.27565,2.29565,2.28965,2.25566,2.26765,2.24366,2.23366,2.21966,2.22366,2.22566,2.22166,4.43133,4.41933,4.39133,4.35934,4.35534,4.32734,4.33134,4.29135,4.29935,4.29135,4.27535,4.27935,4.24335,4.23935,4.20336,4.19136,4.18336,4.16337,4.16737,4.13537,4.11537,4.08738,3.83142,3.86741,3.89141,4.04338,4.11137,4.47332,4.45732,4.45332,4.43532,4.43932,4.42133,4.40933,4.40333,4.38333,3.10353,3.09153,3.07153,3.08353,3.09553,3.09753,3.02154,2.98755,3.15552,3.39148,3.10553,3.09753,2.93955,2.87156,2.87156,2.89156,2.95155,3.02354,3.06753,3.04954,3.06353,3.04354,3.03954,2.97955,2.94955,3.2835,4.21536,3.00354,2.99954,2.96755,2.97155,2.96755,2.97955,2.98555,3.03154,3.57546,4.21136,4.21536,4.22336,4.21136,4.23535,2.86356,2.92755,2.99354,3.03154,3.06753,3.08553,3.09553,3.12752,3.13552,3.15752,3.16152,3.15752,3.18152,3.17152,3.85341,3.86341,3.87941,250,2.20766,2.12768,2.07168,2.05969,2.04369,1.9877,1.9557,1.85372,1.77973,1.72174,1.68174,1.65975,1.65175,1.65375,1.66375,1.65975,1.66575,1.68374,1.67574,1.71174,1.76373,1.82372,1.84372,1.84372,1.84972,1.85572,1.86372,1.87971,1.87371,1.88571,1.90171,1.86972,1.80572,1.78173,1.79373,1.78573,1.78173,1.79373,1.78373,1.79773,1.79773,1.79773,1.81172,1.86372,4.67129,4.67529,4.69129,4.71528,4.71928,4.75928,4.76727,4.36733,4.46732,4.46732,4.09938,4.06338,4.03738,4.03339,4.01339,4.00139,1.75373,1.70974,1.70774,1.68174,1.67175,1.66975,1.65375,1.66775,1.65575,1.63975,1.64775,1.62975,1.64175,1.63975,1.64775,1.64175,1.64175,1.65175,1.65375,1.66375,1.66775,1.66775,1.68974,1.68974,1.69974,1.71774,1.72574,1.73574,1.73774,1.78173,1.79573,1.81172,1.85572,1.88971,250,250,250,250,5.19121,5.2252,5.20121,5.16921,5.14122,5.09522,5.07923,5.07123,5.02723,5.01724,4.98524,4.96524,4.94725,4.90725,4.90125,4.86126,4.84526,4.82127,4.79527,4.77927,4.76327,4.73528,4.72928,4.69129,4.64329,4.48532,4.47732,4.6153,4.5973,4.5893,4.5633,4.54531,4.53731,4.51131,4.50731,4.48932,4.46932,4.45932,3.99139,3.85941,3.84341,3.82742,3.82742,3.80342,3.81142,3.78742,3.77742,3.76543,3.74343,3.74743,3.72143,3.70544,3.69744,3.67344,3.66744,3.67744,3.66344,3.67144};
+std::vector<float> target_scan_1 ={1.93771,1.93171,1.9437,1.9597,1.9537,1.9737,1.9777,1.9757,1.9937,1.9617,1.89771,1.87371,1.85772,1.86372,1.85572,1.86372,1.86172,1.86372,1.88371,1.89171,1.91971,4.73128,4.74128,4.76927,4.76927,4.78927,4.80327,4.81927,4.83526,4.85126,4.31534,4.23136,4.19536,4.16337,4.14137,4.13537,1.82572,1.79173,1.78373,1.75373,1.76173,1.74773,1.73974,1.72774,1.71574,1.71574,1.70974,1.70374,1.70974,1.70374,1.71174,1.70774,1.70374,1.71174,1.69974,1.71574,1.71374,1.70774,1.71774,1.71374,1.72374,1.72574,1.74773,1.75773,1.75373,1.78173,1.77773,1.77173,1.79573,1.79773,1.82972,1.83772,1.85572,1.87571,1.92571,1.9737,250,250,250,250,250,250,250,5.14722,5.2752,5.2692,5.2252,5.18921,5.17521,5.13322,5.12122,5.08523,5.04923,5.03123,5.00524,4.98324,4.95525,4.92525,4.91325,4.86926,4.86126,4.83926,4.81727,4.80527,4.77527,4.75528,4.67729,4.53931,4.54331,4.65929,4.65529,4.63529,4.6153,4.6033,4.5773,4.5633,4.55131,4.52131,4.52131,4.48732,3.9194,3.89541,3.88741,3.87941,3.85941,3.85941,3.83542,3.81542,3.81142,3.78742,3.78142,3.76343,3.74943,3.73343,3.70744,3.72343,3.72143,3.70344,3.70544,3.68344,3.68344,3.66744,3.65144,3.65544,2.85157,2.83557,2.81357,2.78358,2.77158,2.76358,2.76358,2.76358,2.79357,2.82157,2.79557,2.85557,2.89356,3.14552,3.2775,3.32349,3.32949,3.3075,3.2995,3.3055,3.2975,3.3055,3.2855,3.2795,3.2855,3.2675,3.04954,3.02354,3.01954,3.03354,3.01754,3.02554,3.01354,3.00354,3.02154,3.00954,3.01354,3.00354,3.00354,3.01954,2.99954,3.01154,3.00754,3.01354,3.00754,2.99154,3.01354,4.03339,4.02939,4.03539,3.82342,3.62345,3.74343,3.2695,3.2815,3.2735,3.2875,3.2895,3.2875,3.2935,3.2955,3.3115,3.3135,3.3135,3.32949,3.32149,3.34349,3.33749,4.12537,4.10737,4.07138,4.05538,4.03738,3.85941,3.44947,3.42548,3.53146,3.44348,3.43548,3.48547,4.19136,4.20336,4.21336,3.59145,3.59145,3.59145,3.59145,3.59145,3.47147,3.45147,3.42348,3.45147,3.42348,3.34749,3.34749,3.44348,250,250,250,2.95955,2.93355,2.93555,2.92955,2.91556,2.88756,2.88756,2.92355,4.50331,2.19167,2.16767,2.13368,2.04369,1.91971,1.85972,1.83172,1.85972,1.79173,1.76773,1.73174,1.79173,1.84772,1.79173,1.79173,1.86372,1.79173,1.86372,1.89171,1.84772,1.89171,1.87571,1.89171,1.84372,1.85572,1.66775,1.51577,1.45978,1.47977,1.47178,1.42778,1.43178,1.41179,1.40779,1.37979,1.39579,1.39579,1.37579,1.35579,1.35979,1.3078,1.3398,1.3278,1.39579,1.39579,1.39579,250,1.39579,1.43578,1.44778,1.39579,1.45978,1.41578,1.42778,1.43978,1.41179,1.39579,1.36779,1.37979,1.37179,1.3158,1.3318,1.21182,1.17582,1.15582,1.14783,1.11183,1.12383,1.11183,1.12183,1.09783,1.10783,1.10183,1.08783,1.08783,1.08384,1.08384,1.07384,1.06784,1.06984,1.05784,1.06184,1.05584,1.04784,1.05784,1.03784,1.05184,1.04184,1.03584,1.05584,1.01984,1.02384,1.03584,1.01585,1.00785,1.00785,1.09583,250,250,1.19582,250,1.19582,1.17982,1.19582,1.17782,1.17582,1.18782,1.17582,1.17182,1.17382,1.16582,1.17982,1.16782,1.13583,1.12783,1.09583,1.12783,1.08384,1.09583,1.08384,1.07584,1.06384,1.05184,1.03384,1.05384,1.05184,1.04784,1.04184,1.05584,1.05584,1.05984,1.06784,1.12383,1.84772,1.83972,1.85172,1.85972,1.84772,1.85572,1.85972,1.89171,250,4.36734,4.36334,4.37333,4.35534,4.36534,4.36933,4.35934,4.36733,4.35134,4.34734,4.36134,4.33734,4.34934,4.33734,4.35334,4.34134,4.77927,4.85926,4.90325,6.45502,6.45902,6.44702,6.45102,8.5347,250,7.61484,7.59484,8.5287,8.5347,8.5427,8.5447,8.5527,8.5627,8.5627,8.5727,8.57869,8.58269,8.60069,8.59469,8.61669,8.62469,4.86726,4.88326,4.88926,4.89725,4.89925,4.90725,4.92325,4.91525,4.94125,4.93525,4.94725,4.90125,4.79127,4.54931,4.52131,4.51731,4.54331,4.53731,4.55331,4.5633,4.5693,4.6033,4.6073,4.6193,4.6233,4.64729,4.65329,4.66729,4.68129,4.69528,4.72328,4.72128,4.73528,4.75728,4.75728,4.79327,4.79927,4.80727,4.82527,4.83126,4.85726,4.87526,4.89126,3.02154,2.99954,2.98155,2.91556,2.87756,2.85357,2.80757,2.78958,2.75158,2.70359,2.67559,2.6176,2.06569,2.04769,2.03569,2.04369,2.03369,2.03969,2.04969,2.06169,2.10168,2.22166,2.30765,2.32165,2.31165,2.29765,2.25766,2.24566,2.21766,2.17367,2.17767,2.16567,2.19967,2.21966,2.22566,2.24366,2.23966,2.27165,2.27965,2.29365,2.31965,2.32765,2.35564,2.35764,2.36564,2.39164,2.40163,2.41763,2.43363,2.44563,2.47162,2.47962,2.51762,2.52162,2.54161,2.56561,2.57961,2.6056,2.59161,2.6076,7.2149,7.2469,7.30689,9.00663,8.91864,8.85865,8.77066,8.71467,8.63868,8.57469,8.69468,8.5327,8.62469,8.70867,8.80066,8.90464,8.99663,9.10061,9.2046,9.29259,9.43456,9.51655,9.66053,9.75451,9.88649,10.0145,10.1425,10.2784,10.4224,10.5424,10.7024,10.8423,11.0103,11.1783,11.4323,11.6122,11.7702,11.9642,12.0702,12.0462,3.74743,3.70744,3.70944,3.70744,3.69144,3.68144,3.66544,3.66944,3.64944,3.64544,3.64744,3.62345,3.62745,3.61145,3.60545,3.60545,3.58945,3.59345,3.57346,3.57346,3.56346,3.54146,3.55546,3.53746,3.53746,3.54146,3.53346,3.52746,3.51746,3.50947,3.51147,3.49547,3.50347,3.49547,3.48747,3.48947,3.47547,3.47947,3.47347,3.46147,3.46947,3.46147,3.46947,3.46347,3.45147,3.46347,3.44548,3.45347,3.45347,3.44748,3.45147,250,1.86972,1.87172,1.86772,3.43548,3.43348,3.46547,3.44548,3.43548,3.44947,3.44348,3.46747,3.44947,3.43748,3.44747,3.44947,3.45547,3.45547,3.45547,3.46347,3.45747,3.47147,2.36764,2.37164,2.35964,3.47547,1.89771,1.88971,1.87971,1.91171,3.68144,3.59345,4.16936,4.18736,4.20936,3.2695,250,2.79158,2.77758,2.78958,2.81557,2.82357,2.81957,2.82357,2.85357,2.84357,250,250,250,2.09168,2.04369,250,250,2.89356,2.89956,2.89956,2.91556,2.91956,2.92156,2.93755,2.93555,4.46932,4.47532,4.48332,4.50331,4.51331,4.53331,4.54331,4.55131,4.5813,4.54931,4.52131,1.49577,1.45978,1.43978,1.40379,1.38379,1.37979,1.35579,1.3318,1.3218,1.3318,1.3138,1.3018,1.3118,1.49977,1.52577,1.52377,1.52777,1.53977,1.54376,1.56376,1.57176,1.56376,1.58776,1.58376,1.60376,1.60376,1.60975,1.62575,1.62975,1.64575,1.64575,1.65375,1.66775,1.66575,1.68774,1.70174,1.70374,1.71374,1.72574,1.74373,1.74573,1.75573,1.78573,1.78973,1.80173,1.81772,1.81772,1.84172,1.84972,1.86772,1.87371,1.88971,1.90971,1.91371,1.9457,1.9617,1.9737,1.9897,1.9997,2.02369,2.03169,2.04569,2.07968,2.08768,2.12168,2.13368,2.13967,2.17967,2.18767,2.21966,2.23966,2.24366,2.27965,2.29965,2.34364,2.36164,2.37564,2.34364,2.32765,2.33564,2.31165,2.29165,2.29165,2.29565,2.29165,2.29165,4.49132,4.46332,4.43532,4.43133,4.41533,4.39933,4.38333,4.36334,4.33534,4.34734,4.30334,4.29535,4.27935,4.28335,4.29135,4.24735,4.26735,4.22736,4.19936,4.08738,3.87141,3.9594,4.03139,4.23136,4.55131,4.54531,4.52931,4.51731,4.52131,4.50531,4.50131,4.48932,4.47532,4.46932,3.2755,3.21951,3.21151,3.20751,3.24351,3.24151,3.11153,3.11553,3.12552,3.13152,3.09153,3.01954,2.94755,2.96355,3.03554,3.04354,3.09753,3.09953,3.09953,3.07753,3.08953,3.07553,3.01954,3.09353,3.14352,3.09153,3.46547,3.13152,3.09953,3.09153,3.09353,3.13152,3.17352,3.76143,4.31734,4.31934,4.30934,4.31734,4.30934,4.32534,4.31334,4.30934,4.30934,3.9354,3.9174,3.61945,3.9314,3.9394,3.9374,3.9494,3.9454,3.9394,3.9654,3.9454,3.99139,2.09168,2.17167,2.19167,2.08768,2.08768,2.03169,1.88771,1.87971,1.85372,1.83372,1.78973,1.74973,1.74773,1.73774,1.75173,1.74573,1.74773,1.76173,1.75773,1.78173,1.79173};
diff --git a/test/gtest_loop_closure_falko.cpp b/test/gtest_loop_closure_falko.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..be5197e979e390282c464c0babdf67ca3b953741
--- /dev/null
+++ b/test/gtest_loop_closure_falko.cpp
@@ -0,0 +1,313 @@
+#include "../src/loop_closure_base.h"
+#include "../src/loop_closure_falko.h"
+// #include "testData2.h"
+#include "data/scan_data.h"
+#include "gtest/utils_gtest.h"
+#include "matplotlibcpp.h"
+
+using namespace laserscanutils;
+namespace plt = matplotlibcpp;
+
+TEST(loop_closure_falko, TestLoopClosureFalkoAllFunctions)
+{
+    // Initialization
+    int             scan_size = 1440;
+    LaserScan       scan, scan2;
+    LaserScanParams laser_params;
+    laser_params.angle_min_ = 0;
+    laser_params.angle_max_ = 2.0 * M_PI;
+    laser_params.angle_step_ = 0.00701248;
+    laser_params.range_max_ = 50;
+    for (int i = 0; i < scan_size; i++)
+        {
+            scan.ranges_raw_.push_back(testRanges1[i]);
+            scan2.ranges_raw_.push_back(testRanges2[i]);
+        }
+
+    ParameterLoopClosureFalko param;
+    param.matcher_distance_th_ = 0.3;
+    LoopClosureFalkoAht<bsc, bscExtractor> loop_cl_falko(param);
+
+    // Test convert2LaserScanFALKO
+    std::shared_ptr<falkolib::LaserScan> scan_falko = loop_cl_falko.convert2LaserScanFALKO(scan, laser_params);
+    int                                  firstPoint = scan_falko->ranges[0];
+
+    ASSERT_EQ(firstPoint, 250);
+
+    // Test extractScene2
+    auto new_scene         = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan,
+    laser_params)); auto new_scene2        =
+    std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan2, laser_params)); int detectedKeypoints
+    = new_scene->keypoints_list_.size(); int  detectedDescriptors = new_scene->descriptors_list_.size();
+    ASSERT_EQ(detectedKeypoints, 18);
+    ASSERT_EQ(detectedDescriptors, 18);
+
+    // Test matchScene
+    auto new_match = loop_cl_falko.matchScene(new_scene, new_scene);
+    ASSERT_EQ(new_match->keypoints_number_match, 18);
+
+    std::list<std::shared_ptr<SceneBase>> ref_scenes;
+    ref_scenes.emplace_back(new_scene);
+    ref_scenes.emplace_back(new_scene2);
+
+    auto matchings = loop_cl_falko.findLoopClosure(ref_scenes, new_scene);
+
+    ASSERT_EQ(matchings.size(), 2);
+    auto best_match = matchings.rbegin()->second;
+    ASSERT_EQ(best_match->match, true);
+    ASSERT_EQ(best_match->scene_1, new_scene);
+    ASSERT_EQ(best_match->scene_2, new_scene);
+}
+
+TEST(loop_closure_falko, TestDescriptorsRotation)
+{
+    // Initialization
+    int             scan_size = 1440;
+    LaserScan       scan_1, scan2, scan_2;
+    LaserScanParams laser_params;
+
+    laser_params.angle_min_  = 0;
+    laser_params.angle_max_  = 2.0 * M_PI;
+    laser_params.angle_step_ = laser_params.angle_max_ / 1440;
+    laser_params.range_max_ = 50;
+
+    for (int i = 0; i < scan_size; i++)
+        {
+            scan_1.ranges_raw_.push_back(testRanges1[i]);
+            scan_2.ranges_raw_.push_back(testRanges1[i]);
+            scan2.ranges_raw_.push_back(testRanges2[i]);
+        }
+    // Rotate scans
+    int rot = 800;
+    std::rotate(scan_2.ranges_raw_.begin(), scan_2.ranges_raw_.begin() + rot, scan_2.ranges_raw_.end());
+
+    ParameterLoopClosureFalko param;
+    param.matcher_distance_th_ = 0.3;
+    LoopClosureFalkoAht<bsc, bscExtractor> loop_cl_falko(param);
+
+    // Test extractScene
+    auto new_scene   = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan_1, laser_params));
+    auto new_scene_2 = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan_2, laser_params));
+    auto key_1       = new_scene->keypoints_list_;
+    auto key_2       = new_scene_2->keypoints_list_;
+    auto desc_1      = new_scene->descriptors_list_;
+    auto desc_2      = new_scene_2->descriptors_list_rotated;
+
+    int radialRingNumber     = 8;
+    int circularSectorNumber = 16;
+
+    int    acum_distance = 0;
+    double asso_dist[key_1.size()][key_2.size()];
+    double min_dist_vector[key_1.size()];
+    for (int i = 0; i < desc_1.size(); i++)
+        {
+            double min_dist = 1000;
+            int    asso_number;
+            for (int j = 0; j < desc_2.size(); j++)
+                {
+
+                    acum_distance += desc_1[i].distance(desc_2[j]);
+                    asso_dist[i][j] = desc_1[i].distance(desc_2[j]);
+                    if (asso_dist[i][j] < min_dist)
+                        {
+                            min_dist    = asso_dist[i][j];
+                            asso_number = j;
+                        }
+                }
+            // std::cout << "pair : " << i << " , " << asso_number << " , distance : " << min_dist << std::endl;
+        }
+
+    // for (int i = 0; i < desc_1.size(); i++)
+    //     {
+    //         for (int j = 0; j < desc_2.size(); j++)
+    //             {
+    //                 if (key_1[i].index == key_2[j].index + rot or key_1[i].index == key_2[j].index + rot + 1 or
+    //                     key_1[i].index == key_2[j].index - 1440 + rot)
+    //                     {
+
+    //                         std::cout << "pair : " << i << " , " << j
+    //                                   << " , distance : " << desc_1[i].distance(desc_2[j]) << std::endl;
+
+    //                         acum_distance += desc_1[i].distance(desc_2[j]);
+
+    //                         // grid to x and y
+    //                         std::vector<int> x_pos, x_pos_rotated;
+    //                         std::vector<int> y_pos, y_pos_rotated;
+
+    //                         int  desc_1_number = i;
+    //                         int  desc_2_number = j;
+    //                         auto grid_1        = new_scene->descriptors_list_rotated[i].grid;
+    //                         auto grid_2        = new_scene_2->descriptors_list_rotated[j].grid;
+
+    //                         for (int i = 0; i < radialRingNumber; i++)
+    //                             for (int j = 0; j < circularSectorNumber; j++)
+    //                                 {
+    //                                     if (grid_1[i][j] > 0)
+    //                                         {
+    //                                             x_pos.push_back(i);
+    //                                             y_pos.push_back(j);
+    //                                         }
+
+    //                                     if (grid_2[i][j] > 0)
+    //                                         {
+    //                                             x_pos_rotated.push_back(i);
+    //                                             y_pos_rotated.push_back(j);
+    //                                         }
+    //                                 }
+
+    //                         // Plotting descriptors
+    //                         // plt::title("NNMatcher BSC only keypoints");
+    //                         // plt::subplot(2, 1, 1);
+    //                         // plt::xlabel(" descriprtor not rotated");
+    //                         // plt::plot(x_pos, y_pos, "ob");
+
+    //                         // plt::subplot(2, 1, 2);
+    //                         // plt::xlabel(" descriprtor rotated");
+    //                         // plt::plot(x_pos_rotated, y_pos_rotated, "or");
+    //                         // plt::show();
+    //                     }
+    //             }
+    //     }
+}
+
+TEST(loop_closure_falko, TestMatch)
+{
+    // Initialization
+    int             scan_size = 1440;
+    LaserScan       scan_1, scan_2, scan_3, scan_target, scan_ref;
+    LaserScanParams laser_params;
+
+    laser_params.angle_min_  = 0;
+    laser_params.angle_max_  = 2.0 * M_PI;
+    laser_params.angle_step_ = laser_params.angle_max_ / 1440;
+    laser_params.range_max_ = 50;
+
+    for (int i = 0; i < scan_size; i++)
+        {
+            scan_1.ranges_raw_.push_back(testRanges1[i]);
+            scan_2.ranges_raw_.push_back(testRanges1[i]);
+            scan_3.ranges_raw_.push_back(testRanges2[i]);
+        }
+
+    // Rotate scans
+    int rot = 800;
+    std::rotate(scan_2.ranges_raw_.begin(), scan_2.ranges_raw_.begin() + rot, scan_2.ranges_raw_.end());
+
+    ParameterLoopClosureFalko param;
+    param.matcher_distance_th_ = 100;
+    param.matcher_ddesc_th_    = 5;
+    LoopClosureFalkoAht<bsc, bscExtractor> loop_cl_falko(param);
+
+    // Test extractScene
+    auto new_scene_1 = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan_1, laser_params));
+    auto new_scene_2 = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan_2, laser_params));
+    auto new_scene_3 = std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko.extractScene(scan_3, laser_params));
+
+    auto match_1_2 = loop_cl_falko.matchScene(new_scene_1, new_scene_2);
+
+    std::vector<std::pair<int, int>> asso_1_2;
+    for (auto asso : match_1_2->associations)
+        if (asso.second != -1)
+            asso_1_2.push_back(asso);
+}
+
+TEST(loop_closure_falko, TestMatch2)
+{
+
+    // Initialization
+    int             scan_size = 1440;
+    LaserScan       scan_target, scan_ref;
+    LaserScanParams laser_params;
+
+    laser_params.angle_min_  = 0;
+    laser_params.angle_max_  = 2.0 * M_PI;
+    laser_params.angle_step_ = laser_params.angle_max_ / 1440;
+    laser_params.range_max_  = 100;
+
+    // ** TEST WITH TARGET AND REFERENCE SCENE
+    // std::cout << "scan size : " << target_scan_1.size() << std::endl;
+    for (int i = 0; i < target_scan_1.size(); i++)
+        {
+            scan_target.ranges_raw_.push_back(target_scan_1[i]);
+            scan_ref.ranges_raw_.push_back(reference_scan_1[i]);
+        }
+
+    ParameterLoopClosureFalko param;
+    param.use_descriptors_     = true;
+    param.matcher_distance_th_ = 100;
+    param.matcher_ddesc_th_    = 20;
+    param.nms_radius_          = 0.1;
+    param.neigh_b_             = 0.1;
+    param.b_ratio_             = 4;
+    param.enable_subbeam_      = false;
+
+    laser_params.angle_step_ = 0.00701248;
+
+    LoopClosureFalkoAht<bsc, bscExtractor> loop_cl_falko_2(param);
+    auto                                   new_scene_target =
+        std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko_2.extractScene(scan_target, laser_params));
+    auto new_scene_reference =
+        std::static_pointer_cast<SceneFalko<bsc>>(loop_cl_falko_2.extractScene(scan_ref, laser_params));
+
+    // std::cout << "keypoints target size : " << new_scene_target->keypoints_list_.size() << std::endl;
+    // std::cout << "keypoints reference size : " << new_scene_reference->keypoints_list_.size() << std::endl;
+
+    auto match_r_t = loop_cl_falko_2.matchScene(new_scene_reference, new_scene_target);
+    for (int i = 0; i < match_r_t->associations.size(); i++)
+        if (match_r_t->associations[i].second != -1)
+            {
+                // std::cout << "id first : " << match_r_t->associations[i].first << std::endl;
+                // std::cout << "id second : " << match_r_t->associations[i].second << std::endl;
+            }
+
+    // std::cout << "transform : " << match_r_t->transform_vector.transpose() << std::endl;
+
+    auto key_ref    = new_scene_reference->keypoints_list_;
+    auto key_target = new_scene_target->keypoints_list_;
+
+    std::vector<double> x_ref_all, x_target_all;
+    std::vector<double> y_ref_all, y_target_all;
+
+    // Plotting keypoints scenes
+    for (int i = 0; i < key_ref.size(); i++)
+        {
+            x_ref_all.push_back(key_ref[i].point.x());
+            y_ref_all.push_back(key_ref[i].point.y());
+        }
+
+    for (int i = 0; i < key_target.size(); i++)
+        {
+            x_target_all.push_back(key_target[i].point.x());
+            y_target_all.push_back(key_target[i].point.y());
+        }
+
+    plt::title("AHTMatcher BSC without descriptors");
+    plt::plot(x_ref_all, y_ref_all, "ob");
+    plt::plot(x_target_all, y_target_all, "or");
+
+    std::vector<double> x_ref, x_target;
+    std::vector<double> y_ref, y_target;
+    for (auto asso : match_r_t->associations)
+        if (asso.second != -1)
+            {
+                // auto a = key_ref[asso.first].point.x();
+                x_ref.push_back(key_ref[asso.first].point.x());
+                y_ref.push_back(key_ref[asso.first].point.y());
+
+                x_target.push_back(key_target[asso.second].point.x());
+                y_target.push_back(key_target[asso.second].point.y());
+            }
+
+    for (int i = 0; i < x_ref.size(); i++)
+        {
+            plt::plot({x_ref[i], x_target[i]}, {y_ref[i], y_target[i]}, "g");
+        }
+
+    // plt::show();
+}
+
+int main(int argc, char **argv)
+{
+    testing::InitGoogleTest(&argc, argv);
+    return RUN_ALL_TESTS();
+}
diff --git a/test/matplotlibcpp.h b/test/matplotlibcpp.h
new file mode 100644
index 0000000000000000000000000000000000000000..23553ae343df4a47c1ac1eb929dd498bf1866800
--- /dev/null
+++ b/test/matplotlibcpp.h
@@ -0,0 +1,2555 @@
+#pragma once
+
+// Python headers must be included before any system headers, since
+// they define _POSIX_C_SOURCE
+#include <Python.h>
+
+#include <vector>
+#include <map>
+#include <array>
+#include <numeric>
+#include <algorithm>
+#include <stdexcept>
+#include <iostream>
+#include <cstdint> // <cstdint> requires c++11 support
+#include <functional>
+
+#ifndef WITHOUT_NUMPY
+#  define NPY_NO_DEPRECATED_API NPY_1_7_API_VERSION
+#  include <numpy/arrayobject.h>
+
+#  ifdef WITH_OPENCV
+#    include <opencv2/opencv.hpp>
+#  endif // WITH_OPENCV
+
+/*
+ * A bunch of constants were removed in OpenCV 4 in favour of enum classes, so
+ * define the ones we need here.
+ */
+#  if CV_MAJOR_VERSION > 3
+#    define CV_BGR2RGB cv::COLOR_BGR2RGB
+#    define CV_BGRA2RGBA cv::COLOR_BGRA2RGBA
+#  endif
+#endif // WITHOUT_NUMPY
+
+#if PY_MAJOR_VERSION >= 3
+#  define PyString_FromString PyUnicode_FromString
+#  define PyInt_FromLong PyLong_FromLong
+#  define PyString_FromString PyUnicode_FromString
+#endif
+
+
+namespace matplotlibcpp {
+namespace detail {
+
+static std::string s_backend;
+
+struct _interpreter {
+    PyObject* s_python_function_arrow;
+    PyObject *s_python_function_show;
+    PyObject *s_python_function_close;
+    PyObject *s_python_function_draw;
+    PyObject *s_python_function_pause;
+    PyObject *s_python_function_save;
+    PyObject *s_python_function_figure;
+    PyObject *s_python_function_fignum_exists;
+    PyObject *s_python_function_plot;
+    PyObject *s_python_function_quiver;
+    PyObject* s_python_function_contour;
+    PyObject *s_python_function_semilogx;
+    PyObject *s_python_function_semilogy;
+    PyObject *s_python_function_loglog;
+    PyObject *s_python_function_fill;
+    PyObject *s_python_function_fill_between;
+    PyObject *s_python_function_hist;
+    PyObject *s_python_function_imshow;
+    PyObject *s_python_function_scatter;
+    PyObject *s_python_function_boxplot;
+    PyObject *s_python_function_subplot;
+    PyObject *s_python_function_subplot2grid;
+    PyObject *s_python_function_legend;
+    PyObject *s_python_function_xlim;
+    PyObject *s_python_function_ion;
+    PyObject *s_python_function_ginput;
+    PyObject *s_python_function_ylim;
+    PyObject *s_python_function_title;
+    PyObject *s_python_function_axis;
+    PyObject *s_python_function_axvline;
+    PyObject *s_python_function_axvspan;
+    PyObject *s_python_function_xlabel;
+    PyObject *s_python_function_ylabel;
+    PyObject *s_python_function_gca;
+    PyObject *s_python_function_xticks;
+    PyObject *s_python_function_yticks;
+    PyObject* s_python_function_margins;
+    PyObject *s_python_function_tick_params;
+    PyObject *s_python_function_grid;
+    PyObject* s_python_function_cla;
+    PyObject *s_python_function_clf;
+    PyObject *s_python_function_errorbar;
+    PyObject *s_python_function_annotate;
+    PyObject *s_python_function_tight_layout;
+    PyObject *s_python_colormap;
+    PyObject *s_python_empty_tuple;
+    PyObject *s_python_function_stem;
+    PyObject *s_python_function_xkcd;
+    PyObject *s_python_function_text;
+    PyObject *s_python_function_suptitle;
+    PyObject *s_python_function_bar;
+    PyObject *s_python_function_barh;
+    PyObject *s_python_function_colorbar;
+    PyObject *s_python_function_subplots_adjust;
+
+
+    /* For now, _interpreter is implemented as a singleton since its currently not possible to have
+       multiple independent embedded python interpreters without patching the python source code
+       or starting a separate process for each. [1]
+       Furthermore, many python objects expect that they are destructed in the same thread as they
+       were constructed. [2] So for advanced usage, a `kill()` function is provided so that library
+       users can manually ensure that the interpreter is constructed and destroyed within the
+       same thread.
+
+         1: http://bytes.com/topic/python/answers/793370-multiple-independent-python-interpreters-c-c-program
+         2: https://github.com/lava/matplotlib-cpp/pull/202#issue-436220256
+       */
+
+    static _interpreter& get() {
+        return interkeeper(false);
+    }
+
+    static _interpreter& kill() {
+        return interkeeper(true);
+    }
+
+    // Stores the actual singleton object referenced by `get()` and `kill()`.
+    static _interpreter& interkeeper(bool should_kill) {
+        static _interpreter ctx;
+        if (should_kill)
+            ctx.~_interpreter();
+        return ctx;
+    }
+
+    PyObject* safe_import(PyObject* module, std::string fname) {
+        PyObject* fn = PyObject_GetAttrString(module, fname.c_str());
+
+        if (!fn)
+            throw std::runtime_error(std::string("Couldn't find required function: ") + fname);
+
+        if (!PyFunction_Check(fn))
+            throw std::runtime_error(fname + std::string(" is unexpectedly not a PyFunction."));
+
+        return fn;
+    }
+
+private:
+
+#ifndef WITHOUT_NUMPY
+#  if PY_MAJOR_VERSION >= 3
+
+    void *import_numpy() {
+        import_array(); // initialize C-API
+        return NULL;
+    }
+
+#  else
+
+    void import_numpy() {
+        import_array(); // initialize C-API
+    }
+
+#  endif
+#endif
+
+    _interpreter() {
+
+        // optional but recommended
+#if PY_MAJOR_VERSION >= 3
+        wchar_t name[] = L"plotting";
+#else
+        char name[] = "plotting";
+#endif
+        Py_SetProgramName(name);
+        Py_Initialize();
+
+        wchar_t const *dummy_args[] = {L"Python", NULL};  // const is needed because literals must not be modified
+        wchar_t const **argv = dummy_args;
+        int             argc = sizeof(dummy_args)/sizeof(dummy_args[0])-1;
+        char ** argm = (char **)(argv);
+        PySys_SetArgv(argc, argm);
+
+#ifndef WITHOUT_NUMPY
+        import_numpy(); // initialize numpy C-API
+#endif
+
+        PyObject* matplotlibname = PyString_FromString("matplotlib");
+        PyObject* pyplotname = PyString_FromString("matplotlib.pyplot");
+        PyObject* cmname  = PyString_FromString("matplotlib.cm");
+        PyObject* pylabname  = PyString_FromString("pylab");
+        if (!pyplotname || !pylabname || !matplotlibname || !cmname) {
+            throw std::runtime_error("couldnt create string");
+        }
+
+        PyObject* matplotlib = PyImport_Import(matplotlibname);
+        Py_DECREF(matplotlibname);
+        if (!matplotlib) {
+            PyErr_Print();
+            throw std::runtime_error("Error loading module matplotlib!");
+        }
+
+        // matplotlib.use() must be called *before* pylab, matplotlib.pyplot,
+        // or matplotlib.backends is imported for the first time
+        if (!s_backend.empty()) {
+            PyObject_CallMethod(matplotlib, const_cast<char*>("use"), const_cast<char*>("s"), s_backend.c_str());
+        }
+
+        PyObject* pymod = PyImport_Import(pyplotname);
+        Py_DECREF(pyplotname);
+        if (!pymod) { throw std::runtime_error("Error loading module matplotlib.pyplot!"); }
+
+        s_python_colormap = PyImport_Import(cmname);
+        Py_DECREF(cmname);
+        if (!s_python_colormap) { throw std::runtime_error("Error loading module matplotlib.cm!"); }
+
+        PyObject* pylabmod = PyImport_Import(pylabname);
+        Py_DECREF(pylabname);
+        if (!pylabmod) { throw std::runtime_error("Error loading module pylab!"); }
+
+        s_python_function_arrow = safe_import(pymod, "arrow");
+        s_python_function_show = safe_import(pymod, "show");
+        s_python_function_close = safe_import(pymod, "close");
+        s_python_function_draw = safe_import(pymod, "draw");
+        s_python_function_pause = safe_import(pymod, "pause");
+        s_python_function_figure = safe_import(pymod, "figure");
+        s_python_function_fignum_exists = safe_import(pymod, "fignum_exists");
+        s_python_function_plot = safe_import(pymod, "plot");
+        s_python_function_quiver = safe_import(pymod, "quiver");
+        s_python_function_contour = safe_import(pymod, "contour");
+        s_python_function_semilogx = safe_import(pymod, "semilogx");
+        s_python_function_semilogy = safe_import(pymod, "semilogy");
+        s_python_function_loglog = safe_import(pymod, "loglog");
+        s_python_function_fill = safe_import(pymod, "fill");
+        s_python_function_fill_between = safe_import(pymod, "fill_between");
+        s_python_function_hist = safe_import(pymod,"hist");
+        s_python_function_scatter = safe_import(pymod,"scatter");
+        s_python_function_boxplot = safe_import(pymod,"boxplot");
+        s_python_function_subplot = safe_import(pymod, "subplot");
+        s_python_function_subplot2grid = safe_import(pymod, "subplot2grid");
+        s_python_function_legend = safe_import(pymod, "legend");
+        s_python_function_ylim = safe_import(pymod, "ylim");
+        s_python_function_title = safe_import(pymod, "title");
+        s_python_function_axis = safe_import(pymod, "axis");
+        s_python_function_axvline = safe_import(pymod, "axvline");
+        s_python_function_axvspan = safe_import(pymod, "axvspan");
+        s_python_function_xlabel = safe_import(pymod, "xlabel");
+        s_python_function_ylabel = safe_import(pymod, "ylabel");
+        s_python_function_gca = safe_import(pymod, "gca");
+        s_python_function_xticks = safe_import(pymod, "xticks");
+        s_python_function_yticks = safe_import(pymod, "yticks");
+        s_python_function_margins = safe_import(pymod, "margins");
+        s_python_function_tick_params = safe_import(pymod, "tick_params");
+        s_python_function_grid = safe_import(pymod, "grid");
+        s_python_function_xlim = safe_import(pymod, "xlim");
+        s_python_function_ion = safe_import(pymod, "ion");
+        s_python_function_ginput = safe_import(pymod, "ginput");
+        s_python_function_save = safe_import(pylabmod, "savefig");
+        s_python_function_annotate = safe_import(pymod,"annotate");
+        s_python_function_cla = safe_import(pymod, "cla");
+        s_python_function_clf = safe_import(pymod, "clf");
+        s_python_function_errorbar = safe_import(pymod, "errorbar");
+        s_python_function_tight_layout = safe_import(pymod, "tight_layout");
+        s_python_function_stem = safe_import(pymod, "stem");
+        s_python_function_xkcd = safe_import(pymod, "xkcd");
+        s_python_function_text = safe_import(pymod, "text");
+        s_python_function_suptitle = safe_import(pymod, "suptitle");
+        s_python_function_bar = safe_import(pymod,"bar");
+        s_python_function_barh = safe_import(pymod, "barh");
+        s_python_function_colorbar = PyObject_GetAttrString(pymod, "colorbar");
+        s_python_function_subplots_adjust = safe_import(pymod,"subplots_adjust");
+#ifndef WITHOUT_NUMPY
+        s_python_function_imshow = safe_import(pymod, "imshow");
+#endif
+        s_python_empty_tuple = PyTuple_New(0);
+    }
+
+    ~_interpreter() {
+        Py_Finalize();
+    }
+};
+
+} // end namespace detail
+
+/// Select the backend
+///
+/// **NOTE:** This must be called before the first plot command to have
+/// any effect.
+///
+/// Mainly useful to select the non-interactive 'Agg' backend when running
+/// matplotlibcpp in headless mode, for example on a machine with no display.
+///
+/// See also: https://matplotlib.org/2.0.2/api/matplotlib_configuration_api.html#matplotlib.use
+inline void backend(const std::string& name)
+{
+    detail::s_backend = name;
+}
+
+inline bool annotate(std::string annotation, double x, double y)
+{
+    detail::_interpreter::get();
+
+    PyObject * xy = PyTuple_New(2);
+    PyObject * str = PyString_FromString(annotation.c_str());
+
+    PyTuple_SetItem(xy,0,PyFloat_FromDouble(x));
+    PyTuple_SetItem(xy,1,PyFloat_FromDouble(y));
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "xy", xy);
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, str);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_annotate, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+namespace detail {
+
+#ifndef WITHOUT_NUMPY
+// Type selector for numpy array conversion
+template <typename T> struct select_npy_type { const static NPY_TYPES type = NPY_NOTYPE; }; //Default
+template <> struct select_npy_type<double> { const static NPY_TYPES type = NPY_DOUBLE; };
+template <> struct select_npy_type<float> { const static NPY_TYPES type = NPY_FLOAT; };
+template <> struct select_npy_type<bool> { const static NPY_TYPES type = NPY_BOOL; };
+template <> struct select_npy_type<int8_t> { const static NPY_TYPES type = NPY_INT8; };
+template <> struct select_npy_type<int16_t> { const static NPY_TYPES type = NPY_SHORT; };
+template <> struct select_npy_type<int32_t> { const static NPY_TYPES type = NPY_INT; };
+template <> struct select_npy_type<int64_t> { const static NPY_TYPES type = NPY_INT64; };
+template <> struct select_npy_type<uint8_t> { const static NPY_TYPES type = NPY_UINT8; };
+template <> struct select_npy_type<uint16_t> { const static NPY_TYPES type = NPY_USHORT; };
+template <> struct select_npy_type<uint32_t> { const static NPY_TYPES type = NPY_ULONG; };
+template <> struct select_npy_type<uint64_t> { const static NPY_TYPES type = NPY_UINT64; };
+
+// Sanity checks; comment them out or change the numpy type below if you're compiling on
+// a platform where they don't apply
+//static_assert(sizeof(long long) == 8);
+//template <> struct select_npy_type<long long> { const static NPY_TYPES type = NPY_INT64; };
+//static_assert(sizeof(unsigned long long) == 8);
+//template <> struct select_npy_type<unsigned long long> { const static NPY_TYPES type = NPY_UINT64; };
+// TODO: add int, long, etc.
+
+template<typename Numeric>
+PyObject* get_array(const std::vector<Numeric>& v)
+{
+    npy_intp vsize = v.size();
+    NPY_TYPES type = select_npy_type<Numeric>::type;
+    if (type == NPY_NOTYPE) {
+        size_t memsize = v.size()*sizeof(double);
+        double* dp = static_cast<double*>(::malloc(memsize));
+        for (size_t i=0; i<v.size(); ++i)
+            dp[i] = v[i];
+        PyObject* varray = PyArray_SimpleNewFromData(1, &vsize, NPY_DOUBLE, dp);
+        PyArray_UpdateFlags(reinterpret_cast<PyArrayObject*>(varray), NPY_ARRAY_OWNDATA);
+        return varray;
+    }
+    
+    PyObject* varray = PyArray_SimpleNewFromData(1, &vsize, type, (void*)(v.data()));
+    return varray;
+}
+
+
+template<typename Numeric>
+PyObject* get_2darray(const std::vector<::std::vector<Numeric>>& v)
+{
+    if (v.size() < 1) throw std::runtime_error("get_2d_array v too small");
+
+    npy_intp vsize[2] = {static_cast<npy_intp>(v.size()),
+                         static_cast<npy_intp>(v[0].size())};
+
+    PyArrayObject *varray =
+        (PyArrayObject *)PyArray_SimpleNew(2, vsize, NPY_DOUBLE);
+
+    double *vd_begin = static_cast<double *>(PyArray_DATA(varray));
+
+    for (const ::std::vector<Numeric> &v_row : v) {
+      if (v_row.size() != static_cast<size_t>(vsize[1]))
+        throw std::runtime_error("Missmatched array size");
+      std::copy(v_row.begin(), v_row.end(), vd_begin);
+      vd_begin += vsize[1];
+    }
+
+    return reinterpret_cast<PyObject *>(varray);
+}
+
+#else // fallback if we don't have numpy: copy every element of the given vector
+
+template<typename Numeric>
+PyObject* get_array(const std::vector<Numeric>& v)
+{
+    PyObject* list = PyList_New(v.size());
+    for(size_t i = 0; i < v.size(); ++i) {
+        PyList_SetItem(list, i, PyFloat_FromDouble(v.at(i)));
+    }
+    return list;
+}
+
+#endif // WITHOUT_NUMPY
+
+// sometimes, for labels and such, we need string arrays
+inline PyObject * get_array(const std::vector<std::string>& strings)
+{
+  PyObject* list = PyList_New(strings.size());
+  for (std::size_t i = 0; i < strings.size(); ++i) {
+    PyList_SetItem(list, i, PyString_FromString(strings[i].c_str()));
+  }
+  return list;
+}
+
+// not all matplotlib need 2d arrays, some prefer lists of lists
+template<typename Numeric>
+PyObject* get_listlist(const std::vector<std::vector<Numeric>>& ll)
+{
+  PyObject* listlist = PyList_New(ll.size());
+  for (std::size_t i = 0; i < ll.size(); ++i) {
+    PyList_SetItem(listlist, i, get_array(ll[i]));
+  }
+  return listlist;
+}
+
+} // namespace detail
+
+/// Plot a line through the given x and y data points..
+/// 
+/// See: https://matplotlib.org/3.2.1/api/_as_gen/matplotlib.pyplot.plot.html
+template<typename Numeric>
+bool plot(const std::vector<Numeric> &x, const std::vector<Numeric> &y, const std::map<std::string, std::string>& keywords)
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    // using numpy arrays
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    // construct positional args
+    PyObject* args = PyTuple_New(2);
+    PyTuple_SetItem(args, 0, xarray);
+    PyTuple_SetItem(args, 1, yarray);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+// TODO - it should be possible to make this work by implementing
+// a non-numpy alternative for `detail::get_2darray()`.
+#ifndef WITHOUT_NUMPY
+template <typename Numeric>
+void plot_surface(const std::vector<::std::vector<Numeric>> &x,
+                  const std::vector<::std::vector<Numeric>> &y,
+                  const std::vector<::std::vector<Numeric>> &z,
+                  const std::map<std::string, std::string> &keywords =
+                      std::map<std::string, std::string>())
+{
+  detail::_interpreter::get();
+
+  // We lazily load the modules here the first time this function is called
+  // because I'm not sure that we can assume "matplotlib installed" implies
+  // "mpl_toolkits installed" on all platforms, and we don't want to require
+  // it for people who don't need 3d plots.
+  static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr;
+  if (!mpl_toolkitsmod) {
+    detail::_interpreter::get();
+
+    PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits");
+    PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d");
+    if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); }
+
+    mpl_toolkitsmod = PyImport_Import(mpl_toolkits);
+    Py_DECREF(mpl_toolkits);
+    if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); }
+
+    axis3dmod = PyImport_Import(axis3d);
+    Py_DECREF(axis3d);
+    if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); }
+  }
+
+  assert(x.size() == y.size());
+  assert(y.size() == z.size());
+
+  // using numpy arrays
+  PyObject *xarray = detail::get_2darray(x);
+  PyObject *yarray = detail::get_2darray(y);
+  PyObject *zarray = detail::get_2darray(z);
+
+  // construct positional args
+  PyObject *args = PyTuple_New(3);
+  PyTuple_SetItem(args, 0, xarray);
+  PyTuple_SetItem(args, 1, yarray);
+  PyTuple_SetItem(args, 2, zarray);
+
+  // Build up the kw args.
+  PyObject *kwargs = PyDict_New();
+  PyDict_SetItemString(kwargs, "rstride", PyInt_FromLong(1));
+  PyDict_SetItemString(kwargs, "cstride", PyInt_FromLong(1));
+
+  PyObject *python_colormap_coolwarm = PyObject_GetAttrString(
+      detail::_interpreter::get().s_python_colormap, "coolwarm");
+
+  PyDict_SetItemString(kwargs, "cmap", python_colormap_coolwarm);
+
+  for (std::map<std::string, std::string>::const_iterator it = keywords.begin();
+       it != keywords.end(); ++it) {
+    PyDict_SetItemString(kwargs, it->first.c_str(),
+                         PyString_FromString(it->second.c_str()));
+  }
+
+
+  PyObject *fig =
+      PyObject_CallObject(detail::_interpreter::get().s_python_function_figure,
+                          detail::_interpreter::get().s_python_empty_tuple);
+  if (!fig) throw std::runtime_error("Call to figure() failed.");
+
+  PyObject *gca_kwargs = PyDict_New();
+  PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d"));
+
+  PyObject *gca = PyObject_GetAttrString(fig, "gca");
+  if (!gca) throw std::runtime_error("No gca");
+  Py_INCREF(gca);
+  PyObject *axis = PyObject_Call(
+      gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs);
+
+  if (!axis) throw std::runtime_error("No axis");
+  Py_INCREF(axis);
+
+  Py_DECREF(gca);
+  Py_DECREF(gca_kwargs);
+
+  PyObject *plot_surface = PyObject_GetAttrString(axis, "plot_surface");
+  if (!plot_surface) throw std::runtime_error("No surface");
+  Py_INCREF(plot_surface);
+  PyObject *res = PyObject_Call(plot_surface, args, kwargs);
+  if (!res) throw std::runtime_error("failed surface");
+  Py_DECREF(plot_surface);
+
+  Py_DECREF(axis);
+  Py_DECREF(args);
+  Py_DECREF(kwargs);
+  if (res) Py_DECREF(res);
+}
+#endif // WITHOUT_NUMPY
+
+template <typename Numeric>
+void plot3(const std::vector<Numeric> &x,
+                  const std::vector<Numeric> &y,
+                  const std::vector<Numeric> &z,
+                  const std::map<std::string, std::string> &keywords =
+                      std::map<std::string, std::string>())
+{
+  detail::_interpreter::get();
+
+  // Same as with plot_surface: We lazily load the modules here the first time 
+  // this function is called because I'm not sure that we can assume "matplotlib 
+  // installed" implies "mpl_toolkits installed" on all platforms, and we don't 
+  // want to require it for people who don't need 3d plots.
+  static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr;
+  if (!mpl_toolkitsmod) {
+    detail::_interpreter::get();
+
+    PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits");
+    PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d");
+    if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); }
+
+    mpl_toolkitsmod = PyImport_Import(mpl_toolkits);
+    Py_DECREF(mpl_toolkits);
+    if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); }
+
+    axis3dmod = PyImport_Import(axis3d);
+    Py_DECREF(axis3d);
+    if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); }
+  }
+
+  assert(x.size() == y.size());
+  assert(y.size() == z.size());
+
+  PyObject *xarray = detail::get_array(x);
+  PyObject *yarray = detail::get_array(y);
+  PyObject *zarray = detail::get_array(z);
+
+  // construct positional args
+  PyObject *args = PyTuple_New(3);
+  PyTuple_SetItem(args, 0, xarray);
+  PyTuple_SetItem(args, 1, yarray);
+  PyTuple_SetItem(args, 2, zarray);
+
+  // Build up the kw args.
+  PyObject *kwargs = PyDict_New();
+
+  for (std::map<std::string, std::string>::const_iterator it = keywords.begin();
+       it != keywords.end(); ++it) {
+    PyDict_SetItemString(kwargs, it->first.c_str(),
+                         PyString_FromString(it->second.c_str()));
+  }
+
+  PyObject *fig =
+      PyObject_CallObject(detail::_interpreter::get().s_python_function_figure,
+                          detail::_interpreter::get().s_python_empty_tuple);
+  if (!fig) throw std::runtime_error("Call to figure() failed.");
+
+  PyObject *gca_kwargs = PyDict_New();
+  PyDict_SetItemString(gca_kwargs, "projection", PyString_FromString("3d"));
+
+  PyObject *gca = PyObject_GetAttrString(fig, "gca");
+  if (!gca) throw std::runtime_error("No gca");
+  Py_INCREF(gca);
+  PyObject *axis = PyObject_Call(
+      gca, detail::_interpreter::get().s_python_empty_tuple, gca_kwargs);
+
+  if (!axis) throw std::runtime_error("No axis");
+  Py_INCREF(axis);
+
+  Py_DECREF(gca);
+  Py_DECREF(gca_kwargs);
+
+  PyObject *plot3 = PyObject_GetAttrString(axis, "plot");
+  if (!plot3) throw std::runtime_error("No 3D line plot");
+  Py_INCREF(plot3);
+  PyObject *res = PyObject_Call(plot3, args, kwargs);
+  if (!res) throw std::runtime_error("Failed 3D line plot");
+  Py_DECREF(plot3);
+
+  Py_DECREF(axis);
+  Py_DECREF(args);
+  Py_DECREF(kwargs);
+  if (res) Py_DECREF(res);
+}
+
+template<typename Numeric>
+bool stem(const std::vector<Numeric> &x, const std::vector<Numeric> &y, const std::map<std::string, std::string>& keywords)
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    // using numpy arrays
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    // construct positional args
+    PyObject* args = PyTuple_New(2);
+    PyTuple_SetItem(args, 0, xarray);
+    PyTuple_SetItem(args, 1, yarray);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for (std::map<std::string, std::string>::const_iterator it =
+            keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(),
+                PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(
+            detail::_interpreter::get().s_python_function_stem, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if (res)
+        Py_DECREF(res);
+
+    return res;
+}
+
+template< typename Numeric >
+bool fill(const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::map<std::string, std::string>& keywords)
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    // using numpy arrays
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    // construct positional args
+    PyObject* args = PyTuple_New(2);
+    PyTuple_SetItem(args, 0, xarray);
+    PyTuple_SetItem(args, 1, yarray);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template< typename Numeric >
+bool fill_between(const std::vector<Numeric>& x, const std::vector<Numeric>& y1, const std::vector<Numeric>& y2, const std::map<std::string, std::string>& keywords)
+{
+    assert(x.size() == y1.size());
+    assert(x.size() == y2.size());
+
+    detail::_interpreter::get();
+
+    // using numpy arrays
+    PyObject* xarray = detail::get_array(x);
+    PyObject* y1array = detail::get_array(y1);
+    PyObject* y2array = detail::get_array(y2);
+
+    // construct positional args
+    PyObject* args = PyTuple_New(3);
+    PyTuple_SetItem(args, 0, xarray);
+    PyTuple_SetItem(args, 1, y1array);
+    PyTuple_SetItem(args, 2, y2array);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_fill_between, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template <typename Numeric>
+bool arrow(Numeric x, Numeric y, Numeric end_x, Numeric end_y, const std::string& fc = "r",
+           const std::string ec = "k", Numeric head_length = 0.25, Numeric head_width = 0.1625) {
+    PyObject* obj_x = PyFloat_FromDouble(x);
+    PyObject* obj_y = PyFloat_FromDouble(y);
+    PyObject* obj_end_x = PyFloat_FromDouble(end_x);
+    PyObject* obj_end_y = PyFloat_FromDouble(end_y);
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "fc", PyString_FromString(fc.c_str()));
+    PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str()));
+    PyDict_SetItemString(kwargs, "head_width", PyFloat_FromDouble(head_width));
+    PyDict_SetItemString(kwargs, "head_length", PyFloat_FromDouble(head_length));
+
+    PyObject* plot_args = PyTuple_New(4);
+    PyTuple_SetItem(plot_args, 0, obj_x);
+    PyTuple_SetItem(plot_args, 1, obj_y);
+    PyTuple_SetItem(plot_args, 2, obj_end_x);
+    PyTuple_SetItem(plot_args, 3, obj_end_y);
+
+    PyObject* res =
+            PyObject_Call(detail::_interpreter::get().s_python_function_arrow, plot_args, kwargs);
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if (res)
+        Py_DECREF(res);
+
+    return res;
+}
+
+template< typename Numeric>
+bool hist(const std::vector<Numeric>& y, long bins=10,std::string color="b",
+          double alpha=1.0, bool cumulative=false)
+{
+    detail::_interpreter::get();
+
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins));
+    PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str()));
+    PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha));
+    PyDict_SetItemString(kwargs, "cumulative", cumulative ? Py_True : Py_False);
+
+    PyObject* plot_args = PyTuple_New(1);
+
+    PyTuple_SetItem(plot_args, 0, yarray);
+
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs);
+
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+#ifndef WITHOUT_NUMPY
+namespace detail {
+
+inline void imshow(void *ptr, const NPY_TYPES type, const int rows, const int columns, const int colors, const std::map<std::string, std::string> &keywords, PyObject** out)
+{
+    assert(type == NPY_UINT8 || type == NPY_FLOAT);
+    assert(colors == 1 || colors == 3 || colors == 4);
+
+    detail::_interpreter::get();
+
+    // construct args
+    npy_intp dims[3] = { rows, columns, colors };
+    PyObject *args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, PyArray_SimpleNewFromData(colors == 1 ? 2 : 3, dims, type, ptr));
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_imshow, args, kwargs);
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if (!res)
+        throw std::runtime_error("Call to imshow() failed");
+    if (out)
+        *out = res;
+    else
+        Py_DECREF(res);
+}
+
+} // namespace detail
+
+inline void imshow(const unsigned char *ptr, const int rows, const int columns, const int colors, const std::map<std::string, std::string> &keywords = {}, PyObject** out = nullptr)
+{
+    detail::imshow((void *) ptr, NPY_UINT8, rows, columns, colors, keywords, out);
+}
+
+inline void imshow(const float *ptr, const int rows, const int columns, const int colors, const std::map<std::string, std::string> &keywords = {}, PyObject** out = nullptr)
+{
+    detail::imshow((void *) ptr, NPY_FLOAT, rows, columns, colors, keywords, out);
+}
+
+#ifdef WITH_OPENCV
+void imshow(const cv::Mat &image, const std::map<std::string, std::string> &keywords = {})
+{
+    // Convert underlying type of matrix, if needed
+    cv::Mat image2;
+    NPY_TYPES npy_type = NPY_UINT8;
+    switch (image.type() & CV_MAT_DEPTH_MASK) {
+    case CV_8U:
+        image2 = image;
+        break;
+    case CV_32F:
+        image2 = image;
+        npy_type = NPY_FLOAT;
+        break;
+    default:
+        image.convertTo(image2, CV_MAKETYPE(CV_8U, image.channels()));
+    }
+
+    // If color image, convert from BGR to RGB
+    switch (image2.channels()) {
+    case 3:
+        cv::cvtColor(image2, image2, CV_BGR2RGB);
+        break;
+    case 4:
+        cv::cvtColor(image2, image2, CV_BGRA2RGBA);
+    }
+
+    detail::imshow(image2.data, npy_type, image2.rows, image2.cols, image2.channels(), keywords);
+}
+#endif // WITH_OPENCV
+#endif // WITHOUT_NUMPY
+
+template<typename NumericX, typename NumericY>
+bool scatter(const std::vector<NumericX>& x,
+             const std::vector<NumericY>& y,
+             const double s=1.0, // The marker size in points**2
+             const std::map<std::string, std::string> & keywords = {})
+{
+    detail::_interpreter::get();
+
+    assert(x.size() == y.size());
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "s", PyLong_FromLong(s));
+    for (const auto& it : keywords)
+    {
+        PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str()));
+    }
+
+    PyObject* plot_args = PyTuple_New(2);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_scatter, plot_args, kwargs);
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool boxplot(const std::vector<std::vector<Numeric>>& data,
+             const std::vector<std::string>& labels = {},
+             const std::map<std::string, std::string> & keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* listlist = detail::get_listlist(data);
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, listlist);
+
+    PyObject* kwargs = PyDict_New();
+
+    // kwargs needs the labels, if there are (the correct number of) labels
+    if (!labels.empty() && labels.size() == data.size()) {
+        PyDict_SetItemString(kwargs, "labels", detail::get_array(labels));
+    }
+
+    // take care of the remaining keywords
+    for (const auto& it : keywords)
+    {
+        PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool boxplot(const std::vector<Numeric>& data,
+             const std::map<std::string, std::string> & keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* vector = detail::get_array(data);
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, vector);
+
+    PyObject* kwargs = PyDict_New();
+    for (const auto& it : keywords)
+    {
+        PyDict_SetItemString(kwargs, it.first.c_str(), PyString_FromString(it.second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_boxplot, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template <typename Numeric>
+bool bar(const std::vector<Numeric> &               x,
+         const std::vector<Numeric> &               y,
+         std::string                                ec       = "black",
+         std::string                                ls       = "-",
+         double                                     lw       = 1.0,
+         const std::map<std::string, std::string> & keywords = {})
+{
+  detail::_interpreter::get();
+
+  PyObject * xarray = detail::get_array(x);
+  PyObject * yarray = detail::get_array(y);
+
+  PyObject * kwargs = PyDict_New();
+
+  PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str()));
+  PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str()));
+  PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw));
+
+  for (std::map<std::string, std::string>::const_iterator it =
+         keywords.begin();
+       it != keywords.end();
+       ++it) {
+    PyDict_SetItemString(
+      kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+  }
+
+  PyObject * plot_args = PyTuple_New(2);
+  PyTuple_SetItem(plot_args, 0, xarray);
+  PyTuple_SetItem(plot_args, 1, yarray);
+
+  PyObject * res = PyObject_Call(
+    detail::_interpreter::get().s_python_function_bar, plot_args, kwargs);
+
+  Py_DECREF(plot_args);
+  Py_DECREF(kwargs);
+  if (res) Py_DECREF(res);
+
+  return res;
+}
+
+template <typename Numeric>
+bool bar(const std::vector<Numeric> &               y,
+         std::string                                ec       = "black",
+         std::string                                ls       = "-",
+         double                                     lw       = 1.0,
+         const std::map<std::string, std::string> & keywords = {})
+{
+  using T = typename std::remove_reference<decltype(y)>::type::value_type;
+
+  detail::_interpreter::get();
+
+  std::vector<T> x;
+  for (std::size_t i = 0; i < y.size(); i++) { x.push_back(i); }
+
+  return bar(x, y, ec, ls, lw, keywords);
+}
+
+
+template<typename Numeric>
+bool barh(const std::vector<Numeric> &x, const std::vector<Numeric> &y, std::string ec = "black", std::string ls = "-", double lw = 1.0, const std::map<std::string, std::string> &keywords = { }) {
+    PyObject *xarray = detail::get_array(x);
+    PyObject *yarray = detail::get_array(y);
+
+    PyObject *kwargs = PyDict_New();
+
+    PyDict_SetItemString(kwargs, "ec", PyString_FromString(ec.c_str()));
+    PyDict_SetItemString(kwargs, "ls", PyString_FromString(ls.c_str()));
+    PyDict_SetItemString(kwargs, "lw", PyFloat_FromDouble(lw));
+
+    for (std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject *plot_args = PyTuple_New(2);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+
+    PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_barh, plot_args, kwargs);
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+
+inline bool subplots_adjust(const std::map<std::string, double>& keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    for (std::map<std::string, double>::const_iterator it =
+            keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(),
+                             PyFloat_FromDouble(it->second));
+    }
+
+
+    PyObject* plot_args = PyTuple_New(0);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_subplots_adjust, plot_args, kwargs);
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template< typename Numeric>
+bool named_hist(std::string label,const std::vector<Numeric>& y, long bins=10, std::string color="b", double alpha=1.0)
+{
+    detail::_interpreter::get();
+
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(label.c_str()));
+    PyDict_SetItemString(kwargs, "bins", PyLong_FromLong(bins));
+    PyDict_SetItemString(kwargs, "color", PyString_FromString(color.c_str()));
+    PyDict_SetItemString(kwargs, "alpha", PyFloat_FromDouble(alpha));
+
+
+    PyObject* plot_args = PyTuple_New(1);
+    PyTuple_SetItem(plot_args, 0, yarray);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_hist, plot_args, kwargs);
+
+    Py_DECREF(plot_args);
+    Py_DECREF(kwargs);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool plot(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::string& s = "")
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(s.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args);
+
+    Py_DECREF(plot_args);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template <typename NumericX, typename NumericY, typename NumericZ>
+bool contour(const std::vector<NumericX>& x, const std::vector<NumericY>& y,
+             const std::vector<NumericZ>& z,
+             const std::map<std::string, std::string>& keywords = {}) {
+    assert(x.size() == y.size() && x.size() == z.size());
+
+    PyObject* xarray = get_array(x);
+    PyObject* yarray = get_array(y);
+    PyObject* zarray = get_array(z);
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, zarray);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for (std::map<std::string, std::string>::const_iterator it = keywords.begin();
+         it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res =
+            PyObject_Call(detail::_interpreter::get().s_python_function_contour, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res)
+        Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY, typename NumericU, typename NumericW>
+bool quiver(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::vector<NumericU>& u, const std::vector<NumericW>& w, const std::map<std::string, std::string>& keywords = {})
+{
+    assert(x.size() == y.size() && x.size() == u.size() && u.size() == w.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+    PyObject* uarray = detail::get_array(u);
+    PyObject* warray = detail::get_array(w);
+
+    PyObject* plot_args = PyTuple_New(4);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, uarray);
+    PyTuple_SetItem(plot_args, 3, warray);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(
+            detail::_interpreter::get().s_python_function_quiver, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res)
+        Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool stem(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::string& s = "")
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(s.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_CallObject(
+            detail::_interpreter::get().s_python_function_stem, plot_args);
+
+    Py_DECREF(plot_args);
+    if (res)
+        Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool semilogx(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::string& s = "")
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(s.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogx, plot_args);
+
+    Py_DECREF(plot_args);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool semilogy(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::string& s = "")
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(s.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_semilogy, plot_args);
+
+    Py_DECREF(plot_args);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool loglog(const std::vector<NumericX>& x, const std::vector<NumericY>& y, const std::string& s = "")
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(s.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_loglog, plot_args);
+
+    Py_DECREF(plot_args);
+    if(res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename NumericX, typename NumericY>
+bool errorbar(const std::vector<NumericX> &x, const std::vector<NumericY> &y, const std::vector<NumericX> &yerr, const std::map<std::string, std::string> &keywords = {})
+{
+    assert(x.size() == y.size());
+
+    detail::_interpreter::get();
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+    PyObject* yerrarray = detail::get_array(yerr);
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyDict_SetItemString(kwargs, "yerr", yerrarray);
+
+    PyObject *plot_args = PyTuple_New(2);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+
+    PyObject *res = PyObject_Call(detail::_interpreter::get().s_python_function_errorbar, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+
+    if (res)
+        Py_DECREF(res);
+    else
+        throw std::runtime_error("Call to errorbar() failed.");
+
+    return res;
+}
+
+template<typename Numeric>
+bool named_plot(const std::string& name, const std::vector<Numeric>& y, const std::string& format = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(format.c_str());
+
+    PyObject* plot_args = PyTuple_New(2);
+
+    PyTuple_SetItem(plot_args, 0, yarray);
+    PyTuple_SetItem(plot_args, 1, pystring);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool named_plot(const std::string& name, const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::string& format = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(format.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool named_semilogx(const std::string& name, const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::string& format = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(format.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogx, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool named_semilogy(const std::string& name, const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::string& format = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(format.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_semilogy, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool named_loglog(const std::string& name, const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::string& format = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+    PyObject* xarray = detail::get_array(x);
+    PyObject* yarray = detail::get_array(y);
+
+    PyObject* pystring = PyString_FromString(format.c_str());
+
+    PyObject* plot_args = PyTuple_New(3);
+    PyTuple_SetItem(plot_args, 0, xarray);
+    PyTuple_SetItem(plot_args, 1, yarray);
+    PyTuple_SetItem(plot_args, 2, pystring);
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_loglog, plot_args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(plot_args);
+    if (res) Py_DECREF(res);
+
+    return res;
+}
+
+template<typename Numeric>
+bool plot(const std::vector<Numeric>& y, const std::string& format = "")
+{
+    std::vector<Numeric> x(y.size());
+    for(size_t i=0; i<x.size(); ++i) x.at(i) = i;
+    return plot(x,y,format);
+}
+
+template<typename Numeric>
+bool plot(const std::vector<Numeric>& y, const std::map<std::string, std::string>& keywords)
+{
+    std::vector<Numeric> x(y.size());
+    for(size_t i=0; i<x.size(); ++i) x.at(i) = i;
+    return plot(x,y,keywords);
+}
+
+template<typename Numeric>
+bool stem(const std::vector<Numeric>& y, const std::string& format = "")
+{
+    std::vector<Numeric> x(y.size());
+    for (size_t i = 0; i < x.size(); ++i) x.at(i) = i;
+    return stem(x, y, format);
+}
+
+template<typename Numeric>
+void text(Numeric x, Numeric y, const std::string& s = "")
+{
+    detail::_interpreter::get();
+
+    PyObject* args = PyTuple_New(3);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(x));
+    PyTuple_SetItem(args, 1, PyFloat_FromDouble(y));
+    PyTuple_SetItem(args, 2, PyString_FromString(s.c_str()));
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_text, args);
+    if(!res) throw std::runtime_error("Call to text() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void colorbar(PyObject* mappable = NULL, const std::map<std::string, float>& keywords = {})
+{
+    if (mappable == NULL)
+        throw std::runtime_error("Must call colorbar with PyObject* returned from an image, contour, surface, etc.");
+
+    detail::_interpreter::get();
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, mappable);
+
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, float>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(it->second));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_colorbar, args, kwargs);
+    if(!res) throw std::runtime_error("Call to colorbar() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    Py_DECREF(res);
+}
+
+
+inline long figure(long number = -1)
+{
+    detail::_interpreter::get();
+
+    PyObject *res;
+    if (number == -1)
+        res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, detail::_interpreter::get().s_python_empty_tuple);
+    else {
+        assert(number > 0);
+
+        // Make sure interpreter is initialised
+        detail::_interpreter::get();
+
+        PyObject *args = PyTuple_New(1);
+        PyTuple_SetItem(args, 0, PyLong_FromLong(number));
+        res = PyObject_CallObject(detail::_interpreter::get().s_python_function_figure, args);
+        Py_DECREF(args);
+    }
+
+    if(!res) throw std::runtime_error("Call to figure() failed.");
+
+    PyObject* num = PyObject_GetAttrString(res, "number");
+    if (!num) throw std::runtime_error("Could not get number attribute of figure object");
+    const long figureNumber = PyLong_AsLong(num);
+
+    Py_DECREF(num);
+    Py_DECREF(res);
+
+    return figureNumber;
+}
+
+inline bool fignum_exists(long number)
+{
+    detail::_interpreter::get();
+
+    PyObject *args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, PyLong_FromLong(number));
+    PyObject *res = PyObject_CallObject(detail::_interpreter::get().s_python_function_fignum_exists, args);
+    if(!res) throw std::runtime_error("Call to fignum_exists() failed.");
+
+    bool ret = PyObject_IsTrue(res);
+    Py_DECREF(res);
+    Py_DECREF(args);
+
+    return ret;
+}
+
+inline void figure_size(size_t w, size_t h)
+{
+    detail::_interpreter::get();
+
+    const size_t dpi = 100;
+    PyObject* size = PyTuple_New(2);
+    PyTuple_SetItem(size, 0, PyFloat_FromDouble((double)w / dpi));
+    PyTuple_SetItem(size, 1, PyFloat_FromDouble((double)h / dpi));
+
+    PyObject* kwargs = PyDict_New();
+    PyDict_SetItemString(kwargs, "figsize", size);
+    PyDict_SetItemString(kwargs, "dpi", PyLong_FromSize_t(dpi));
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_figure,
+            detail::_interpreter::get().s_python_empty_tuple, kwargs);
+
+    Py_DECREF(kwargs);
+
+    if(!res) throw std::runtime_error("Call to figure_size() failed.");
+    Py_DECREF(res);
+}
+
+inline void legend()
+{
+    detail::_interpreter::get();
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple);
+    if(!res) throw std::runtime_error("Call to legend() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void legend(const std::map<std::string, std::string>& keywords)
+{
+  detail::_interpreter::get();
+
+  // construct keyword args
+  PyObject* kwargs = PyDict_New();
+  for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+  {
+    PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+  }
+
+  PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_legend, detail::_interpreter::get().s_python_empty_tuple, kwargs);
+  if(!res) throw std::runtime_error("Call to legend() failed.");
+
+  Py_DECREF(kwargs);
+  Py_DECREF(res);  
+}
+
+template<typename Numeric>
+void ylim(Numeric left, Numeric right)
+{
+    detail::_interpreter::get();
+
+    PyObject* list = PyList_New(2);
+    PyList_SetItem(list, 0, PyFloat_FromDouble(left));
+    PyList_SetItem(list, 1, PyFloat_FromDouble(right));
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, list);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args);
+    if(!res) throw std::runtime_error("Call to ylim() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+template<typename Numeric>
+void xlim(Numeric left, Numeric right)
+{
+    detail::_interpreter::get();
+
+    PyObject* list = PyList_New(2);
+    PyList_SetItem(list, 0, PyFloat_FromDouble(left));
+    PyList_SetItem(list, 1, PyFloat_FromDouble(right));
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, list);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args);
+    if(!res) throw std::runtime_error("Call to xlim() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+
+inline double* xlim()
+{
+    detail::_interpreter::get();
+
+    PyObject* args = PyTuple_New(0);
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_xlim, args);
+    PyObject* left = PyTuple_GetItem(res,0);
+    PyObject* right = PyTuple_GetItem(res,1);
+
+    double* arr = new double[2];
+    arr[0] = PyFloat_AsDouble(left);
+    arr[1] = PyFloat_AsDouble(right);
+
+    if(!res) throw std::runtime_error("Call to xlim() failed.");
+
+    Py_DECREF(res);
+    return arr;
+}
+
+
+inline double* ylim()
+{
+    detail::_interpreter::get();
+
+    PyObject* args = PyTuple_New(0);
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_ylim, args);
+    PyObject* left = PyTuple_GetItem(res,0);
+    PyObject* right = PyTuple_GetItem(res,1);
+
+    double* arr = new double[2];
+    arr[0] = PyFloat_AsDouble(left);
+    arr[1] = PyFloat_AsDouble(right);
+
+    if(!res) throw std::runtime_error("Call to ylim() failed.");
+
+    Py_DECREF(res);
+    return arr;
+}
+
+template<typename Numeric>
+inline void xticks(const std::vector<Numeric> &ticks, const std::vector<std::string> &labels = {}, const std::map<std::string, std::string>& keywords = {})
+{
+    assert(labels.size() == 0 || ticks.size() == labels.size());
+
+    detail::_interpreter::get();
+
+    // using numpy array
+    PyObject* ticksarray = detail::get_array(ticks);
+
+    PyObject* args;
+    if(labels.size() == 0) {
+        // construct positional args
+        args = PyTuple_New(1);
+        PyTuple_SetItem(args, 0, ticksarray);
+    } else {
+        // make tuple of tick labels
+        PyObject* labelstuple = PyTuple_New(labels.size());
+        for (size_t i = 0; i < labels.size(); i++)
+            PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str()));
+
+        // construct positional args
+        args = PyTuple_New(2);
+        PyTuple_SetItem(args, 0, ticksarray);
+        PyTuple_SetItem(args, 1, labelstuple);
+    }
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xticks, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if(!res) throw std::runtime_error("Call to xticks() failed");
+
+    Py_DECREF(res);
+}
+
+template<typename Numeric>
+inline void xticks(const std::vector<Numeric> &ticks, const std::map<std::string, std::string>& keywords)
+{
+    xticks(ticks, {}, keywords);
+}
+
+template<typename Numeric>
+inline void yticks(const std::vector<Numeric> &ticks, const std::vector<std::string> &labels = {}, const std::map<std::string, std::string>& keywords = {})
+{
+    assert(labels.size() == 0 || ticks.size() == labels.size());
+
+    detail::_interpreter::get();
+
+    // using numpy array
+    PyObject* ticksarray = detail::get_array(ticks);
+
+    PyObject* args;
+    if(labels.size() == 0) {
+        // construct positional args
+        args = PyTuple_New(1);
+        PyTuple_SetItem(args, 0, ticksarray);
+    } else {
+        // make tuple of tick labels
+        PyObject* labelstuple = PyTuple_New(labels.size());
+        for (size_t i = 0; i < labels.size(); i++)
+            PyTuple_SetItem(labelstuple, i, PyUnicode_FromString(labels[i].c_str()));
+
+        // construct positional args
+        args = PyTuple_New(2);
+        PyTuple_SetItem(args, 0, ticksarray);
+        PyTuple_SetItem(args, 1, labelstuple);
+    }
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_yticks, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if(!res) throw std::runtime_error("Call to yticks() failed");
+
+    Py_DECREF(res);
+}
+
+template<typename Numeric>
+inline void yticks(const std::vector<Numeric> &ticks, const std::map<std::string, std::string>& keywords)
+{
+    yticks(ticks, {}, keywords);
+}
+
+template <typename Numeric> inline void margins(Numeric margin)
+{
+    // construct positional args
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin));
+
+    PyObject* res =
+            PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args);
+    if (!res)
+        throw std::runtime_error("Call to margins() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+template <typename Numeric> inline void margins(Numeric margin_x, Numeric margin_y)
+{
+    // construct positional args
+    PyObject* args = PyTuple_New(2);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(margin_x));
+    PyTuple_SetItem(args, 1, PyFloat_FromDouble(margin_y));
+
+    PyObject* res =
+            PyObject_CallObject(detail::_interpreter::get().s_python_function_margins, args);
+    if (!res)
+        throw std::runtime_error("Call to margins() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+
+inline void tick_params(const std::map<std::string, std::string>& keywords, const std::string axis = "both")
+{
+  detail::_interpreter::get();
+
+  // construct positional args
+  PyObject* args;
+  args = PyTuple_New(1);
+  PyTuple_SetItem(args, 0, PyString_FromString(axis.c_str()));
+
+  // construct keyword args
+  PyObject* kwargs = PyDict_New();
+  for (std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+  {
+    PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+  }
+
+
+  PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_tick_params, args, kwargs);
+
+  Py_DECREF(args);
+  Py_DECREF(kwargs);
+  if (!res) throw std::runtime_error("Call to tick_params() failed");
+
+  Py_DECREF(res);
+}
+
+inline void subplot(long nrows, long ncols, long plot_number)
+{
+    detail::_interpreter::get();
+    
+    // construct positional args
+    PyObject* args = PyTuple_New(3);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(nrows));
+    PyTuple_SetItem(args, 1, PyFloat_FromDouble(ncols));
+    PyTuple_SetItem(args, 2, PyFloat_FromDouble(plot_number));
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot, args);
+    if(!res) throw std::runtime_error("Call to subplot() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void subplot2grid(long nrows, long ncols, long rowid=0, long colid=0, long rowspan=1, long colspan=1)
+{
+    detail::_interpreter::get();
+
+    PyObject* shape = PyTuple_New(2);
+    PyTuple_SetItem(shape, 0, PyLong_FromLong(nrows));
+    PyTuple_SetItem(shape, 1, PyLong_FromLong(ncols));
+
+    PyObject* loc = PyTuple_New(2);
+    PyTuple_SetItem(loc, 0, PyLong_FromLong(rowid));
+    PyTuple_SetItem(loc, 1, PyLong_FromLong(colid));
+
+    PyObject* args = PyTuple_New(4);
+    PyTuple_SetItem(args, 0, shape);
+    PyTuple_SetItem(args, 1, loc);
+    PyTuple_SetItem(args, 2, PyLong_FromLong(rowspan));
+    PyTuple_SetItem(args, 3, PyLong_FromLong(colspan));
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_subplot2grid, args);
+    if(!res) throw std::runtime_error("Call to subplot2grid() failed.");
+
+    Py_DECREF(shape);
+    Py_DECREF(loc);
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void title(const std::string &titlestr, const std::map<std::string, std::string> &keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* pytitlestr = PyString_FromString(titlestr.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pytitlestr);
+
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_title, args, kwargs);
+    if(!res) throw std::runtime_error("Call to title() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    Py_DECREF(res);
+}
+
+inline void suptitle(const std::string &suptitlestr, const std::map<std::string, std::string> &keywords = {})
+{
+    detail::_interpreter::get();
+    
+    PyObject* pysuptitlestr = PyString_FromString(suptitlestr.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pysuptitlestr);
+
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_suptitle, args, kwargs);
+    if(!res) throw std::runtime_error("Call to suptitle() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    Py_DECREF(res);
+}
+
+inline void axis(const std::string &axisstr)
+{
+    detail::_interpreter::get();
+
+    PyObject* str = PyString_FromString(axisstr.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, str);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_axis, args);
+    if(!res) throw std::runtime_error("Call to title() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void axvline(double x, double ymin = 0., double ymax = 1., const std::map<std::string, std::string>& keywords = std::map<std::string, std::string>())
+{
+    detail::_interpreter::get();
+
+    // construct positional args
+    PyObject* args = PyTuple_New(3);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(x));
+    PyTuple_SetItem(args, 1, PyFloat_FromDouble(ymin));
+    PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymax));
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvline, args, kwargs);
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if(res) Py_DECREF(res);
+}
+
+inline void axvspan(double xmin, double xmax, double ymin = 0., double ymax = 1., const std::map<std::string, std::string>& keywords = std::map<std::string, std::string>())
+{
+    // construct positional args
+    PyObject* args = PyTuple_New(4);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(xmin));
+    PyTuple_SetItem(args, 1, PyFloat_FromDouble(xmax));
+    PyTuple_SetItem(args, 2, PyFloat_FromDouble(ymin));
+    PyTuple_SetItem(args, 3, PyFloat_FromDouble(ymax));
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+    if (it->first == "linewidth" || it->first == "alpha")
+            PyDict_SetItemString(kwargs, it->first.c_str(), PyFloat_FromDouble(std::stod(it->second)));
+    else
+            PyDict_SetItemString(kwargs, it->first.c_str(), PyString_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_axvspan, args, kwargs);
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+
+    if(res) Py_DECREF(res);
+}
+
+inline void xlabel(const std::string &str, const std::map<std::string, std::string> &keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* pystr = PyString_FromString(str.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pystr);
+
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_xlabel, args, kwargs);
+    if(!res) throw std::runtime_error("Call to xlabel() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    Py_DECREF(res);
+}
+
+inline void ylabel(const std::string &str, const std::map<std::string, std::string>& keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject* pystr = PyString_FromString(str.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pystr);
+
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_ylabel, args, kwargs);
+    if(!res) throw std::runtime_error("Call to ylabel() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    Py_DECREF(res);
+}
+
+inline void set_zlabel(const std::string &str, const std::map<std::string, std::string>& keywords = {})
+{
+    detail::_interpreter::get();
+
+    // Same as with plot_surface: We lazily load the modules here the first time 
+    // this function is called because I'm not sure that we can assume "matplotlib 
+    // installed" implies "mpl_toolkits installed" on all platforms, and we don't 
+    // want to require it for people who don't need 3d plots.
+    static PyObject *mpl_toolkitsmod = nullptr, *axis3dmod = nullptr;
+    if (!mpl_toolkitsmod) {
+        PyObject* mpl_toolkits = PyString_FromString("mpl_toolkits");
+        PyObject* axis3d = PyString_FromString("mpl_toolkits.mplot3d");
+        if (!mpl_toolkits || !axis3d) { throw std::runtime_error("couldnt create string"); }
+
+        mpl_toolkitsmod = PyImport_Import(mpl_toolkits);
+        Py_DECREF(mpl_toolkits);
+        if (!mpl_toolkitsmod) { throw std::runtime_error("Error loading module mpl_toolkits!"); }
+
+        axis3dmod = PyImport_Import(axis3d);
+        Py_DECREF(axis3d);
+        if (!axis3dmod) { throw std::runtime_error("Error loading module mpl_toolkits.mplot3d!"); }
+    }
+
+    PyObject* pystr = PyString_FromString(str.c_str());
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pystr);
+
+    PyObject* kwargs = PyDict_New();
+    for (auto it = keywords.begin(); it != keywords.end(); ++it) {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject *ax =
+    PyObject_CallObject(detail::_interpreter::get().s_python_function_gca,
+      detail::_interpreter::get().s_python_empty_tuple);
+    if (!ax) throw std::runtime_error("Call to gca() failed.");
+    Py_INCREF(ax);
+
+    PyObject *zlabel = PyObject_GetAttrString(ax, "set_zlabel");
+    if (!zlabel) throw std::runtime_error("Attribute set_zlabel not found.");
+    Py_INCREF(zlabel);
+
+    PyObject *res = PyObject_Call(zlabel, args, kwargs);
+    if (!res) throw std::runtime_error("Call to set_zlabel() failed.");
+    Py_DECREF(zlabel);
+
+    Py_DECREF(ax);
+    Py_DECREF(args);
+    Py_DECREF(kwargs);
+    if (res) Py_DECREF(res);
+}
+
+inline void grid(bool flag)
+{
+    detail::_interpreter::get();
+
+    PyObject* pyflag = flag ? Py_True : Py_False;
+    Py_INCREF(pyflag);
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pyflag);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_grid, args);
+    if(!res) throw std::runtime_error("Call to grid() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void show(const bool block = true)
+{
+    detail::_interpreter::get();
+
+    PyObject* res;
+    if(block)
+    {
+        res = PyObject_CallObject(
+                detail::_interpreter::get().s_python_function_show,
+                detail::_interpreter::get().s_python_empty_tuple);
+    }
+    else
+    {
+        PyObject *kwargs = PyDict_New();
+        PyDict_SetItemString(kwargs, "block", Py_False);
+        res = PyObject_Call( detail::_interpreter::get().s_python_function_show, detail::_interpreter::get().s_python_empty_tuple, kwargs);
+       Py_DECREF(kwargs);
+    }
+
+
+    if (!res) throw std::runtime_error("Call to show() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void close()
+{
+    detail::_interpreter::get();
+
+    PyObject* res = PyObject_CallObject(
+            detail::_interpreter::get().s_python_function_close,
+            detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res) throw std::runtime_error("Call to close() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void xkcd() {
+    detail::_interpreter::get();
+
+    PyObject* res;
+    PyObject *kwargs = PyDict_New();
+
+    res = PyObject_Call(detail::_interpreter::get().s_python_function_xkcd,
+            detail::_interpreter::get().s_python_empty_tuple, kwargs);
+
+    Py_DECREF(kwargs);
+
+    if (!res)
+        throw std::runtime_error("Call to show() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void draw()
+{
+    detail::_interpreter::get();
+
+    PyObject* res = PyObject_CallObject(
+        detail::_interpreter::get().s_python_function_draw,
+        detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res) throw std::runtime_error("Call to draw() failed.");
+
+    Py_DECREF(res);
+}
+
+template<typename Numeric>
+inline void pause(Numeric interval)
+{
+    detail::_interpreter::get();
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, PyFloat_FromDouble(interval));
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_pause, args);
+    if(!res) throw std::runtime_error("Call to pause() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void save(const std::string& filename)
+{
+    detail::_interpreter::get();
+
+    PyObject* pyfilename = PyString_FromString(filename.c_str());
+
+    PyObject* args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, pyfilename);
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_save, args);
+    if (!res) throw std::runtime_error("Call to save() failed.");
+
+    Py_DECREF(args);
+    Py_DECREF(res);
+}
+
+inline void clf() {
+    detail::_interpreter::get();
+
+    PyObject *res = PyObject_CallObject(
+        detail::_interpreter::get().s_python_function_clf,
+        detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res) throw std::runtime_error("Call to clf() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void cla() {
+    detail::_interpreter::get();
+
+    PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_cla,
+                                        detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res)
+        throw std::runtime_error("Call to cla() failed.");
+
+    Py_DECREF(res);
+}
+
+inline void ion() {
+    detail::_interpreter::get();
+
+    PyObject *res = PyObject_CallObject(
+        detail::_interpreter::get().s_python_function_ion,
+        detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res) throw std::runtime_error("Call to ion() failed.");
+
+    Py_DECREF(res);
+}
+
+inline std::vector<std::array<double, 2>> ginput(const int numClicks = 1, const std::map<std::string, std::string>& keywords = {})
+{
+    detail::_interpreter::get();
+
+    PyObject *args = PyTuple_New(1);
+    PyTuple_SetItem(args, 0, PyLong_FromLong(numClicks));
+
+    // construct keyword args
+    PyObject* kwargs = PyDict_New();
+    for(std::map<std::string, std::string>::const_iterator it = keywords.begin(); it != keywords.end(); ++it)
+    {
+        PyDict_SetItemString(kwargs, it->first.c_str(), PyUnicode_FromString(it->second.c_str()));
+    }
+
+    PyObject* res = PyObject_Call(
+        detail::_interpreter::get().s_python_function_ginput, args, kwargs);
+
+    Py_DECREF(kwargs);
+    Py_DECREF(args);
+    if (!res) throw std::runtime_error("Call to ginput() failed.");
+
+    const size_t len = PyList_Size(res);
+    std::vector<std::array<double, 2>> out;
+    out.reserve(len);
+    for (size_t i = 0; i < len; i++) {
+        PyObject *current = PyList_GetItem(res, i);
+        std::array<double, 2> position;
+        position[0] = PyFloat_AsDouble(PyTuple_GetItem(current, 0));
+        position[1] = PyFloat_AsDouble(PyTuple_GetItem(current, 1));
+        out.push_back(position);
+    }
+    Py_DECREF(res);
+
+    return out;
+}
+
+// Actually, is there any reason not to call this automatically for every plot?
+inline void tight_layout() {
+    detail::_interpreter::get();
+
+    PyObject *res = PyObject_CallObject(
+        detail::_interpreter::get().s_python_function_tight_layout,
+        detail::_interpreter::get().s_python_empty_tuple);
+
+    if (!res) throw std::runtime_error("Call to tight_layout() failed.");
+
+    Py_DECREF(res);
+}
+
+// Support for variadic plot() and initializer lists:
+
+namespace detail {
+
+template<typename T>
+using is_function = typename std::is_function<std::remove_pointer<std::remove_reference<T>>>::type;
+
+template<bool obj, typename T>
+struct is_callable_impl;
+
+template<typename T>
+struct is_callable_impl<false, T>
+{
+    typedef is_function<T> type;
+}; // a non-object is callable iff it is a function
+
+template<typename T>
+struct is_callable_impl<true, T>
+{
+    struct Fallback { void operator()(); };
+    struct Derived : T, Fallback { };
+
+    template<typename U, U> struct Check;
+
+    template<typename U>
+    static std::true_type test( ... ); // use a variadic function to make sure (1) it accepts everything and (2) its always the worst match
+
+    template<typename U>
+    static std::false_type test( Check<void(Fallback::*)(), &U::operator()>* );
+
+public:
+    typedef decltype(test<Derived>(nullptr)) type;
+    typedef decltype(&Fallback::operator()) dtype;
+    static constexpr bool value = type::value;
+}; // an object is callable iff it defines operator()
+
+template<typename T>
+struct is_callable
+{
+    // dispatch to is_callable_impl<true, T> or is_callable_impl<false, T> depending on whether T is of class type or not
+    typedef typename is_callable_impl<std::is_class<T>::value, T>::type type;
+};
+
+template<typename IsYDataCallable>
+struct plot_impl { };
+
+template<>
+struct plot_impl<std::false_type>
+{
+    template<typename IterableX, typename IterableY>
+    bool operator()(const IterableX& x, const IterableY& y, const std::string& format)
+    {
+        detail::_interpreter::get();
+
+        // 2-phase lookup for distance, begin, end
+        using std::distance;
+        using std::begin;
+        using std::end;
+
+        auto xs = distance(begin(x), end(x));
+        auto ys = distance(begin(y), end(y));
+        assert(xs == ys && "x and y data must have the same number of elements!");
+
+        PyObject* xlist = PyList_New(xs);
+        PyObject* ylist = PyList_New(ys);
+        PyObject* pystring = PyString_FromString(format.c_str());
+
+        auto itx = begin(x), ity = begin(y);
+        for(size_t i = 0; i < xs; ++i) {
+            PyList_SetItem(xlist, i, PyFloat_FromDouble(*itx++));
+            PyList_SetItem(ylist, i, PyFloat_FromDouble(*ity++));
+        }
+
+        PyObject* plot_args = PyTuple_New(3);
+        PyTuple_SetItem(plot_args, 0, xlist);
+        PyTuple_SetItem(plot_args, 1, ylist);
+        PyTuple_SetItem(plot_args, 2, pystring);
+
+        PyObject* res = PyObject_CallObject(detail::_interpreter::get().s_python_function_plot, plot_args);
+
+        Py_DECREF(plot_args);
+        if(res) Py_DECREF(res);
+
+        return res;
+    }
+};
+
+template<>
+struct plot_impl<std::true_type>
+{
+    template<typename Iterable, typename Callable>
+    bool operator()(const Iterable& ticks, const Callable& f, const std::string& format)
+    {
+        if(begin(ticks) == end(ticks)) return true;
+
+        // We could use additional meta-programming to deduce the correct element type of y,
+        // but all values have to be convertible to double anyways
+        std::vector<double> y;
+        for(auto x : ticks) y.push_back(f(x));
+        return plot_impl<std::false_type>()(ticks,y,format);
+    }
+};
+
+} // end namespace detail
+
+// recursion stop for the above
+template<typename... Args>
+bool plot() { return true; }
+
+template<typename A, typename B, typename... Args>
+bool plot(const A& a, const B& b, const std::string& format, Args... args)
+{
+    return detail::plot_impl<typename detail::is_callable<B>::type>()(a,b,format) && plot(args...);
+}
+
+/*
+ * This group of plot() functions is needed to support initializer lists, i.e. calling
+ *    plot( {1,2,3,4} )
+ */
+inline bool plot(const std::vector<double>& x, const std::vector<double>& y, const std::string& format = "") {
+    return plot<double,double>(x,y,format);
+}
+
+inline bool plot(const std::vector<double>& y, const std::string& format = "") {
+    return plot<double>(y,format);
+}
+
+inline bool plot(const std::vector<double>& x, const std::vector<double>& y, const std::map<std::string, std::string>& keywords) {
+    return plot<double>(x,y,keywords);
+}
+
+/*
+ * This class allows dynamic plots, ie changing the plotted data without clearing and re-plotting
+ */
+class Plot
+{
+public:
+    // default initialization with plot label, some data and format
+    template<typename Numeric>
+    Plot(const std::string& name, const std::vector<Numeric>& x, const std::vector<Numeric>& y, const std::string& format = "") {
+        detail::_interpreter::get();
+
+        assert(x.size() == y.size());
+
+        PyObject* kwargs = PyDict_New();
+        if(name != "")
+            PyDict_SetItemString(kwargs, "label", PyString_FromString(name.c_str()));
+
+        PyObject* xarray = detail::get_array(x);
+        PyObject* yarray = detail::get_array(y);
+
+        PyObject* pystring = PyString_FromString(format.c_str());
+
+        PyObject* plot_args = PyTuple_New(3);
+        PyTuple_SetItem(plot_args, 0, xarray);
+        PyTuple_SetItem(plot_args, 1, yarray);
+        PyTuple_SetItem(plot_args, 2, pystring);
+
+        PyObject* res = PyObject_Call(detail::_interpreter::get().s_python_function_plot, plot_args, kwargs);
+
+        Py_DECREF(kwargs);
+        Py_DECREF(plot_args);
+
+        if(res)
+        {
+            line= PyList_GetItem(res, 0);
+
+            if(line)
+                set_data_fct = PyObject_GetAttrString(line,"set_data");
+            else
+                Py_DECREF(line);
+            Py_DECREF(res);
+        }
+    }
+
+    // shorter initialization with name or format only
+    // basically calls line, = plot([], [])
+    Plot(const std::string& name = "", const std::string& format = "")
+        : Plot(name, std::vector<double>(), std::vector<double>(), format) {}
+
+    template<typename Numeric>
+    bool update(const std::vector<Numeric>& x, const std::vector<Numeric>& y) {
+        assert(x.size() == y.size());
+        if(set_data_fct)
+        {
+            PyObject* xarray = detail::get_array(x);
+            PyObject* yarray = detail::get_array(y);
+
+            PyObject* plot_args = PyTuple_New(2);
+            PyTuple_SetItem(plot_args, 0, xarray);
+            PyTuple_SetItem(plot_args, 1, yarray);
+
+            PyObject* res = PyObject_CallObject(set_data_fct, plot_args);
+            if (res) Py_DECREF(res);
+            return res;
+        }
+        return false;
+    }
+
+    // clears the plot but keep it available
+    bool clear() {
+        return update(std::vector<double>(), std::vector<double>());
+    }
+
+    // definitely remove this line
+    void remove() {
+        if(line)
+        {
+            auto remove_fct = PyObject_GetAttrString(line,"remove");
+            PyObject* args = PyTuple_New(0);
+            PyObject* res = PyObject_CallObject(remove_fct, args);
+            if (res) Py_DECREF(res);
+        }
+        decref();
+    }
+
+    ~Plot() {
+        decref();
+    }
+private:
+
+    void decref() {
+        if(line)
+            Py_DECREF(line);
+        if(set_data_fct)
+            Py_DECREF(set_data_fct);
+    }
+
+
+    PyObject* line = nullptr;
+    PyObject* set_data_fct = nullptr;
+};
+
+} // end namespace matplotlibcpp