فهرست منبع

Preparing merge.

anonimous 1 سال پیش
والد
کامیت
fffcc86ab1
100فایلهای تغییر یافته به همراه8566 افزوده شده و 443 حذف شده
  1. 466 157
      src/yafl.c
  2. 55 19
      src/yafl.h
  3. 33 4
      src/yafl_math.c
  4. 19 2
      src/yafl_math.h
  5. 2064 207
      src/yaflpy/yaflpy.pyx
  6. 537 0
      tests/src/filterpy/UDEKF.py
  7. 161 0
      tests/src/filterpy/UDEKHFPrior2.py
  8. 73 0
      tests/src/filterpy/init_tests.py
  9. 103 0
      tests/src/filterpy/testFilterpy01.py
  10. 116 0
      tests/src/filterpy/testFilterpy02.py
  11. 133 0
      tests/src/filterpy/testFilterpy03.py
  12. 106 0
      tests/src/filterpy/testFilterpy04.py
  13. 48 0
      tests/src/np/testNp001.py
  14. 50 0
      tests/src/np/testNp002.py
  15. 50 0
      tests/src/np/testNp003.py
  16. 52 0
      tests/src/np/testNp004.py
  17. 53 0
      tests/src/np/testNp005.py
  18. 53 0
      tests/src/np/testNp006.py
  19. 48 0
      tests/src/np/testNp007.py
  20. 49 0
      tests/src/np/testNp008.py
  21. 49 0
      tests/src/np/testNp009.py
  22. 48 0
      tests/src/np/testNp010.py
  23. 49 0
      tests/src/np/testNp011.py
  24. 49 0
      tests/src/np/testNp012.py
  25. 48 0
      tests/src/np/testNp013.py
  26. 51 0
      tests/src/np/testNp014.py
  27. 51 0
      tests/src/np/testNp015.py
  28. 51 0
      tests/src/np/testNp016.py
  29. 56 0
      tests/src/np/testNp017.py
  30. 56 0
      tests/src/np/testNp018.py
  31. 56 0
      tests/src/np/testNp019.py
  32. 51 0
      tests/src/np/testNp020.py
  33. 51 0
      tests/src/np/testNp021.py
  34. 51 0
      tests/src/np/testNp022.py
  35. 51 0
      tests/src/np/testNp023.py
  36. 51 0
      tests/src/np/testNp024.py
  37. 51 0
      tests/src/np/testNp025.py
  38. 52 0
      tests/src/np/testNp026.py
  39. 52 0
      tests/src/np/testNp027.py
  40. 52 0
      tests/src/np/testNp028.py
  41. 49 0
      tests/src/np/testNp029.py
  42. 49 0
      tests/src/np/testNp030.py
  43. 50 0
      tests/src/np/testNp031.py
  44. 50 0
      tests/src/np/testNp032.py
  45. 50 0
      tests/src/np/testNp033.py
  46. 50 0
      tests/src/np/testNp034.py
  47. 50 0
      tests/src/np/testNp035.py
  48. 50 0
      tests/src/np/testNp036.py
  49. 50 0
      tests/src/np/testNp037.py
  50. 50 0
      tests/src/np/testNp038.py
  51. 50 0
      tests/src/np/testNp039.py
  52. 57 0
      tests/src/np/testNp040.py
  53. 57 0
      tests/src/np/testNp041.py
  54. 57 0
      tests/src/np/testNp042.py
  55. 56 0
      tests/src/np/testNp043.py
  56. 56 0
      tests/src/np/testNp044.py
  57. 56 0
      tests/src/np/testNp045.py
  58. 56 0
      tests/src/np/testNp046.py
  59. 57 0
      tests/src/np/testNp047.py
  60. 56 0
      tests/src/np/testNp048.py
  61. 56 0
      tests/src/np/testNp049.py
  62. 56 0
      tests/src/np/testNp050.py
  63. 56 0
      tests/src/np/testNp051.py
  64. 57 0
      tests/src/np/testNp052.py
  65. 57 0
      tests/src/np/testNp053.py
  66. 57 0
      tests/src/np/testNp054.py
  67. 58 0
      tests/src/np/testNp055.py
  68. 58 0
      tests/src/np/testNp056.py
  69. 58 0
      tests/src/np/testNp057.py
  70. 62 0
      tests/src/np/testNp058.py
  71. 62 0
      tests/src/np/testNp059.py
  72. 62 0
      tests/src/np/testNp060.py
  73. 49 0
      tests/src/np/testNp061.py
  74. 49 0
      tests/src/np/testNp062.py
  75. 49 0
      tests/src/np/testNp063.py
  76. 54 0
      tests/src/np/testNp064.py
  77. 57 0
      tests/src/np/testNp065.py
  78. 62 0
      tests/src/np/testNp066.py
  79. 47 22
      tests/src/yafl/ab_tests.py
  80. 11 18
      tests/src/yafl/case1.py
  81. 14 14
      tests/src/yafl/create_test_data.py
  82. 0 0
      tests/src/yafl/test001.py
  83. 71 0
      tests/src/yafl/test002.py
  84. 71 0
      tests/src/yafl/test003.py
  85. 71 0
      tests/src/yafl/test004.py
  86. 0 0
      tests/src/yafl/test005.py
  87. 72 0
      tests/src/yafl/test006.py
  88. 73 0
      tests/src/yafl/test007.py
  89. 73 0
      tests/src/yafl/test008.py
  90. 0 0
      tests/src/yafl/test009.py
  91. 86 0
      tests/src/yafl/test010.py
  92. 0 0
      tests/src/yafl/test011.py
  93. 74 0
      tests/src/yafl/test012.py
  94. 73 0
      tests/src/yafl/test013.py
  95. 74 0
      tests/src/yafl/test014.py
  96. 74 0
      tests/src/yafl/test015.py
  97. 75 0
      tests/src/yafl/test016.py
  98. 76 0
      tests/src/yafl/test017.py
  99. 83 0
      tests/src/yafl/test018.py
  100. 78 0
      tests/src/yafl/test019.py

تفاوت فایلی نمایش داده نمی شود زیرا این فایل بسیار بزرگ است
+ 466 - 157
src/yafl.c


+ 55 - 19
src/yafl.h

@@ -64,6 +64,8 @@ struct _yaflKalmanBaseSt {
     yaflFloat * Ur; /*Upper triangular part of R*/
     yaflFloat * Dr; /*Diagonal part of R*/
 
+    yaflFloat rff;  /*R forgetting factor*/
+
     yaflInt   Nx;   /*State vector size*/
     yaflInt   Nz;   /*Measurement vector size*/
 };
@@ -83,6 +85,7 @@ struct _yaflKalmanBaseSt {
     yaflFloat Dr[nz]
 
 /*---------------------------------------------------------------------------*/
+/*TODO: make qff and rff parameters*/
 #define YAFL_KALMAN_BASE_INITIALIZER(_f, _h, _zrf, _nx, _nz, _mem) \
 {                                                                  \
     .f   = (yaflKalmanFuncP)_f,                                    \
@@ -101,6 +104,8 @@ struct _yaflKalmanBaseSt {
     .Ur  = _mem.Ur,                                                \
     .Dr  = _mem.Dr,                                                \
                                                                    \
+    .rff = 0.0,                                                    \
+                                                                   \
     .Nx  = _nx,                                                    \
     .Nz  = _nz                                                     \
 }
@@ -134,6 +139,8 @@ struct _yaflEKFBaseSt {
     yaflFloat * H;   /*Measurement Jacobian values*/
     yaflFloat * W;   /*Scratchpad memory block matrix*/
     yaflFloat * D;   /*Scratchpad memory diagonal matrix*/
+
+    yaflFloat qff;  /*Q forgetting factor*/
 };
 
 /*---------------------------------------------------------------------------*/
@@ -141,8 +148,16 @@ struct _yaflEKFBaseSt {
     YAFL_KALMAN_BASE_MEMORY_MIXIN(nx, nz); \
                                            \
     yaflFloat H[nz * nx];                  \
-    yaflFloat W[2 * nx * nx];              \
-    yaflFloat D[2 * nx]
+    union {                                \
+        yaflFloat x[2 * nx * nx];          \
+        yaflFloat z[(nx + nz) * nz];       \
+    } W;                                   \
+    union {                                \
+        yaflFloat x[2 * nx];               \
+        yaflFloat z[nx + nz];              \
+    } D
+
+
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_EKF_BASE_INITIALIZER(_f, _jf, _h, _jh, _zrf, _nx, _nz, _mem) \
@@ -153,8 +168,10 @@ struct _yaflEKFBaseSt {
     .jh  = (yaflKalmanFuncP)_jh,                                          \
                                                                           \
     .H   = _mem.H,                                                        \
-    .W   = _mem.W,                                                        \
-    .D   = _mem.D                                                         \
+    .W   = _mem.W.x,                                                      \
+    .D   = _mem.D.x,                                                      \
+                                                                          \
+    .qff = 0.0                                                            \
 }
 
 /*---------------------------------------------------------------------------*/
@@ -382,6 +399,7 @@ struct _yaflUKFBaseSt {
 
     /*Scratchpad memory*/
     yaflFloat * Sx;  /* State       */
+    yaflFloat * Sz;  /* Measurement */
     yaflFloat * Pzx; /* Pzx cross covariance matrix */
 
     yaflFloat * sigmas_x; /* State sigma points       */
@@ -395,13 +413,36 @@ struct _yaflUKFBaseSt {
 Warning: sigmas_x and _sigmas_z aren't defined in this mixin, see
          sigma points generators mixins!!!
 */
-#define YAFL_UKF_BASE_MEMORY_MIXIN(nx, nz) \
+#define YAFL_UKF_BASE_MEMORY_MIXIN(nx, nz)  \
     YAFL_KALMAN_BASE_MEMORY_MIXIN(nx, nz);  \
     yaflFloat zp[nz];                       \
-                                            \
-    yaflFloat Pzx[nz * nx];                 \
-                                            \
-    yaflFloat Sx[nx]
+    yaflFloat Sx[nx];                       \
+    yaflFloat Sz[nz];                       \
+    yaflFloat Pzx[nz * nx]
+
+
+/*---------------------------------------------------------------------------*/
+/*
+Sigma point memory mixin.
+
+WARNING:
+
+1. _SIGMAS_X and _SIGMAS_Z must be the parts of some larger
+    memory pool which has minimum size of (nx + nz) * (nz + 1)
+    or np * (nx + nz) where np is number of sigma points
+
+2. _SIGMAS_X must be at start of this pool
+*/
+#define YAFL_UKF_SP_MEMORY_MIXIN(np, nx, nz)          \
+    yaflFloat wm[np];                                 \
+    yaflFloat wc[np];                                 \
+    union{                                            \
+        struct {                                      \
+                yaflFloat x[(np) * nx];               \
+                yaflFloat z[(np) * nz];               \
+        } sigmas;                                     \
+        yaflFloat r_update_buf[(nx + nz) * (nz + 1)]; \
+    } pool
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_UKF_BASE_INITIALIZER(_p, _pm, _f, _xmf, _xrf, _h, _zmf,          \
@@ -420,10 +461,11 @@ Warning: sigmas_x and _sigmas_z aren't defined in this mixin, see
     .zp  = _mem.zp,                                                           \
                                                                               \
     .Sx  = _mem.Sx,                                                           \
+    .Sz  = _mem.Sz,                                                           \
     .Pzx = _mem.Pzx,                                                          \
                                                                               \
-    .sigmas_x  = _mem.sigmas_x,                                               \
-    .sigmas_z  = _mem.sigmas_z,                                               \
+    .sigmas_x  = _mem.pool.sigmas.x,                                          \
+    .sigmas_z  = _mem.pool.sigmas.z,                                          \
                                                                               \
     .wm   = _mem.wm,                                                          \
     .wc   = _mem.wc                                                           \
@@ -606,10 +648,7 @@ typedef struct _yaflUKFMerweSt {
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_UKF_MERWE_MEMORY_MIXIN(nx, nz) \
-    yaflFloat wm[2 * nx + 1];               \
-    yaflFloat wc[2 * nx + 1];               \
-    yaflFloat sigmas_x[(2 * nx + 1) * nx];  \
-    yaflFloat sigmas_z[(2 * nx + 1) * nz]
+    YAFL_UKF_SP_MEMORY_MIXIN(2 * nx + 1, nx, nz)
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_UKF_MERWE_INITIALIZER(_nx, _addf, _alpha, _beta, _kappa, _mem) \
@@ -633,10 +672,7 @@ typedef struct _yaflUKFJulierSt {
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_UKF_JULIER_MEMORY_MIXIN(nx, nz) \
-    yaflFloat wm[2 * nx + 1];               \
-    yaflFloat wc[2 * nx + 1];               \
-    yaflFloat sigmas_x[(2 * nx + 1) * nx];  \
-    yaflFloat sigmas_z[(2 * nx + 1) * nz]
+    YAFL_UKF_SP_MEMORY_MIXIN(2 * nx + 1, nx, nz)
 
 /*---------------------------------------------------------------------------*/
 #define YAFL_UKF_JULIER_INITIALIZER(_nx, _addf, _kappa, _mem) \

+ 33 - 4
src/yafl_math.c

@@ -470,6 +470,35 @@ yaflStatusEn name(yaflInt sz, yaflFloat *res, yaflFloat *u) \
 _DO_U(yafl_math_add_u, +=)
 _DO_U(yafl_math_sub_u, -=)
 
+#define _DO_BM(name, op)                                                           \
+yaflStatusEn name(yaflInt nc, yaflFloat *res, yaflInt sr, yaflInt sc, yaflFloat *a) \
+{                                                                                  \
+    yaflInt j;                                                          \
+                                                                        \
+    YAFL_CHECK(res, YAFL_ST_INV_ARG_2);                                 \
+    YAFL_CHECK(a,   YAFL_ST_INV_ARG_4);                                 \
+                                                                        \
+    for (j = 0; j < sr; j++)                                            \
+    {                                                                   \
+        yaflInt k;                                                      \
+        yaflInt ncj;                                                    \
+        yaflInt scj;                                                    \
+                                                                        \
+        ncj = nc * j;                                                   \
+        scj = sc * j;                                                   \
+                                                                        \
+        for (k = 0; k < sc; k++)                                        \
+        {                                                               \
+            res[ncj + k] op a[scj + k];                                 \
+        }                                                               \
+    }                                                                   \
+    return YAFL_ST_OK;                                                  \
+}
+
+_DO_BM(yafl_math_bset_m,  =)
+_DO_BM(yafl_math_badd_m, +=)
+_DO_BM(yafl_math_bsub_m, -=)
+
 yaflStatusEn yafl_math_bset_u(yaflInt nc, yaflFloat *res, yaflInt sz, yaflFloat *u)
 {
     yaflInt i;
@@ -563,7 +592,7 @@ yaflStatusEn name(yaflInt nc, yaflFloat *res, yaflInt sz, yaflFloat *u) \
     YAFL_CHECK(res, YAFL_ST_INV_ARG_2);                                 \
     YAFL_CHECK(u,   YAFL_ST_INV_ARG_4);                                 \
                                                                         \
-    for (szi = 0, i = 1; i < sz; szi += i++)                            \
+    for (szi = 0, i = 0; i < sz; szi += i++)                            \
     {                                                                   \
         yaflInt nci;                                                    \
         yaflInt j;                                                      \
@@ -639,7 +668,7 @@ yaflStatusEn name(yaflInt rnc, yaflFloat *res, yaflInt nr, yaflInt nc, yaflFloat
     YAFL_CHECK(res,      YAFL_ST_INV_ARG_2);                                                       \
     YAFL_CHECK(a,        YAFL_ST_INV_ARG_5);                                                       \
     YAFL_CHECK(b,        YAFL_ST_INV_ARG_6);                                                       \
-    YAFL_CHECK(rnc > nc, YAFL_ST_INV_ARG_1);                                                       \
+    YAFL_CHECK(rnc >= nc, YAFL_ST_INV_ARG_1);                                                      \
                                                                                                    \
     for (i = 0; i < nr; i++)                                                                       \
     {                                                                                              \
@@ -684,8 +713,8 @@ yaflStatusEn name(yaflInt rnc, yaflFloat *res, yaflInt nr, yaflInt nc, yaflInt a
     YAFL_CHECK(res,      YAFL_ST_INV_ARG_2);                                                                    \
     YAFL_CHECK(a,        YAFL_ST_INV_ARG_6);                                                                    \
     YAFL_CHECK(b,        YAFL_ST_INV_ARG_7);                                                                    \
-    YAFL_CHECK(rnc > nc, YAFL_ST_INV_ARG_1);                                                                    \
-    YAFL_CHECK(anc > nc, YAFL_ST_INV_ARG_5);                                                                    \
+    YAFL_CHECK(rnc >= nc, YAFL_ST_INV_ARG_1);                                                                   \
+    YAFL_CHECK(anc >= nc, YAFL_ST_INV_ARG_5);                                                                   \
                                                                                                                 \
     for (i = 0; i < nr; i++)                                                                                    \
     {                                                                                                           \

+ 19 - 2
src/yafl_math.h

@@ -72,7 +72,8 @@ typedef enum {
     YAFL_ST_INV_ARG_8    = 0x170,
     YAFL_ST_INV_ARG_9    = 0x180,
     YAFL_ST_INV_ARG_10   = 0x190,
-    YAFL_ST_INV_ARG_11   = 0x1a0
+    YAFL_ST_INV_ARG_11   = 0x1a0,
+    YAFL_ST_INV_ARG_12   = 0x1b0
 } yaflStatusEn;
 
 #define _YAFL_TRY(status, exp, file, func, line)                              \
@@ -213,7 +214,15 @@ yaflStatusEn yafl_math_add_u(yaflInt sz, yaflFloat *res, yaflFloat *u);
 yaflStatusEn yafl_math_sub_u(yaflInt sz, yaflFloat *res, yaflFloat *u);                            /* res -= u          */
 
 /*Matrix row size and block start address*/
-#define YAFL_BLK(m,nc,r,c) nc, ((yaflFloat *)m + nc * r + c)
+#define YAFL_BLK_PTR(m,nc,r,c) ((yaflFloat *)m + nc * r + c)
+#define YAFL_BLK(m,nc,r,c) nc, YAFL_BLK_PTR(m,nc,r,c)
+
+/*For test purposes...*/
+static inline yaflFloat * _yafl_blk_ptr(yaflFloat * m, yaflInt nc, yaflInt r, yaflInt c)
+{
+    return YAFL_BLK_PTR(m,nc,r,c);
+}
+
 /*
 Block operations:
 
@@ -223,6 +232,14 @@ v - vector
 ------------------------------------------------------------------------------------------------------------------------
                                    Function/Macro                                                   NumPy expr
 ----------------------------------------------------------------------------------------------------------------------*/
+yaflStatusEn yafl_math_bset_m(yaflInt nc, yaflFloat *res, yaflInt sr, yaflInt sc, yaflFloat *a); /* res[:sr, :sc]  = a       */
+yaflStatusEn yafl_math_badd_m(yaflInt nc, yaflFloat *res, yaflInt sr, yaflInt sc, yaflFloat *a); /* res[:sr, :sc] += a       */
+yaflStatusEn yafl_math_bsub_m(yaflInt nc, yaflFloat *res, yaflInt sr, yaflInt sc, yaflFloat *a); /* res[:sr, :sc] -= a       */
+
+#define YAFL_MATH_BSET_M(nc, r, c, m, sr, sc, a) yafl_math_bset_u(YAFL_BLK(m,nc,r,c), sr, sc, a) /* m[r:r+sz, c:c+sz]  = a   */
+#define YAFL_MATH_BADD_M(nc, r, c, m, sr, sc, a) yafl_math_badd_u(YAFL_BLK(m,nc,r,c), sr, sc, a) /* m[r:r+sz, c:c+sz] += a   */
+#define YAFL_MATH_BSUB_M(nc, r, c, m, sr, sc, a) yafl_math_bsub_u(YAFL_BLK(m,nc,r,c), sr, sc, a) /* m[r:r+sz, c:c+sz] -= a   */
+
 yaflStatusEn yafl_math_bset_u(yaflInt nc, yaflFloat *res, yaflInt sz, yaflFloat *u);      /* res[:sz, :sz]  = u       */
 yaflStatusEn yafl_math_badd_u(yaflInt nc, yaflFloat *res, yaflInt sz, yaflFloat *u);      /* res[:sz, :sz] += u       */
 yaflStatusEn yafl_math_bsub_u(yaflInt nc, yaflFloat *res, yaflInt sz, yaflFloat *u);      /* res[:sz, :sz] -= u       */

تفاوت فایلی نمایش داده نمی شود زیرا این فایل بسیار بزرگ است
+ 2064 - 207
src/yaflpy/yaflpy.pyx


+ 537 - 0
tests/src/filterpy/UDEKF.py

@@ -0,0 +1,537 @@
+# -*- coding: utf-8 -*-
+# pylint: disable=invalid-name,too-many-instance-attributes, too-many-arguments
+"""
+Copyright 2022 Paul A Beltyukov
+Copyright 2019 Paul A Beltyukov
+Copyright 2015 Roger R Labbe Jr.
+
+FilterPy library.
+http://github.com/rlabbe/filterpy
+
+Documentation at:
+https://filterpy.readthedocs.org
+
+Supporting book at:
+https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
+
+This is licensed under an MIT license. See the readme.MD file
+for more information.
+"""
+from copy import deepcopy
+from math import log, exp, sqrt
+import sys
+import numpy as np
+from numpy import dot, outer, eye, zeros, ones, diag
+import scipy.linalg as linalg
+from filterpy.stats import logpdf
+from filterpy.common import pretty_str, reshape_z
+'''
+UDU decomposition:
+P = U * diag(D) * U^T
+'''
+def udu(p):
+
+    if 2 != len(p.shape):
+        return None
+
+    if p.shape[0] != p.shape[1]:
+        return None
+
+    n = p.shape[0]
+
+    u = zeros((n, n))
+    d = zeros((n))
+
+    d[n-1] = p[n-1,n-1]
+    u[:,n-1]   = p[:,n-1] / d[n-1]
+
+    for j in range(n-2, -1, -1):
+        dd = d[j+1:]
+        c = dd * u[j,j+1:] #dd is meant to be diag(d[j+1:])
+        d[j] = p[j,j] - np.dot(u[j,j+1:].T, c)
+
+        if d[j] == 0:
+            return None
+
+        for i in range(j, -1, -1):
+            c = dd * u[j,j+1:]
+            u[i,j] = (p[i,j] - np.dot(u[i,j+1:].T, c))/d[j]
+
+    return u, d
+'''
+MWGS update:
+U * diag(D) * U^T = w * diag(d) * w^T
+
+Params:
+w - is n*k float full rank
+d - is k*None float
+where k>n
+return:
+u - is n*n float upper triangular
+D - id n*None float
+'''
+def mwgs(w,d):
+
+    if 1 != len(d.shape):
+        return None
+
+    if 2 != len(w.shape):
+        return None
+
+    if w.shape[1] != d.shape[0]:
+        return None
+
+    if w.shape[0] >= d.shape[0]:
+        return None
+
+    n = w.shape[0]
+
+    u = np.eye(n)
+    D = np.zeros((n))
+
+    for i in range(n-1, -1, -1):
+        c = w[i,:] * d
+        D[i] = np.dot(w[i,:], c)
+
+        if D[i] <= 1e-15:
+            # How about partial reset heuristics here?
+            D[i] = 1e-15
+            for j in range(0, i):
+                u[j,i] = 0
+            continue
+
+        dd = c/D[i]
+
+        for j in range(0, i):
+            u[j,i]  = np.dot(dd, w[j,:])
+            w[j,:] -= u[j,i] * w[i,:]
+
+    return u, D
+
+
+class UDExtendedKalmanFilter(object):
+
+    """ Implements an UD modification of extended Kalman filter (EKF).
+    You are responsible for setting the various state variables to
+    reasonable values; the defaults will  not give you a functional filter.
+
+    You will have to set the following attributes after constructing this
+    object for the filter to perform properly. Please note that there are
+    various checks in place to ensure that you have made everything the
+    'correct' size. However, it is possible to provide incorrectly sized
+    arrays such that the linear algebra can not perform an operation.
+    It can also fail silently - you can end up with matrices of a size that
+    allows the linear algebra to work, but are the wrong shape for the problem
+    you are trying to solve.
+
+    Parameters
+    ----------
+
+    dim_x : int
+        Number of state variables for the Kalman filter. For example, if
+        you are tracking the position and velocity of an object in two
+        dimensions, dim_x would be 4.
+
+        This is used to set the default size of P, Q, and u
+
+    dim_z : int
+        Number of of measurement inputs. For example, if the sensor
+        provides you with position in (x,y), dim_z would be 2.
+
+    Attributes
+    ----------
+    x : numpy.array(dim_x, 1)
+        State estimate vector
+
+    P : numpy.array(dim_x, dim_x)
+        Covariance matrix
+
+    x_prior : numpy.array(dim_x, 1)
+        Prior (predicted) state estimate. The *_prior and *_post attributes
+        are for convienence; they store the  prior and posterior of the
+        current epoch. Read Only.
+
+    P_prior : numpy.array(dim_x, dim_x)
+        Prior (predicted) state covariance matrix. Read Only.
+
+    x_post : numpy.array(dim_x, 1)
+        Posterior (updated) state estimate. Read Only.
+
+    P_post : numpy.array(dim_x, dim_x)
+        Posterior (updated) state covariance matrix. Read Only.
+
+    R : numpy.array(dim_z, dim_z)
+        Measurement noise matrix
+
+    Q : numpy.array(dim_x, dim_x)
+        Process noise matrix
+
+    F : numpy.array()
+        State Transition matrix
+
+    H : numpy.array(dim_x, dim_x)
+        Measurement function
+
+    y : numpy.array
+        Residual of the update step. Read only.
+
+    K : numpy.array(dim_x, dim_z)
+        Kalman gain of the update step. Read only.
+
+    S :  numpy.array
+        Systen uncertaintly projected to measurement space. Read only.
+
+    z : ndarray
+        Last measurement used in update(). Read only.
+
+    log_likelihood : float
+        log-likelihood of the last measurement. Read only.
+
+    likelihood : float
+        likelihood of last measurment. Read only.
+
+        Computed from the log-likelihood. The log-likelihood can be very
+        small,  meaning a large negative value such as -28000. Taking the
+        exp() of that results in 0.0, which can break typical algorithms
+        which multiply by this value, so by default we always return a
+        number >= sys.float_info.min.
+
+    mahalanobis : float
+        mahalanobis distance of the innovation. E.g. 3 means measurement
+        was 3 standard deviations away from the predicted value.
+
+        Read only.
+    """
+
+    def __init__(self, dim_x, dim_z, dim_u=0):
+
+        self.dim_x = dim_x
+        self.dim_z = dim_z
+        self.dim_u = dim_u
+
+        self.x = zeros((dim_x, 1)) # state
+        # uncertainty covariance
+        self.U = eye(dim_x)
+        self.D = ones((dim_x))
+        self.B = 0                 # control transition matrix
+        self.F = np.eye(dim_x)     # state transition matrix
+        # state uncertainty
+        self.Dm = eye(dim_z)       #Decorrelation matrix
+        self.Ur = eye(dim_z)       #Decorrelation matrix
+        self.Dr = ones((dim_z))
+        # process uncertainty
+        self.Uq = eye(dim_x)
+        self.Dq = ones((dim_x))
+
+        z = np.array([None]*self.dim_z)
+        self.z = reshape_z(z, self.dim_z, self.x.ndim)
+
+        # residual is computed during the innovation step. We
+        # save them so that in case you want to inspect it for various
+        # purposes
+        self.y = zeros((dim_z, 1)) # residual
+        self.S = np.zeros((dim_z, dim_z))   # system uncertainty
+        self.SI = np.zeros((dim_z, dim_z))  # inverse system uncertainty
+
+        self._log_likelihood = log(sys.float_info.min)
+        self._likelihood = sys.float_info.min
+        self._mahalanobis = None
+
+        # these will always be a copy of x,P after predict() is called
+        self.x_prior = self.x.copy()
+        self.U_prior = self.U.copy()
+        self.D_prior = self.D.copy()
+
+        # these will always be a copy of x,P after update() is called
+        self.x_post = self.x.copy()
+        self.U_post = self.U.copy()
+        self.D_post = self.D.copy()
+
+    @property
+    def Q(self):
+        """ Process uncertainty"""
+        return dot(self.Uq, dot(diag(self.Dq), self.Uq.T))
+
+    @Q.setter
+    def Q(self, value):
+        """ Process uncertainty"""
+        self.Uq, self.Dq = udu(value)
+
+    @property
+    def P(self):
+        """ covariance matrix"""
+        return dot(self.U, dot(diag(self.D), self.U.T))
+
+    @property
+    def P_prior(self):
+        """ covariance matrix of the prior"""
+        return dot(self.U_prior, dot(diag(self.D_prior), self.U_prior.T))
+
+    @property
+    def P_post(self):
+        """ covariance matrix of the posterior"""
+        return dot(self.U_post, dot(diag(self.D_post), self.U_post.T))
+
+    @P.setter
+    def P(self, value):
+        """ covariance matrix"""
+        self.U,self.D = udu(value);
+
+    @property
+    def R(self):
+        """ measurement uncertainty"""
+        return dot(self.Ur, dot(diag(self.Dr), self.Ur.T))
+
+    @R.setter
+    def R(self, value):
+        """ measurement uncertainty"""
+        self.Ur, self.Dr = udu(value)
+        self.Dm = linalg.inv(self.Ur)
+
+    def predict_x(self, u=0):
+        """
+        Predicts the next state of X. If you need to
+        compute the next state yourself, override this function. You would
+        need to do this, for example, if the usual Taylor expansion to
+        generate F is not providing accurate results for you.
+        """
+        self.x = dot(self.F, self.x) + dot(self.B, u)
+
+    def predict(self, u=0):
+        """
+        Predict next state (prior) using the Kalman filter state propagation
+        equations.
+
+        Parameters
+        ----------
+
+        u : np.array
+            Optional control vector. If non-zero, it is multiplied by B
+            to create the control input into the system.
+        """
+
+        self.predict_x(u)
+
+        W = np.concatenate((self.Uq, dot(self.F, self.U)), axis=1)
+        D = np.concatenate((self.Dq, self.D))
+        self.U, self.D = mwgs(W, D)
+
+        # save prior
+        self.x_prior = np.copy(self.x)
+        self.U_prior = np.copy(self.U)
+        self.D_prior = np.copy(self.D)
+
+    def _scalar_update(self, nu, h, r):
+        """Joseph scalar update
+
+        Parameters
+        ----------
+
+        axis_residual : function which returns current axis residual
+                        returns scalar, float.
+
+        axis_hjacobian : function which returns current axis HJacobian row
+                         returns np.array, float.
+
+        r : scalar, float, current axis state disp
+        """
+        u, d, n = self.U, self.D, self.dim_x
+
+        f = h.dot(u)
+        v = d * f
+
+        a = r + f.dot(v)
+        K = u.dot(v / a).reshape((n, 1))
+
+        WW = np.concatenate((outer(K, f) - u, K), axis = 1)
+        DD = np.concatenate((d, np.array([r])))
+
+        self.U, self.D = mwgs(WW, DD)
+        self.x += (K*nu).reshape(self.x.shape)
+
+    def update(self, z, HJacobian, Hx, R=None, args=(), hx_args=(),
+               residual=np.subtract):
+        """ Performs the update innovation of the extended Kalman filter.
+
+        Parameters
+        ----------
+
+        z : np.array
+            measurement for this step.
+            If `None`, posterior is not computed
+
+        HJacobian : function
+           function which computes the Jacobian of the H matrix (measurement
+           function). Takes state variable (self.x) as input, returns H.
+
+        Hx : function
+            function which takes as input the state variable (self.x) along
+            with the optional arguments in hx_args, and returns the measurement
+            that would correspond to that state.
+
+        R : np.array, scalar, or None
+            Optionally provide R to override the measurement noise for this
+            one call, otherwise  self.R will be used.
+
+        args : tuple, optional, default (,)
+            arguments to be passed into HJacobian after the required state
+            variable. for robot localization you might need to pass in
+            information about the map and time of day, so you might have
+            `args=(map_data, time)`, where the signature of HCacobian will
+            be `def HJacobian(x, map, t)`
+
+        hx_args : tuple, optional, default (,)
+            arguments to be passed into Hx function after the required state
+            variable.
+
+        residual : function (z, z2), optional
+            Optional function that computes the residual (difference) between
+            the two measurement vectors. If you do not provide this, then the
+            built in minus operator will be used. You will normally want to use
+            the built in unless your residual computation is nonlinear (for
+            example, if they are angles)
+        """
+        if z is None:
+            self.z = np.array([[None]*self.dim_z]).T
+            self.x_post = self.x.copy()
+            self.P_post = self.P.copy()
+            return
+
+        if not isinstance(args, tuple):
+            args = (args,)
+
+        if not isinstance(hx_args, tuple):
+            hx_args = (hx_args,)
+
+        if R is None:
+            Dm = self.Dm
+            Dr = self.Dr
+        elif np.isscalar(R):
+            Dm = eye(self.dim_z)       #Decorrelation matrix
+            Dr = ones((self.dim_z)) * R
+        else:
+            u,d = udu(R);
+            Dm = linalg.inv(u)
+            Dr = d
+
+        if np.isscalar(z) and self.dim_z == 1:
+            z = np.asarray([z], float)
+
+        #The ExtendedKalmanFilter class has self.y, self.S, and self.SI
+        #so we have to update them for [partial] compatibility.
+        #And yes, this is completely ineffective!!!
+        H = HJacobian(self.x, *args)
+        hx = Hx(self.x, *hx_args)
+        self.y = residual(z, hx)
+
+        self.S = dot(H, dot(self.P, H.T)) + self.R
+        self.SI = linalg.inv(self.S)
+
+        #Scalar updates
+        dy = dot(Dm, self.y)
+        dh = dot(Dm, H)
+        for j in range(self.dim_z):
+            self._scalar_update(dy[j], dh[j], Dr[j])
+
+        # set to None to force recompute
+        self._log_likelihood = None
+        self._likelihood = None
+        self._mahalanobis = None
+
+        # save measurement and posterior state
+        self.z = deepcopy(z)
+        self.x_post = self.x.copy()
+        self.U_post = self.U.copy()
+        self.D_post = self.D.copy()
+
+    def predict_update(self, z, HJacobian, Hx, args=(), hx_args=(), u=0):
+        """ Performs the predict/update innovation of the extended Kalman
+        filter.
+
+        Parameters
+        ----------
+
+        z : np.array
+            measurement for this step.
+            If `None`, only predict step is perfomed.
+
+        HJacobian : function
+           function which computes the Jacobian of the H matrix (measurement
+           function). Takes state variable (self.x) as input, along with the
+           optional arguments in args, and returns H.
+
+        Hx : function
+            function which takes as input the state variable (self.x) along
+            with the optional arguments in hx_args, and returns the measurement
+            that would correspond to that state.
+
+        args : tuple, optional, default (,)
+            arguments to be passed into HJacobian after the required state
+            variable.
+
+        hx_args : tuple, optional, default (,)
+            arguments to be passed into Hx after the required state
+            variable.
+
+        u : np.array or scalar
+            optional control vector input to the filter.
+        """
+        self.predict(u)
+        self.update(z, HJacobian, Hx, self.R, args, hx_args, residual=np.subtract)
+
+    @property
+    def log_likelihood(self):
+        """
+        log-likelihood of the last measurement.
+        """
+
+        if self._log_likelihood is None:
+            self._log_likelihood = logpdf(x=self.y, cov=self.S)
+        return self._log_likelihood
+
+    @property
+    def likelihood(self):
+        """
+        Computed from the log-likelihood. The log-likelihood can be very
+        small,  meaning a large negative value such as -28000. Taking the
+        exp() of that results in 0.0, which can break typical algorithms
+        which multiply by this value, so by default we always return a
+        number >= sys.float_info.min.
+        """
+        if self._likelihood is None:
+            self._likelihood = exp(self.log_likelihood)
+            if self._likelihood == 0:
+                self._likelihood = sys.float_info.min
+        return self._likelihood
+
+    @property
+    def mahalanobis(self):
+        """
+        Mahalanobis distance of innovation. E.g. 3 means measurement
+        was 3 standard deviations away from the predicted value.
+
+        Returns
+        -------
+        mahalanobis : float
+        """
+        if self._mahalanobis is None:
+            self._mahalanobis = sqrt(float(dot(dot(self.y.T, self.SI), self.y)))
+        return self._mahalanobis
+
+    def __repr__(self):
+        return '\n'.join([
+            'KalmanFilter object',
+            pretty_str('x', self.x),
+            pretty_str('P', self.P),
+            pretty_str('x_prior', self.x_prior),
+            pretty_str('P_prior', self.P_prior),
+            pretty_str('F', self.F),
+            pretty_str('Q', self.Q),
+            pretty_str('R', self.R),
+            pretty_str('K', self.K),
+            pretty_str('y', self.y),
+            pretty_str('S', self.S),
+            pretty_str('likelihood', self.likelihood),
+            pretty_str('log-likelihood', self.log_likelihood),
+            pretty_str('mahalanobis', self.mahalanobis)
+            ])

+ 161 - 0
tests/src/filterpy/UDEKHFPrior2.py

@@ -0,0 +1,161 @@
+# -*- coding: utf-8 -*-
+# pylint: disable=invalid-name,too-many-instance-attributes, too-many-arguments
+"""
+Copyright 2022 Paul A Beltyukov
+Copyright 2019 Paul A Beltyukov
+Copyright 2015 Roger R Labbe Jr.
+
+FilterPy library.
+http://github.com/rlabbe/filterpy
+
+Documentation at:
+https://filterpy.readthedocs.org
+
+Supporting book at:
+https://github.com/rlabbe/Kalman-and-Bayesian-Filters-in-Python
+
+This is licensed under an MIT license. See the readme.MD file
+for more information.
+"""
+import numpy as np
+from numpy import dot, outer
+from scipy.stats import chi2
+from UDEKF import mwgs, UDExtendedKalmanFilter
+
+
+class UDExtendedKalmanHinfFilterPrior2(UDExtendedKalmanFilter):
+
+    """
+    Implements an UD modification of extended Kalman/Hinfinity filter (EKHF)
+    with prior resuduals used for Hinfinity correction. You are responsible
+    for setting the various state variables to reasonable values;
+    the defaults will  not give you a functional filter.
+
+    You will have to set the following attributes after constructing this
+    object for the filter to perform properly. Please note that there are
+    various checks in place to ensure that you have made everything the
+    'correct' size. However, it is possible to provide incorrectly sized
+    arrays such that the linear algebra can not perform an operation.
+    It can also fail silently - you can end up with matrices of a size that
+    allows the linear algebra to work, but are the wrong shape for the problem
+    you are trying to solve.
+
+    Parameters
+    ----------
+
+    dim_x : int
+        Number of state variables for the Kalman filter. For example, if
+        you are tracking the position and velocity of an object in two
+        dimensions, dim_x would be 4.
+
+        This is used to set the default size of P, Q, and u
+
+    dim_z : int
+        Number of of measurement inputs. For example, if the sensor
+        provides you with position in (x,y), dim_z would be 2.
+
+    Attributes
+    ----------
+    x : numpy.array(dim_x, 1)
+        State estimate vector
+
+    P : numpy.array(dim_x, dim_x)
+        Covariance matrix
+
+    x_prior : numpy.array(dim_x, 1)
+        Prior (predicted) state estimate. The *_prior and *_post attributes
+        are for convienence; they store the  prior and posterior of the
+        current epoch. Read Only.
+
+    P_prior : numpy.array(dim_x, dim_x)
+        Prior (predicted) state covariance matrix. Read Only.
+
+    x_post : numpy.array(dim_x, 1)
+        Posterior (updated) state estimate. Read Only.
+
+    P_post : numpy.array(dim_x, dim_x)
+        Posterior (updated) state covariance matrix. Read Only.
+
+    R : numpy.array(dim_z, dim_z)
+        Measurement noise matrix
+
+    Q : numpy.array(dim_x, dim_x)
+        Process noise matrix
+
+    F : numpy.array()
+        State Transition matrix
+
+    H : numpy.array(dim_x, dim_x)
+        Measurement function
+
+    y : numpy.array
+        Residual of the update step. Read only.
+
+    K : numpy.array(dim_x, dim_z)
+        Kalman gain of the update step. Read only.
+
+    S :  numpy.array
+        Systen uncertaintly projected to measurement space. Read only.
+
+    z : ndarray
+        Last measurement used in update(). Read only.
+
+    log_likelihood : float
+        log-likelihood of the last measurement. Read only.
+
+    likelihood : float
+        likelihood of last measurment. Read only.
+
+        Computed from the log-likelihood. The log-likelihood can be very
+        small,  meaning a large negative value such as -28000. Taking the
+        exp() of that results in 0.0, which can break typical algorithms
+        which multiply by this value, so by default we always return a
+        number >= sys.float_info.min.
+
+    mahalanobis : float
+        mahalanobis distance of the innovation. E.g. 3 means measurement
+        was 3 standard deviations away from the predicted value.
+
+        Read only.
+    """
+
+    def __init__(self, dim_x, dim_z, dim_u=0, alpha = 0.001):
+        UDExtendedKalmanFilter.__init__(self, dim_x, dim_z, dim_u)
+        self.beta_1 = chi2.ppf(1.0 - alpha, 1)
+
+    def _scalar_update(self, nu, h, r):
+        """Joseph/Hinfinity scalar update using prior errors
+
+        Parameters
+        ----------
+
+        axis_residual : function which returns current axis residual
+                        returns scalar, float.
+
+        axis_hjacobian : function which returns current axis HJacobian row
+                         returns np.array, float.
+
+        r : scalar, float, current axis state disp
+        """
+        u, d, n = self.U, self.D, self.dim_x
+
+        f = h.dot(u)
+        v = d * f
+        c = f.dot(v)
+        s = c + r
+
+        a = (nu * nu) / self.beta_1 - s
+        if a > 0.0:
+            #Divergence detected, H-infinity correction needed
+            k = a / c + 1.0
+            d *= k
+            v *= k
+            s = k * c + r
+
+        K = u.dot(v / s).reshape((n, 1))
+
+        WW = np.concatenate((outer(K, f) - u, K), axis = 1)
+        DD = np.concatenate((d, np.array([r])))
+
+        self.U, self.D = mwgs(WW, DD)
+        self.x += (K*nu).reshape(self.x.shape)

+ 73 - 0
tests/src/filterpy/init_tests.py

@@ -0,0 +1,73 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import sys
+sys.path.append("../yafl")
+
+import numpy as np
+
+from filterpy.kalman import ExtendedKalmanFilter
+from filterpy.kalman import UnscentedKalmanFilter
+from filterpy.kalman import JulierSigmaPoints
+
+from ab_tests import *
+from case1    import *
+from case1    import _fx, _jfx, _hx, _jhx
+
+from yaflpy import _mwgs, _ruv, _rum, _set_u
+
+class SeqEKF(ExtendedKalmanFilter):
+
+    def shx(self, x):
+        return _ruv(self.Ur, _hx(x))[1]
+
+    def sjhx(self, x):
+        sjhx = _jhx(x)
+        _rum(sjhx, self.Ur)
+        return sjhx
+
+    def update(self, z):
+        # Decorrelate noice z
+        zd = _ruv(self.Ur, z)[1]
+        super().update(zd, self.sjhx, self.shx)
+        _, self.Up, self.Dp = _mwgs(np.linalg.cholesky(self.P), np.ones(self.dim_x))
+        _, self.Uq, self.Dq = _mwgs(np.linalg.cholesky(self.Q), np.ones(self.dim_x))
+
+def new_seq_ekf(std):
+    sz = 4
+
+    ekf = SeqEKF(sz, 2)
+    ekf.x = np.array([0, 0.3, 0, 0])
+    ekf.F = _jfx(ekf.x, 1.0)
+
+    up = _set_u(1e-8 * np.ones(((sz*(sz-1))//2,)))[1]
+    dp = 0.00001 * np.eye(sz)
+    ekf.P = up.dot(dp.dot(up.T))
+
+    uq = up.copy()
+    dq = 1e-6 * np.eye(sz)
+    ekf.Q = uq.dot(dq.dot(uq.T))
+
+    ekf.Ur = np.array([0.5])
+    ekf.Dr = std * std * np.array([0.75, 1.0])
+
+    #ur = _set_u(ekf.Ur)[1]
+    #dr = np.diag(ekf.Dr)
+
+    ekf.R = np.diag(ekf.Dr) #ur.dot(dr.dot(ur.T))
+
+    return ekf

+ 103 - 0
tests/src/filterpy/testFilterpy01.py

@@ -0,0 +1,103 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+import init_tests
+
+from ab_tests import *
+from case1    import *
+from case1    import _fx, _jfx, _hx, _jhx
+
+from UDEKF import UDExtendedKalmanFilter
+
+from yaflpy import Bierman as B
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+class A(UDExtendedKalmanFilter):
+    def update(self, z):
+        super().update(z, self.jhx, self.hx)
+        self.y = np.dot(self.Dm, self.y)
+
+a = A(4,2)
+a.x = np.array([0, 0.3, 0, 0])
+a.F = _jfx(a.x, 1.0)
+
+aup = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adp = 0.00001 * np.eye(4)
+a.P = aup.dot(adp.dot(aup.T))
+
+auq = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adq = 1e-6 * np.eye(4)
+a.Q = auq.dot(adq.dot(auq.T))
+
+
+aur = np.array([[1, 0.5],
+                [0, 1   ]])
+
+adr = STD * STD * np.eye(2)
+adr[0,0] *= 0.75
+a.R = aur.dot(adr.dot(aur.T))
+
+a.hx  = _hx
+a.jhx = _jhx
+
+#------------------------------------------------------------------------------
+b = case_ekf(B, STD)
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+xa,xb, nP,nQ,nR, nx,ny = filterpy_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nP)
+plt.show()
+
+plt.plot(nQ)
+plt.show()
+
+plt.plot(nR)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 116 - 0
tests/src/filterpy/testFilterpy02.py

@@ -0,0 +1,116 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+import init_tests
+
+from ab_tests import *
+from case1    import *
+from case1    import _fx, _jfx, _hx, _jhx
+
+from UDEKF import UDExtendedKalmanFilter
+
+from yaflpy import Bierman as B
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+class A(UDExtendedKalmanFilter):
+    def update(self, z):
+
+        if self.rff > 0:
+            self.R *= 1.0 - self.rff
+            self.R += self.rff * np.outer(self.y, self.y)
+            h = self.jhx(self.x)
+            self.R += self.rff * h.dot(self.P.dot(h.T))
+
+        super().update(z, self.jhx, self.hx)
+
+        if self.rff > 0:
+            self.y = z - self.hx(self.x)
+        else:
+            self.y = np.dot(self.Dm, self.y)
+
+a = A(4,2)
+a.x = np.array([0, 0.3, 0, 0])
+a.F = _jfx(a.x, 1.0)
+
+aup = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adp = 0.00001 * np.eye(4)
+a.P = aup.dot(adp.dot(aup.T))
+
+auq = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adq = 1e-6 * np.eye(4)
+a.Q = auq.dot(adq.dot(auq.T))
+
+
+aur = np.array([[1, 0.5],
+                [0, 1   ]])
+
+adr = STD * STD * np.eye(2)
+adr[0,0] *= 0.75
+a.R = aur.dot(adr.dot(aur.T))
+
+a.hx  = _hx
+a.jhx = _jhx
+
+a.rff = 0.001
+
+#------------------------------------------------------------------------------
+b = case_ekf(B, STD)
+b.rff = 0.001
+#------------------------------------------------------------------------------
+start = time.time()
+
+xa,xb, nP,nQ,nR, nx,ny = filterpy_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nP)
+plt.show()
+
+plt.plot(nQ)
+plt.show()
+
+plt.plot(nR)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 133 - 0
tests/src/filterpy/testFilterpy03.py

@@ -0,0 +1,133 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+import init_tests
+
+from ab_tests import *
+from case1    import *
+from case1    import _fx, _jfx, _hx, _jhx
+
+from UDEKF import UDExtendedKalmanFilter
+
+from yaflpy import Bierman as B
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+class A(UDExtendedKalmanFilter):
+
+    def _scalar_update(self, nu, h, r):
+
+        x_prior = self.x.copy()
+
+        super()._scalar_update(nu, h, r)
+
+        if self.qff > 0:
+            knu = self.x - x_prior
+            self.Q += self.qff * np.outer(knu, knu)
+
+
+    def update(self, z):
+
+        if self.rff > 0:
+            self.R *= 1.0 - self.rff
+            self.R += self.rff * np.outer(self.y, self.y)
+            h = self.jhx(self.x)
+            self.R += self.rff * h.dot(self.P.dot(h.T))
+
+        if self.qff > 0:
+            self.Q *= 1.0 - self.qff
+
+        super().update(z, self.jhx, self.hx)
+
+        if self.rff > 0:
+            self.y = z - self.hx(self.x)
+        else:
+            self.y = np.dot(self.Dm, self.y)
+
+a = A(4,2)
+a.x = np.array([0, 0.3, 0, 0])
+a.F = _jfx(a.x, 1.0)
+
+aup = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adp = 0.00001 * np.eye(4)
+a.P = aup.dot(adp.dot(aup.T))
+
+auq = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adq = 1e-6 * np.eye(4)
+a.Q = auq.dot(adq.dot(auq.T))
+
+
+aur = np.array([[1, 0.5],
+                [0, 1   ]])
+
+adr = STD * STD * np.eye(2)
+adr[0,0] *= 0.75
+a.R = aur.dot(adr.dot(aur.T))
+
+a.hx  = _hx
+a.jhx = _jhx
+
+a.rff = 0.001
+a.qff = 0.0001
+
+#------------------------------------------------------------------------------
+b = case_ekf(B, STD)
+b.rff = 0.001
+b.qff = 0.0001
+#------------------------------------------------------------------------------
+start = time.time()
+
+xa,xb, nP,nQ,nR, nx,ny = filterpy_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nP)
+plt.show()
+
+plt.plot(nQ)
+plt.show()
+
+plt.plot(nR)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 106 - 0
tests/src/filterpy/testFilterpy04.py

@@ -0,0 +1,106 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+import init_tests
+
+from ab_tests import *
+from case1    import *
+from case1    import _fx, _jfx, _hx, _jhx
+
+from UDEKHFPrior2 import UDExtendedKalmanHinfFilterPrior2
+
+from yaflpy import AdaptiveBierman as B
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+class A(UDExtendedKalmanHinfFilterPrior2):
+    def update(self, z):
+        super().update(z, self.jhx, self.hx)
+        self.y = np.dot(self.Dm, self.y)
+
+a = A(4,2)
+a.x = np.array([0, 0.3, 0, 0])
+a.F = _jfx(a.x, 1.0)
+
+aup = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adp = 0.00001 * np.eye(4)
+a.P = aup.dot(adp.dot(aup.T))
+
+auq = np.array([[1, 1e-8, 1e-8, 1e-8],
+                [0, 1,    1e-8, 1e-8],
+                [0, 0,    1,    1e-8],
+                [0, 0,    0,    1]])
+adq = 1e-6 * np.eye(4)
+a.Q = auq.dot(adq.dot(auq.T))
+
+
+aur = np.array([[1, 0.5],
+                [0, 1   ]])
+
+adr = STD * STD * np.eye(2)
+adr[0,0] *= 0.75
+a.R = aur.dot(adr.dot(aur.T))
+
+a.hx  = _hx
+a.jhx = _jhx
+
+a.beta_1 = 10.827566170662733
+
+#------------------------------------------------------------------------------
+b = case_ekf(B, STD)
+b.chi2 = 10.827566170662733
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+xa,xb, nP,nQ,nR, nx,ny = filterpy_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nP)
+plt.show()
+
+plt.plot(nQ)
+plt.show()
+
+plt.plot(nR)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 48 - 0
tests/src/np/testNp001.py

@@ -0,0 +1,48 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    v = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    n = np.random.uniform(low=-1.0, high=1.0)
+
+    a = v*n
+    s,b = yaflpy._set_vxn(v, n)
+
+    aa.append(np.linalg.norm(a))
+    ss.append(s)
+    dd.append(np.linalg.norm(a - b))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp002.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    n = np.random.uniform(low=-1.0, high=1.0)
+
+    p = a + b*n
+    s,r = yaflpy._add_vxn(a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp003.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    n = np.random.uniform(low=-1.0, high=1.0)
+
+    p = a - b*n
+    s,r = yaflpy._sub_vxn(a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 52 - 0
tests/src/np/testNp004.py

@@ -0,0 +1,52 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    v = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.linalg.norm(n) > 1e-15:
+            break;
+
+    a = v/n
+    s,b = yaflpy._set_vrn(v, n)
+
+    aa.append(np.linalg.norm(a))
+    ss.append(s)
+    dd.append(np.linalg.norm(a - b))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 53 - 0
tests/src/np/testNp005.py

@@ -0,0 +1,53 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.linalg.norm(n) > 1e-15:
+            break;
+
+    p = a + b/n
+    s,r = yaflpy._add_vrn(a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 53 - 0
tests/src/np/testNp006.py

@@ -0,0 +1,53 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.linalg.norm(n) > 1e-15:
+            break;
+
+    p = a - b/n
+    s,r = yaflpy._sub_vrn(a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 48 - 0
tests/src/np/testNp007.py

@@ -0,0 +1,48 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = a*b
+    s,r = yaflpy._set_vxv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp008.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    r = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = r + a*b
+    s = yaflpy._add_vxv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp009.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    r = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = r - a*b
+    s = yaflpy._sub_vxv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 48 - 0
tests/src/np/testNp010.py

@@ -0,0 +1,48 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = a/b
+    s,r = yaflpy._set_vrv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp011.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    r = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = r + a/b
+    s = yaflpy._add_vrv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp012.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    r = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = r - a/b
+    s = yaflpy._sub_vrv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 48 - 0
tests/src/np/testNp013.py

@@ -0,0 +1,48 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    a = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(i,))
+
+    p = a.dot(b)
+    s,r = yaflpy._vtv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp014.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = np.outer(a,b)
+    s,r = yaflpy._set_vvt(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp015.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = r + np.outer(a,b)
+    s = yaflpy._add_vvt(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp016.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = r - np.outer(a,b)
+    s = yaflpy._sub_vvt(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 56 - 0
tests/src/np/testNp017.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.abs(n) > 1e-15:
+            break;
+
+    p = np.outer(a,b) * n
+    s,r = yaflpy._set_vvtxn(a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 56 - 0
tests/src/np/testNp018.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.abs(n) > 1e-15:
+            break;
+
+    p = r + np.outer(a,b) * n
+    s = yaflpy._add_vvtxn(r, a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 56 - 0
tests/src/np/testNp019.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    while True:
+        n = np.random.uniform(low=-1.0, high=1.0)
+        if np.abs(n) > 1e-15:
+            break;
+
+    p = r - np.outer(a,b) * n
+    s = yaflpy._sub_vvtxn(r, a, b, n)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp020.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = a.dot(b)
+    s,r = yaflpy._set_mv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp021.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = r + a.dot(b)
+    s = yaflpy._add_mv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp022.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+
+    p = r - a.dot(b)
+    s = yaflpy._sub_mv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp023.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = a.reshape((nr,1)).T.dot(b)
+    s,r = yaflpy._set_vtm(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp024.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = r + a.reshape((nr,1)).T.dot(b)
+    s = yaflpy._add_vtm(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 51 - 0
tests/src/np/testNp025.py

@@ -0,0 +1,51 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=1, high=i+1))
+    nc = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = r - a.reshape((nr,1)).T.dot(b)
+    s = yaflpy._sub_vtm(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 52 - 0
tests/src/np/testNp026.py

@@ -0,0 +1,52 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr  = int(np.random.uniform(low=1, high=i+1))
+    ncr = int(np.random.uniform(low=1, high=i+1))
+    nc  = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,ncr))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(ncr,nc))
+
+    p = a.dot(b)
+    s,r = yaflpy._set_mm(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 52 - 0
tests/src/np/testNp027.py

@@ -0,0 +1,52 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr  = int(np.random.uniform(low=1, high=i+1))
+    ncr = int(np.random.uniform(low=1, high=i+1))
+    nc  = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,ncr))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(ncr,nc))
+
+    p = r + a.dot(b)
+    s = yaflpy._add_mm(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 52 - 0
tests/src/np/testNp028.py

@@ -0,0 +1,52 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr  = int(np.random.uniform(low=1, high=i+1))
+    ncr = int(np.random.uniform(low=1, high=i+1))
+    nc  = int(np.random.uniform(low=1, high=i+1))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,ncr))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(ncr,nc))
+
+    p = r - a.dot(b)
+    s = yaflpy._sub_mm(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp029.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    u = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r + yaflpy._set_u(u)[1]
+    s = yaflpy._add_u(r, u)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp030.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    u = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r - yaflpy._set_u(u)[1]
+    s = yaflpy._sub_u(r, u)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp031.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = a.reshape((sz,1)).T.dot(yaflpy._set_u(b)[1])
+    s,r = yaflpy._set_vtu(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp032.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r + a.reshape((sz,1)).T.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._add_vtu(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp033.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r - a.reshape((sz,1)).T.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._sub_vtu(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp034.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = yaflpy._set_u(a)[1].dot(b)
+    s,r = yaflpy._set_uv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp035.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = r + yaflpy._set_u(a)[1].dot(b)
+    s = yaflpy._add_uv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp036.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = r - yaflpy._set_u(a)[1].dot(b)
+    s = yaflpy._sub_uv(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp037.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = a.dot(yaflpy._set_u(b)[1])
+    s,r = yaflpy._set_mu(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp038.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r + a.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._add_mu(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 50 - 0
tests/src/np/testNp039.py

@@ -0,0 +1,50 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = r - a.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._sub_mu(r, a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 57 - 0
tests/src/np/testNp040.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nr  = int(np.random.uniform(low=2, high=rnr))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc]  = a
+    s = yaflpy._bset_m(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp041.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nr  = int(np.random.uniform(low=2, high=rnr))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] += a
+    s = yaflpy._badd_m(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp042.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nr  = int(np.random.uniform(low=2, high=rnr))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] -= a
+    s = yaflpy._bsub_m(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp043.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] = yaflpy._set_u(a)[1]
+    s = yaflpy._bset_u(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp044.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] += yaflpy._set_u(a)[1]
+    s = yaflpy._badd_u(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp045.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] -= yaflpy._set_u(a)[1]
+    s = yaflpy._bsub_u(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp046.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] = yaflpy._set_u(a)[1].T
+    s = yaflpy._bset_ut(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp047.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    #res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    res = np.zeros((rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] += yaflpy._set_u(a)[1].T
+    s = yaflpy._badd_ut(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp048.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnc, rnr)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] -= yaflpy._set_u(a)[1]
+    s = yaflpy._bsub_u(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp049.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=rnr))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c] = a
+    s = yaflpy._bset_v(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp050.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=rnr))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c] += a
+    s = yaflpy._badd_v(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 56 - 0
tests/src/np/testNp051.py

@@ -0,0 +1,56 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=rnr))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c] -= a
+    s = yaflpy._bsub_v(res, a, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp052.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] = np.outer(a,b)
+    s = yaflpy._bset_vvt(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp053.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] += np.outer(a,b)
+    s = yaflpy._badd_vvt(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 57 - 0
tests/src/np/testNp054.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    sz  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-sz-1))
+    c  = int(np.random.uniform(low=0, high=rnc-sz-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = res.copy()
+    p[r:r+sz, c:c+sz] -= np.outer(a,b)
+    s = yaflpy._bsub_vvt(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 58 - 0
tests/src/np/testNp055.py

@@ -0,0 +1,58 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] = a.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._bset_mu(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 58 - 0
tests/src/np/testNp056.py

@@ -0,0 +1,58 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] += a.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._badd_mu(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 58 - 0
tests/src/np/testNp057.py

@@ -0,0 +1,58 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] -= a.dot(yaflpy._set_u(b)[1])
+    s = yaflpy._bsub_mu(res, a, b, r, c)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 62 - 0
tests/src/np/testNp058.py

@@ -0,0 +1,62 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+    anr = int(np.random.uniform(low=nr, high=i+nr))
+    anc = int(np.random.uniform(low=nc, high=i+nc))
+    ar  = int(np.random.uniform(low=0, high=anr-nr-1))
+    ac  = int(np.random.uniform(low=0, high=anc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(anr,anc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] = a[ar:ar+nr, ac:ac+nc].dot(yaflpy._set_u(b)[1])
+    s = yaflpy._bset_bu(res, a, b, r, c, ar, ac, nr, nc)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 62 - 0
tests/src/np/testNp059.py

@@ -0,0 +1,62 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+    anr = int(np.random.uniform(low=nr, high=i+nr))
+    anc = int(np.random.uniform(low=nc, high=i+nc))
+    ar  = int(np.random.uniform(low=0, high=anr-nr-1))
+    ac  = int(np.random.uniform(low=0, high=anc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(anr,anc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] += a[ar:ar+nr, ac:ac+nc].dot(yaflpy._set_u(b)[1])
+    s = yaflpy._badd_bu(res, a, b, r, c, ar, ac, nr, nc)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 62 - 0
tests/src/np/testNp060.py

@@ -0,0 +1,62 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    rnr = int(np.random.uniform(low=2, high=i+2))
+    rnc = int(np.random.uniform(low=2, high=i+2))
+    nc  = int(np.random.uniform(low=2, high=rnc))
+    nr  = int(np.random.uniform(low=2, high=min(rnr, rnc)))
+    r  = int(np.random.uniform(low=0, high=rnr-nr-1))
+    c  = int(np.random.uniform(low=0, high=rnc-nc-1))
+    anr = int(np.random.uniform(low=nr, high=i+nr))
+    anc = int(np.random.uniform(low=nc, high=i+nc))
+    ar  = int(np.random.uniform(low=0, high=anr-nr-1))
+    ac  = int(np.random.uniform(low=0, high=anc-nc-1))
+
+    res = np.random.uniform(low=1e-15, high=1.0, size=(rnr,rnc))
+    a = np.random.uniform(low=1e-15, high=1.0, size=(anr,anc))
+    b = np.random.uniform(low=1e-15, high=1.0, size=((nc*(nc-1))//2,))
+
+    p = res.copy()
+    p[r:r+nr, c:c+nc] -= a[ar:ar+nr, ac:ac+nc].dot(yaflpy._set_u(b)[1])
+    s = yaflpy._bsub_bu(res, a, b, r, c, ar, ac, nr, nc)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - res)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))
+

+ 49 - 0
tests/src/np/testNp061.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = np.linalg.inv(yaflpy._set_u(a)[1]).dot(b)
+    s,r = yaflpy._ruv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp062.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    a = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    b = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    p = np.linalg.inv(yaflpy._set_u(a)[1].T).dot(b)
+    s,r = yaflpy._rutv(a, b)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 49 - 0
tests/src/np/testNp063.py

@@ -0,0 +1,49 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+    u = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    r = np.random.uniform(low=1e-15, high=1.0, size=(sz,sz))
+
+    p = np.linalg.inv(yaflpy._set_u(u)[1]).dot(r)
+    s = yaflpy._rum(r, u)
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 54 - 0
tests/src/np/testNp064.py

@@ -0,0 +1,54 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    nr = int(np.random.uniform(low=2, high=i+2))
+    nc = int(np.random.uniform(low=2, high=i+2))
+
+    d = np.random.uniform(low=1e-15, high=1.0, size=(nc,))
+    w = np.random.uniform(low=1e-15, high=1.0, size=(nr,nc))
+
+    p = w.dot(np.diag(d).dot(w.T))
+    s,_u,_d = yaflpy._mwgs(w, d)
+
+    _u = yaflpy._set_u(_u)[1]
+    r = _u.dot(np.diag(_d).dot(_u.T))
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 57 - 0
tests/src/np/testNp065.py

@@ -0,0 +1,57 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+
+    u = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    d = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    v = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    alpha = np.random.uniform(low=1e-15, high=1.0)
+
+    _u = yaflpy._set_u(u)[1]
+    p = _u.dot(np.diag(d).dot(_u.T)) + alpha*np.outer(v,v)
+
+    s = yaflpy._udu_up(u, d, alpha, v)
+    _u = yaflpy._set_u(u)[1]
+    r = _u.dot(np.diag(d).dot(_u.T))
+
+    aa.append(np.linalg.norm(p))
+    ss.append(s)
+    dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 62 - 0
tests/src/np/testNp066.py

@@ -0,0 +1,62 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+
+import numpy as np
+
+import yaflpy
+
+N = 1000
+
+aa = []
+dd = []
+ss = []
+
+for i in range(1,N):
+    sz  = int(np.random.uniform(low=2, high=i+2))
+
+    u = np.random.uniform(low=1e-15, high=1.0, size=((sz*(sz-1))//2,))
+    d = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+
+    v = np.random.uniform(low=1e-15, high=1.0, size=(sz,))
+    alpha = np.random.uniform(low=1e-15, high=1.0)
+
+    _u = yaflpy._set_u(u)[1]
+    p = _u.dot(np.diag(d).dot(_u.T))
+
+    s = yaflpy._udu_up(u, d, alpha, v.copy())
+
+    s = yaflpy._udu_down(u, d, alpha, v)
+
+    _u = yaflpy._set_u(u)[1]
+    r = _u.dot(np.diag(d).dot(_u.T))
+
+    #s = 0
+    if 0 == s:
+        aa.append(np.linalg.norm(p))
+        ss.append(s)
+        dd.append(np.linalg.norm(p - r)/np.linalg.norm(p))
+
+print(np.min(aa))
+print(np.max(aa))
+print(np.average(aa))
+print(np.median(aa))
+
+print(np.min(dd))
+print(np.max(dd))
+print(np.average(dd))
+print(np.median(dd))

+ 47 - 22
tests/src/ab_tests.py → tests/src/yafl/ab_tests.py

@@ -18,7 +18,7 @@
 import h5py
 import numpy as np
 from numpy.linalg import norm
-import yaflpy
+
 #------------------------------------------------------------------------------
 def yafl_ab_test(a, b, measurements):
 
@@ -85,16 +85,6 @@ def yafl_ab_test(a, b, measurements):
     return rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny
 
 #------------------------------------------------------------------------------
-ROBUST_EKF = [yaflpy.RobustBierman,
-              yaflpy.RobustJoseph,
-              yaflpy.AdaptiveRobustBierman,
-              yaflpy.AdaptiveRobustJoseph]
-
-ROBUST_UKF = [yaflpy.UnscentedRobustBierman,
-              yaflpy.UnscentedAdaptiveRobustBierman]
-
-ROBUST = ROBUST_EKF + ROBUST_UKF
-
 def yafl_record_test_data(a, clear, noisy, t, fname):
     rp = []
     ru = []
@@ -120,11 +110,7 @@ def yafl_record_test_data(a, clear, noisy, t, fname):
         dq.append(a.Dq.copy())
 
         ur.append(a.Ur.copy())
-
-        if type(a) in ROBUST:
-            dr.append(a.Dr * a.Dr)
-        else:
-            dr.append(a.Dr.copy())
+        dr.append(a.Dr.copy())
 
     rp = np.array(rp)
     ru = np.array(ru)
@@ -229,11 +215,7 @@ def yafl_file_test(b, fname):
         ndq.append(2. * norm(adq[i] - b.Dq) / norm(adq[i] + b.Dq))
 
         nur.append(2. * norm(aur[i] - b.Ur) / norm(aur[i] + b.Ur))
-
-        if type(b) in ROBUST:
-            ndr.append(2. * norm(np.sqrt(adr[i]) - b.Dr) / norm(np.sqrt(adr[i]) + b.Dr))
-        else:
-            ndr.append(2. * norm(adr[i] - b.Dr) / norm(adr[i] + b.Dr))
+        ndr.append(2. * norm(adr[i] - b.Dr) / norm(adr[i] + b.Dr))
 
     rpb = np.array(rpb)
     rub = np.array(rub)
@@ -251,4 +233,47 @@ def yafl_file_test(b, fname):
     nx = np.array(nx)
     ny = np.array(ny)
 
-    return clear,noisy,t, rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny
+    return clear,noisy,t, rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny
+
+#------------------------------------------------------------------------------
+def filterpy_ab_test(a, b, measurements):
+
+    xa  = []
+    xb  = []
+
+    nP = []
+    nQ = []
+    nR = []
+
+    nx  = []
+    ny  = []
+
+    for z in measurements:
+        # Run A
+        a.predict()
+        a.update(z)
+        xa.append(a.x.copy())
+
+        # Run B
+        b.predict()
+        b.update(z)
+        xb.append(b.x.copy())
+
+        nx.append(2. * norm(a.x - b.x) / norm(a.x + b.x))
+        ny.append(2. * norm(a.y - b.y) / norm(a.y + b.y))
+
+        nP.append(2. * norm(a.P - b.P) / norm(a.P + b.P))
+        nQ.append(2. * norm(a.Q - b.Q) / norm(a.Q + b.Q))
+        nR.append(2. * norm(a.R - b.R) / norm(a.R + b.R))
+
+    xa  = np.array(xa)
+    xb  = np.array(xb)
+
+    nP = np.array(nP)
+    nQ = np.array(nQ)
+    nR = np.array(nR)
+
+    nx = np.array(nx)
+    ny = np.array(ny)
+
+    return xa,xb, nP,nQ,nR, nx,ny

+ 11 - 18
tests/src/case1.py → tests/src/yafl/case1.py

@@ -81,23 +81,13 @@ def case_data(n, std):
     t     = np.zeros((n,), dtype=np.float)
 
     for i in range(1, len(clear)):
-        clear[i] = clear[i-1] + np.array([1.,1.])
+        clear[i] = clear[i-1] + np.array([2.,1.])
         noisy[i] = clear[i]   + np.random.normal(scale=std, size=2)
         t[i] = i
 
     return clear, noisy, t
 
 #------------------------------------------------------------------------------
-ROBUST_EKF = [yaflpy.RobustBierman,
-              yaflpy.RobustJoseph,
-              yaflpy.AdaptiveRobustBierman,
-              yaflpy.AdaptiveRobustJoseph]
-
-ROBUST_UKF = [yaflpy.UnscentedRobustBierman,
-              yaflpy.UnscentedAdaptiveRobustBierman]
-
-ROBUST = ROBUST_EKF + ROBUST_UKF
-
 def _kf_init(kf, std):
 
     kf.x[0] = 0.
@@ -109,16 +99,16 @@ def _kf_init(kf, std):
     kf.Uq = 1e-8
     kf.Dq *= 1.0e-6
 
-    if type(kf) in ROBUST:
-        kf.Dr *= std
-        kf.Dr[0] *= np.sqrt(0.75)
-    else:
-        kf.Dr *= std * std
-        kf.Dr[0] *= 0.75
-
+    kf.Dr *= std * std
+    kf.Dr[0] *= .75
     kf.Ur += 0.5
 
 #------------------------------------------------------------------------------
+ROBUST_EKF = [yaflpy.RobustBierman,
+              yaflpy.RobustJoseph,
+              yaflpy.AdaptiveRobustBierman,
+              yaflpy.AdaptiveRobustJoseph]
+
 def case_ekf(clsEKF, std):
     if clsEKF in ROBUST_EKF:
         kf = clsEKF(4, 2, 1., _fx, _jfx, _hx, _jhx, gz=_gz, gdotz=_gdotz)
@@ -128,6 +118,9 @@ def case_ekf(clsEKF, std):
     return kf
 
 #------------------------------------------------------------------------------
+ROBUST_UKF = [yaflpy.UnscentedRobustBierman,
+              yaflpy.UnscentedAdaptiveRobustBierman]
+
 def case_ukf(clsUKF, std, sp=None):
 
     if not sp:

+ 14 - 14
tests/src/create_test_data.py → tests/src/yafl/create_test_data.py

@@ -46,56 +46,56 @@ clear, noisy, t = case_data(N, STD)
 
 #------------------------------------------------------------------------------
 a = case_ekf(Joseph, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/j_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/j_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(Bierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/b_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/b_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(AdaptiveJoseph, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/aj_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/aj_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(AdaptiveBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/ab_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/ab_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(RobustJoseph, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/rj_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/rj_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(RobustBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/rb_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/rb_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(AdaptiveRobustJoseph, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/arj_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/arj_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ekf(AdaptiveRobustBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/arb_ekf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/arb_ekf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(Unscented, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/ukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/ukf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(UnscentedAdaptive, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/aukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/aukf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(UnscentedBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/b_ukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/b_ukf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(UnscentedAdaptiveBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/ab_ukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/ab_ukf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(UnscentedRobustBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/rb_ukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/rb_ukf_case1_64bit.h5')
 
 #------------------------------------------------------------------------------
 a = case_ukf(UnscentedAdaptiveRobustBierman, STD)
-yafl_record_test_data(a, clear, noisy, t, '../data/arb_ukf_case1_64bit.h5')
+yafl_record_test_data(a, clear, noisy, t, '../../data/arb_ukf_case1_64bit.h5')

+ 0 - 0
tests/src/test1.py → tests/src/yafl/test001.py


+ 71 - 0
tests/src/yafl/test002.py

@@ -0,0 +1,71 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import RobustJoseph  as A
+from yaflpy import RobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ekf(B, STD)
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 71 - 0
tests/src/yafl/test003.py

@@ -0,0 +1,71 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveJoseph  as A
+from yaflpy import AdaptiveBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ekf(B, STD)
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 71 - 0
tests/src/yafl/test004.py

@@ -0,0 +1,71 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveRobustJoseph  as A
+from yaflpy import AdaptiveRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ekf(B, STD)
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 0 - 0
tests/src/test3.py → tests/src/yafl/test005.py


+ 72 - 0
tests/src/yafl/test006.py

@@ -0,0 +1,72 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import RobustJoseph           as A
+from yaflpy import UnscentedRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ukf(B, STD)
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 73 - 0
tests/src/yafl/test007.py

@@ -0,0 +1,73 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveJoseph           as A
+from yaflpy import UnscentedAdaptiveBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ukf(B, STD)
+b.chi2 = a.chi2
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 73 - 0
tests/src/yafl/test008.py

@@ -0,0 +1,73 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveRobustJoseph           as A
+from yaflpy import UnscentedAdaptiveRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+b = case_ukf(B, STD)
+b.chi2 = a.chi2
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 0 - 0
tests/src/test2.py → tests/src/yafl/test009.py


+ 86 - 0
tests/src/yafl/test010.py

@@ -0,0 +1,86 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+import scipy
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveJoseph    as A
+from yaflpy import UnscentedAdaptive as B
+
+
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+ALPHA=0.001
+
+a = case_ekf(A, STD)
+a.chi2 = scipy.stats.chi2.ppf(1.0 - ALPHA, 1)
+
+b = case_ukf(B, STD)
+b.chi2 = scipy.stats.chi2.ppf(1.0 - ALPHA, 2)
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xb[:,0], xb[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xb[:,0], xb[:,2])
+plt.show()

+ 0 - 0
tests/src/test4.py → tests/src/yafl/test011.py


+ 74 - 0
tests/src/yafl/test012.py

@@ -0,0 +1,74 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import Joseph  as A
+from yaflpy import Bierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.0001
+
+b = case_ekf(B, STD)
+b.rff = 0.0001
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 73 - 0
tests/src/yafl/test013.py

@@ -0,0 +1,73 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import RobustJoseph  as A
+from yaflpy import RobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.0001
+
+b = case_ekf(B, STD)
+b.rff = 0.0001
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 74 - 0
tests/src/yafl/test014.py

@@ -0,0 +1,74 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveJoseph  as A
+from yaflpy import AdaptiveBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.0001
+
+b = case_ekf(B, STD)
+b.rff = 0.0001
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 74 - 0
tests/src/yafl/test015.py

@@ -0,0 +1,74 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveRobustJoseph  as A
+from yaflpy import AdaptiveRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clean, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.0001
+
+b = case_ekf(B, STD)
+b.rff = 0.0001
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+plt.plot(clean[:,0], clean[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 75 - 0
tests/src/yafl/test016.py

@@ -0,0 +1,75 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import Joseph           as A
+from yaflpy import UnscentedBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.001
+
+b = case_ukf(B, STD)
+b.rff = 0.001
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 76 - 0
tests/src/yafl/test017.py

@@ -0,0 +1,76 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import RobustJoseph           as A
+from yaflpy import UnscentedRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.001
+
+b = case_ukf(B, STD)
+b.rff = 0.001
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

+ 83 - 0
tests/src/yafl/test018.py

@@ -0,0 +1,83 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveJoseph           as A
+from yaflpy import UnscentedAdaptiveBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.001
+
+b = case_ukf(B, STD)
+b.rff = 0.001
+
+b.chi2 = a.chi2
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xb[:,0], xb[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xb[:,0], xb[:,2])
+plt.show()

+ 78 - 0
tests/src/yafl/test019.py

@@ -0,0 +1,78 @@
+#!/usr/bin/env python3
+# -*- coding: utf-8 -*-
+"""
+    Copyright 2022 anonimous <shkolnick-kun@gmail.com> and contributors.
+
+    Licensed under the Apache License, Version 2.0 (the "License");
+    you may not use this file except in compliance with the License.
+    You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+    Unless required by applicable law or agreed to in writing,
+    software distributed under the License is distributed on an "AS IS" BASIS,
+    WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+
+    See the License for the specific language governing permissions
+"""
+import time
+import matplotlib.pyplot as plt
+import numpy as np
+
+from ab_tests import *
+from case1    import *
+
+from yaflpy import AdaptiveRobustJoseph           as A
+from yaflpy import UnscentedAdaptiveRobustBierman as B
+
+#------------------------------------------------------------------------------
+N = 10000
+STD = 100.
+
+#------------------------------------------------------------------------------
+clear, noisy, t = case_data(N, STD)
+
+#------------------------------------------------------------------------------
+a = case_ekf(A, STD)
+a.rff = 0.001
+
+b = case_ukf(B, STD)
+b.rff = 0.001
+
+b.chi2 = a.chi2
+
+#------------------------------------------------------------------------------
+start = time.time()
+
+rpa,rua,xa, rpb,rub,xb, nup,ndp, nuq,ndq, nur,ndr, nx, ny = yafl_ab_test(a, b, noisy)
+
+end = time.time()
+print(end - start)
+
+#------------------------------------------------------------------------------
+plt.plot(nup)
+plt.show()
+plt.plot(ndp)
+plt.show()
+
+plt.plot(nuq)
+plt.show()
+plt.plot(ndq)
+plt.show()
+
+plt.plot(nur)
+plt.show()
+plt.plot(ndr)
+plt.show()
+
+plt.plot(nx)
+plt.show()
+
+plt.plot(ny)
+plt.show()
+
+plt.plot(noisy[:,0], noisy[:,1], xa[:,0], xa[:,2])
+plt.show()
+
+plt.plot(clear[:,0], clear[:,1], xa[:,0], xa[:,2])
+plt.show()

برخی فایل ها در این مقایسه diff نمایش داده نمی شوند زیرا تعداد فایل ها بسیار زیاد است