diff --git a/include/base/processor/processor_tracker_landmark_apriltag.h b/include/base/processor/processor_tracker_landmark_apriltag.h
index cc0677e7145ce3f3865524f45044bd3dad50ffe0..9e0532cf5f869e2b4eedb750f90b996020203bfe 100644
--- a/include/base/processor/processor_tracker_landmark_apriltag.h
+++ b/include/base/processor/processor_tracker_landmark_apriltag.h
@@ -23,7 +23,6 @@ struct ProcessorParamsTrackerLandmarkApriltag : public ProcessorParamsTrackerLan
 {
     //tag parameters
     std::string tag_family_;
-    int tag_black_border_;
 
     // tag sizes
     Scalar tag_width_default_;
@@ -35,8 +34,6 @@ struct ProcessorParamsTrackerLandmarkApriltag : public ProcessorParamsTrackerLan
     unsigned int nthreads_;
     bool debug_;
     bool refine_edges_;
-    bool refine_decode_;
-    bool refine_pose_;
 
     Scalar std_xy_, std_z_, std_rpy_;
     Scalar std_pix_;
diff --git a/src/examples/processor_tracker_landmark_apriltag.yaml b/src/examples/processor_tracker_landmark_apriltag.yaml
index fc78c0d2b7c8feaa92f85600e68f3cc8cb565e39..e8b1fd02dc80ffedefafc44ae3af9898a873cb3b 100644
--- a/src/examples/processor_tracker_landmark_apriltag.yaml
+++ b/src/examples/processor_tracker_landmark_apriltag.yaml
@@ -7,8 +7,6 @@ detector parameters:
     nthreads:       8       # how many thread during tag detection (does not change much?)
     debug:          false    # write some debugging images
     refine_edges:   true    # better edge detection if quad_decimate > 1 (quite inexpensive, almost no diff)
-    refine_decode:  false    # improve detection probability for small tags (quite expensive (~*3)
-    refine_pose:    false    # improves detection by maximizing local contrast so that future pose extraction works better (VERY expensive ~*10-20)
     ippe_min_ratio:     3.0  	# quite arbitrary, always > 1 (to deactive, set at 0 for example)
     ippe_max_rep_error: 2.0     # to deactivate, set at something big (100)
 
@@ -20,7 +18,7 @@ tag widths:
 
 tag parameters:
     tag_family:           "tag36h11" 
-    tag_black_border:     1
+    # tag_black_border:     1
     tag_width_default:    0.165   # used if tag width not specified
 
     
diff --git a/src/processor/processor_tracker_landmark_apriltag.cpp b/src/processor/processor_tracker_landmark_apriltag.cpp
index 41cd1101da0ecb36e9c202b0d4078c853070b846..52fa046a9fc7049ed0799a506afd9a114e233753 100644
--- a/src/processor/processor_tracker_landmark_apriltag.cpp
+++ b/src/processor/processor_tracker_landmark_apriltag.cpp
@@ -13,11 +13,14 @@
 #include "common/homography.h"
 #include "common/zarray.h"
 
-#include <tag36h11.h>
-#include <tag36h10.h>
-#include <tag36artoolkit.h>
+#include <tag16h5.h>
 #include <tag25h9.h>
-#include <tag25h7.h>
+#include <tag36h11.h>
+#include <tagCircle21h7.h>
+#include <tagCircle49h12.h>
+#include <tagCustom48h12.h>
+#include <tagStandard41h12.h>
+#include <tagStandard52h13.h>
 
 #include "base/processor/ippe.h"
 
@@ -58,22 +61,28 @@ ProcessorTrackerLandmarkApriltag::ProcessorTrackerLandmarkApriltag( ProcessorPar
 
     // configure apriltag detector
     std::string famname(_params_tracker_landmark_apriltag->tag_family_);
-    if (famname == "tag36h11")
-        tag_family_ = *tag36h11_create();
-    else if (famname == "tag36h10")
-        tag_family_ = *tag36h10_create();
-    else if (famname == "tag36artoolkit")
-        tag_family_ = *tag36artoolkit_create();
+    if (famname == "tag16h5")
+        tag_family_ = *tag16h5_create();
     else if (famname == "tag25h9")
         tag_family_ = *tag25h9_create();
-    else if (famname == "tag25h7")
-        tag_family_ = *tag25h7_create();
+    else if (famname == "tag36h11")
+        tag_family_ = *tag36h11_create();
+    else if (famname == "tagCircle21h7")
+        tag_family_ = *tagCircle21h7_create();
+    else if (famname == "tagCircle49h12")
+        tag_family_ = *tagCircle49h12_create();
+    else if (famname == "tagCustom48h12")
+        tag_family_ = *tagCustom48h12_create();
+    else if (famname == "tagStandard41h12")
+        tag_family_ = *tagStandard41h12_create();
+    else if (famname == "tagStandard52h13")
+        tag_family_ = *tagStandard52h13_create();
     else {
-        WOLF_ERROR("Unrecognized tag family name. Use e.g. \"tag36h11\".");
+        WOLF_ERROR(famname, ": Unrecognized tag family name. Use e.g. \"tag36h11\".");
         exit(-1);
     }
 
-    tag_family_.black_border     = _params_tracker_landmark_apriltag->tag_black_border_;
+    // tag_family_.black_border     = _params_tracker_landmark_apriltag->tag_black_border_;
 
     detector_ = *apriltag_detector_create();
     apriltag_detector_add_family(&detector_, &tag_family_);
@@ -83,8 +92,6 @@ ProcessorTrackerLandmarkApriltag::ProcessorTrackerLandmarkApriltag( ProcessorPar
     detector_.nthreads          = _params_tracker_landmark_apriltag->nthreads_;
     detector_.debug             = _params_tracker_landmark_apriltag->debug_;
     detector_.refine_edges      = _params_tracker_landmark_apriltag->refine_edges_;
-    detector_.refine_decode     = _params_tracker_landmark_apriltag->refine_decode_;
-    detector_.refine_pose       = _params_tracker_landmark_apriltag->refine_pose_;
 }
 
 // Destructor
diff --git a/src/yaml/processor_tracker_landmark_apriltag_yaml.cpp b/src/yaml/processor_tracker_landmark_apriltag_yaml.cpp
index 339fb428d5daf46266cce1b6604c8c189dab623c..70a44fc672b41eaacd09fd5dc36b7d642bb283cf 100644
--- a/src/yaml/processor_tracker_landmark_apriltag_yaml.cpp
+++ b/src/yaml/processor_tracker_landmark_apriltag_yaml.cpp
@@ -38,14 +38,12 @@ static ProcessorParamsBasePtr createProcessorParamsLandmarkApriltag(const std::s
         params->nthreads_                   = detector_parameters["nthreads"]                 .as<int>();
         params->debug_                      = detector_parameters["debug"]                    .as<bool>();
         params->refine_edges_               = detector_parameters["refine_edges"]             .as<bool>();
-        params->refine_decode_              = detector_parameters["refine_decode"]            .as<bool>();
-        params->refine_pose_                = detector_parameters["refine_pose"]              .as<bool>();
         params->ippe_min_ratio_             = detector_parameters["ippe_min_ratio"]           .as<Scalar>();
         params->ippe_max_rep_error_         = detector_parameters["ippe_max_rep_error"]       .as<Scalar>();
 
         YAML::Node tag_parameters           = config["tag parameters"];
         params->tag_family_                 = tag_parameters["tag_family"]          .as<std::string>();
-        params->tag_black_border_           = tag_parameters["tag_black_border"]    .as<int>();
+        // params->tag_black_border_           = tag_parameters["tag_black_border"]    .as<int>();
         params->tag_width_default_          = tag_parameters["tag_width_default"]   .as<Scalar>();
 
         // read list of tag widths
diff --git a/test/gtest_odom_2D.cpp b/test/gtest_odom_2D.cpp
index 604ef489478f5779ac4b79a14095c37436c81be4..2c8ab239bb890532f8a26f1e41bb713d9c6e0019 100644
--- a/test/gtest_odom_2D.cpp
+++ b/test/gtest_odom_2D.cpp
@@ -329,7 +329,7 @@ TEST(Odom2D, KF_callback)
     params->angle_turned    = 6.28;
     params->max_time_span   = 100;
     params->cov_det         = 100;
-    params->unmeasured_perturbation_std = 0.000001;
+    params->unmeasured_perturbation_std = 0.0000001;
     Matrix3s unmeasured_cov = params->unmeasured_perturbation_std*params->unmeasured_perturbation_std*Matrix3s::Identity();
     ProcessorBasePtr prc_base = problem->installProcessor("ODOM 2D", "odom", sensor_odom2d, params);
     ProcessorOdom2DPtr processor_odom2d = std::static_pointer_cast<ProcessorOdom2D>(prc_base);