From 7e5d2ddeb29c7defb895e83e5df4d9d85ae5a022 Mon Sep 17 00:00:00 2001 From: Jonathan Van Schenck Date: Thu, 27 Apr 2023 09:21:56 -0700 Subject: [PATCH 1/3] Add printing --- .../dead_reckon/dead_reckon_pure.py | 56 ++++- test2.py | 60 +++++ test3.py | 228 ++++++++++++++++++ test4.py | 18 ++ test5.py | 199 +++++++++++++++ 5 files changed, 552 insertions(+), 9 deletions(-) create mode 100644 test2.py create mode 100644 test3.py create mode 100644 test4.py create mode 100644 test5.py diff --git a/robotransforms/dead_reckon/dead_reckon_pure.py b/robotransforms/dead_reckon/dead_reckon_pure.py index 63d1351..f81c8bc 100644 --- a/robotransforms/dead_reckon/dead_reckon_pure.py +++ b/robotransforms/dead_reckon/dead_reckon_pure.py @@ -100,6 +100,8 @@ def dead_reckon_apply(x_hat, P_hat, step): # print(v) # print(w.T) raise e + + for i in range(L): # The first SS are gotten via composition dlrQ = t.lrq2lrQ(dz[i][:SM]) @@ -109,32 +111,68 @@ def dead_reckon_apply(x_hat, P_hat, step): # The last 2 are gotten via addition Z[1 + i][SS:] = z[SS:] + dz[i][SM:] Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) + print() # Transform to new vectors def T(_z): quat = _z[3:SS] - dx = dead_reckon_step( quat=_z[3:SS], dl=z[SS+0], dr=z[SS+1], vave=step[7], vdiff=step[8] ) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1], vave=step[7], vdiff=step[8] ) + nquat = t.compose_quat(quat,step[3:7]) # Only return offset, this is marginalizing out all the quat dependances - return _z[:3] + dx + # return _z[:3] + dx + return np.hstack([_z[:3] + dx, nquat]); Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row)) + print() M = len(Y[0]) LAMBDA = L_PLUS_LAMBDA - L W0 = LAMBDA / L_PLUS_LAMBDA W = 1 / ( 2 * L_PLUS_LAMBDA ) - y_bar = Y[0]*W0 + np.sum(Y[1:]*W,axis=0) # Note, this probably only works becuase we have neglected the quat -- not sure how to average on the manifold.... - dY = Y - y_bar + Y_pos = Y[:,:3] + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:3] + + # Iteratively calculate the quaternion mean + Y_quat = Y[:,3:] + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rquats = np.array([t.quat2redquat(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rquats[0]*W0 + np.sum(e_rquats[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, t.redquat2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rquats]) + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product for k in range(1,len(dY)): cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product - x_tilde = np.zeros(7) - x_tilde[:3] = T(z) # transform the mean - x_tilde[3:] = t.compose_quat(x_hat[3:],step[3:7]) # accumulate the new difference along the manifold - P_tilde = np.eye(6)*1e-5 # Set imu variance value - P_tilde[:3,:3] = cov # write in deviation for translation + x_tilde = T(z) # transform the mean + P_tilde = cov + # P_tilde[3:,:3] = 0 + # P_tilde[:3,3:] = 0 return x_tilde, P_tilde diff --git a/test2.py b/test2.py new file mode 100644 index 0000000..1ba1f07 --- /dev/null +++ b/test2.py @@ -0,0 +1,60 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.dead_reckon as dr + +D = 0.46637199585 + +_dl = 0.08 +_dr = 0.07 +to2 = ( _dl - _dr ) / ( 2 * D ) + +x_hat = np.array([0,0,0, 1,0,0,0]) +P_hat = np.diag([1e-1,1e-1,1e-1,1e-5,1e-5,1e-2]) +step = np.array([ + 43994.76, # ts + _dl, _dr, # dl, dr + np.cos(to2), 0, 0, np.sin(to2), # Dq: a,b,c,d + 1, 0, # vave, vdiff +]) +steps = 10*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(20): + x_hat, P_hat = dr.dead_reckon_pure.dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test3.py b/test3.py new file mode 100644 index 0000000..0eb80aa --- /dev/null +++ b/test3.py @@ -0,0 +1,228 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean as t + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dq, vave, vdiff): + return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3], vave, vdiff ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( quat, dl, dr, vave, vdiff ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, vave, vdiff, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho = 1-1e-8 + if ( np.abs(vdiff) >= 1e-3 ) : + rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +def dead_reckon_apply(x_hat, P_hat, step): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 3 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + e = dead_reckon_step_errors( step[1], step[2], step[7], step[8] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + + lrQ = t.lrq2lrQ([z[0], z[1], 0, 0 ,0, z[2]]) + for i in range(L): + # The first SS are gotten via composition + dlrQ = t.lrq2lrQ([dz[i][0], dz[i][1], 0, 0 ,0, dz[i][2]]) + lrQ1 = t.compose_lrQ(lrQ, dlrQ) + Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[6]]) + lrQ2 = t.compose_lrQ(lrQ, t.invert_lrQ(dlrQ)) + Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[6]]) + + # The last 2 are gotten via addition + Z[1 + i][SS:] = z[SS:] + dz[i][SM:] + Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + # Transform to new vectors + def T(_z): + quat = t.redquat2quat([0 ,0, _z[2]]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1], vave=step[7], vdiff=step[8] ) + nquat = t.compose_quat(quat,step[3:7]) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], nquat[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + Y_pos = Y[:,:2] + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] + + # Iteratively calculate the quaternion mean + Y_quat = np.array([t.redquat2quat([0,0,d]) for d in Y[:,2]]) + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rquats = np.array([t.quat2redquat(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rquats[0]*W0 + np.sum(e_rquats[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, t.redquat2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rquats[:,2:]]) + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + x_tilde = T(z) # transform the mean + P_tilde = cov + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps): + for step in steps: + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + return x_hat, P_hat + +## ====================== +## test +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +x_hat = np.array([0,0,0]) +P_hat = np.diag([1e-1,1e-1,1e-1]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + 0.215, 0.143, # vave, vdiff +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test4.py b/test4.py new file mode 100644 index 0000000..a3d6a62 --- /dev/null +++ b/test4.py @@ -0,0 +1,18 @@ +import numpy as np +DR_D_NOM = 0.464 +DR_LO2G = 0.05 +DR_MU = 0.8 +DR_D_EFF_PARAMS = [0.505225138, 4.55440687, 0.00237199585] + +def dr_calculate_d(v_ave,v_diff): + _v_diff = v_diff + if (np.abs(v_diff) < 1e-8): + _v_diff = 1e-8 + + return DR_D_NOM \ + + (DR_D_EFF_PARAMS[0] - DR_D_NOM) \ + * np.exp( -0.5 * (v_ave / (_v_diff * DR_D_EFF_PARAMS[1]))**2 ) \ + + DR_D_EFF_PARAMS[2] * np.abs(v_ave) + + +print(dr_calculate_d(1,0)) diff --git a/test5.py b/test5.py new file mode 100644 index 0000000..dc65ab9 --- /dev/null +++ b/test5.py @@ -0,0 +1,199 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean as t + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dyaw): + return np.array([ timestamp, dl, dr, Dyaw ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( yaw, dl, dr ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + sy, cy = np.sin(yaw), np.cos(yaw) + + return np.array([ + cy*dx + sy*dy, + -sy*dx + cy*dy + ]) + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho = 1-1e-3 + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +def dead_reckon_apply(x_hat, P_hat, step): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 3 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + e = dead_reckon_step_errors( step[1], step[2] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + + for i in range(L): + Z[1 + i] = z + dz[i] + Z[1 + i + L] = z - dz[i] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + # Transform to new vectors + def T(_z): + dx = dead_reckon_step( yaw=_z[2], dl=z[SS+0], dr=z[SS+1] ) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], _z[2] + step[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + y_bar = (Y[0]*W0 + np.sum(Y[1:]*W,axis=0)) + dY = Y - y_bar + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + x_tilde = T(z) # transform the mean + P_tilde = cov + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps): + for step in steps: + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + return x_hat, P_hat + +## ====================== +## test +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) +yaw = to2*2 + +x_hat = np.array([0,0,0]) +P_hat = np.diag([1e-1,1e-1,0.2]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + yaw +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + From 1a2694bebd5ebcb75ef9b351cd5b5b2fc9093466 Mon Sep 17 00:00:00 2001 From: Thomas Noel Date: Thu, 27 Apr 2023 17:34:10 -0700 Subject: [PATCH 2/3] Saving before adding a to state vector --- .test3.py.swp | Bin 0 -> 20480 bytes .test3.py.un~ | Bin 0 -> 72606 bytes .test5.py.swp | Bin 0 -> 20480 bytes .test5.py.un~ | Bin 0 -> 7643 bytes .test6.py.un~ | Bin 0 -> 20100 bytes ...on_wrapper.cpython-310-x86_64-linux-gnu.so | Bin 0 -> 129856 bytes ...an_wrapper.cpython-310-x86_64-linux-gnu.so | Bin 0 -> 110720 bytes .../euclidean/.euclidean_pure.py.swp | Bin 0 -> 32768 bytes robotransforms/euclidean/euclidean_pure.py | 10 +- test3.py | 49 ++-- test3.py~ | 241 ++++++++++++++++++ test5.py | 5 +- test5.py~ | 202 +++++++++++++++ test6.py~ | 179 +++++++++++++ utils_wrapper.cpython-310-x86_64-linux-gnu.so | Bin 0 -> 68928 bytes 15 files changed, 666 insertions(+), 20 deletions(-) create mode 100644 .test3.py.swp create mode 100644 .test3.py.un~ create mode 100644 .test5.py.swp create mode 100644 .test5.py.un~ create mode 100644 .test6.py.un~ create mode 100755 dead_reckon_wrapper.cpython-310-x86_64-linux-gnu.so create mode 100755 euclidean_wrapper.cpython-310-x86_64-linux-gnu.so create mode 100644 robotransforms/euclidean/.euclidean_pure.py.swp create mode 100644 test3.py~ create mode 100644 test5.py~ create mode 100644 test6.py~ create mode 100755 utils_wrapper.cpython-310-x86_64-linux-gnu.so diff --git a/.test3.py.swp b/.test3.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..920e49bf9d8def43c97d83eb5e74e9753e258057 GIT binary patch literal 20480 zcmeI3TZ|;vS%52cY;wUD*?vo$J)V|v_e@Vuch9bOcjU2m?Oo+I;~npez1eLhO-)zL zOnG~{daJ5udIr{xKo&#-M2sN80R;j=WKkSNaiU1P#0~@q2&@Pm!c92lAr{0K0Z#!f z-+#`juAZLRP1aagMpf%?y6T)$=klN1|NnKoQhn@$^Xf>Y?r`1eIQ|_U_Das<&VjGq z?j-Bsh8s)7)i0B7@*@k2lSilP)hi}`!X%tJ5w?08ekX~i)`DaziQG=S8b%xOWOths zovFl+lj%x#`-&Om5xE3%30#{5ddceKk(-?9dQDHz!q{Ev_S+u4wmkCGxdd_vlW*;W+n@7qRx-)^6m?C;$p@z>ku9s7G>B;G#e zKe+^Q3FH#UC6G%Xmq0FoTmrcSatY)T$R&_VAeX?KAOY8NoG-lFanAfGh4cMCwf`^Q z;yC{Te-595Pr^m$K?4rJAK&aa-+<@fOYpn!GjI|rFbQ|Vt2a5$i|{P`66}BnEqEA? z0-q)w2QE{OOYn2B3R17rFc0s8JK>+GZy&Z`4n7Q%a09&ZF30&Ud>y_DpMj4<49oE2 zFbQLD9sJ`v9p@R?gasIf8{r1H^bW`Q4R`_`hm-Jj`2LTOKeXTjZ~)!~-@6exz%$^% zJRF6~H#pAA@FM&H{61WQ&p{ttn1b)&WcefbS$G6)ft%qaoGV|3r(hF2D8ZfZUifdE zH?P9;;6fcvO%5ma%8`Cp~mrH}>USG|U zkLxufzjZ$BG$l<@XFsdoQC@p?r?I#=QC%)8FEaNv?l;{{e^%#sSf0FKb=5o`Syoy8 zgW5#CC--&vQ*2aKxms4uoko4xR>t#J)l#v!Q<~9rE2yRP0E$XN)$zB~rr%1!h=VWE z)NT}Xl44elc^)f|RUQw6PI2rfXKMAzk=2W16*&9BS__lJ@2JhdRj%g+Nf35Si-&SHHJMpll$vz96*r39?P8-HJyLH-H|ZPcBYksk zDq_h&LU<_~9Rw7CF;@vXn|_ouCB);8712<+%Z>fYtfghv8n(<@W3HI*C2e-54 z7w7EI+f$1j-M}5)xs`_Sm%glhbtdeULKUiBYW^WrI`~8;RP1H&K!*o(^ zto$rvZ)aB)t@W_&$LF_;D$7TeDoga|!>5)`mYHvMwT{&sPhp}?msK39Enn#~bF${D zAaO(vauwA3{f-~G3GqyI&u41OtWMW6mh_OteZ%bpt6|%79ktyby_;Nc5vQTu8LV-Sw*5SG&LA%#H?Cq?x=A!*Ibx;bg?;i zeEz``$8~Y%7~lwDhb^PKZ5P#ZMk+gg6voA3eSB`BR%REd+f`wX=*9Vox_*DCiE*&D z;i@ica1xKSOsz)YhVnbDb{NZcwpS8cL9(tJ8YhU$OfBl%s7)-+FPpy<>$7Pf)lD~Q zdXX+aOH-AUI!#T|FqxWOdnlETAIj-!sj|F~jxDdP%kwE=bkA)1QN-@Vu#rtx7Ak#H zPj6(C)FFfIQEEN2I9~>-@35)YYPunhduotvF)$1z1 z&j#Z8p0wVL0#OeX!)-9Ybb7s|)B4%8npvnG3$_(D)GqsdQ$@4W*=dtjEgKpvyjQE0 z?pr(fhgMIc0O=CSMi#p4U{w`uUDWI>E5Fo>6wUL;C1dv)JC|; zC=$(LxVPMHx4m5)F3I!^Iq4#;F4j<<*B%FU+nPUlq^zR#P@W+|74jmvv5`tf$kM43 zr__uLU{(N`g&dd-n6Z9bRx55ykI)Tk-T0nZ)jqJJ%PJ_MQ-xc%I zvY~3()RH%q)CgH~Nlj)I+jdh=cxJi2h@Y)ZQhPHX26MrqRa#iKUbEFowR)&DqY9!u(jw6sNiq_>s~?hz?l7aq4wMwFM#`U3 zSv934P^Z>Nr@#b?ct`FgmtrH5N$%a$wJM` zv#QMqj>wtFRu;?4A|=`)N@1i*YKo^i=}uU6*u2LWt{fs%r$i+r<-RgBI=IM2L?|MY z0Wc7nVzi#1Kr-7UEt(>g?w6+eS{5>YYOL9C2g%Hi@fvk4_Q(5E_m&vQawq?$ zYW1oSL_s~uQ0|6XKH7vI1%9lRrg%flkiM?BmO@|V&aQohs!fkp%&Mu1Nx{r;H@a!- z%Id@gtz+>cD*L@35=H0+Gbf4lV#sb_lS*p77DBz`&|y_BPeTL? za0>2$+u=6&Hn#mU@M{o25pIK5u;;%Ge+JLPm*D5&BHRUH>%RaWho68Zh`s+IxC1U@ z!@mH}!SBE);4%0RIPem7{4c^UzymM|Ww;e?fmg8SzXiVn7vZO11l?k00pg#OvV}DzRD1BtWKavF}_ZZo4tVW>i*vxv5#3DSNdsBWqm0QJaxPZme(ZnZE2= zvQ!&me(qRyZx{6*dmXp3RrN}&ixXr*9(qaciA_KxhEUvfTYj-xu8;HF4a&7@mDGAS z5Ut%L5^ISK&6qmf68V(L$`P}%Uq+4UsGXo&?60G`bk}29-d*t&tp;lq+!D>Wx1!}x ztJO*lfka6IxntSW;xhK3Dc0JG*W#QRa?EJOc*e1rEFi8l?`z6eD|{#{_9YR!mPwi! zii5tcDbsyDN!H}H8J)5HJ6z5+m9c5{F#A$!|L$x1YFVWXTaQI`!WJmnU}+y+nuZ#Q zI671`d#iWTmqY6EK8kX@t5^5iN=L)g*hHK}#bBaFTSnY2hpIBV7-W>&&=p;FsH8mU z3Zm~iqEt%A^ms#VmmNEv3)M=!b_j=1rFL+-EDh0y+CWQkB*ab`(e8}*sH`RlOLaT_ zS^;HaM!Dsca;t1i@Kkk`9LUr>I`VLE`smSvmBaU%@+5@#B-WLrj%018u%laJg1o?8 zD>l%+YGwTgMfebn&@J5cQWeLj)?}})P-=ajOb$C*JLm3*)dvsWdyxI^YD&)1$;G9s zq;RA~RzcMDv*SXCOWbfEbsrim%`4hg`ep5uqW`qBO1gALYjQ&w>^s^R9#ZU}N(qK8 z#=}BW-MQQ+|GDwHc;wJ0rE0gn*vyR&!EF+UG1H1 zoJUo~O>}H;D8oZ+@+e?&?M9*3YZ>2+h~vD-f+F!h*2-QK z?$0Ww)TFZO^M-F%Yr~8~{l;oe+gw)LCF4KdmQi?Co7i?`m8$c_V^-B1x!qb1 z+CDaGfC)K&{3F^6V_J5{xZ z6^Z##NBp(fS}+)I6k60nkSgx#HWRqJ&qPIASwvVKXO-8U-yabNT1xcaZe09vF7D7yjUA}C3aiuMi30V zS!Mjfq}!E3SKLOCX4r*{4`EJ6i#Jl1u(P_ubkG~W^6XxC2J6m{IDGkEB=&?OJA+n$&BdKThfqgcqIZa!#eIixg-#r=g`uyt^ppxOlXd zj_S@Ppr@GjYB=(iT!r*qd12bTpzZ&Qd@p`Q>_F`Q^nCxT*!SOrPs20d!hd4N{|Edj z{0UrwpN3WN;TRl(_ri_v8utC)fY|<*;4|-?TiEx{f_&>=f%{<=zJp!=*YFki zEL?>9U>d%UP5){57@UCz;cocncak6cIy?mz;4r)g-U0uP&Hgfc2fhMN!8$ww2jK6q z)4vQ)!g2U7Z1KN>r{NROfGLn~`LDr0z;DAR;a6b`*5NqZ0bj)K-hdgn zPZBUQTIRGp)p5muG$Q>Syzz#e14&mK7UfX|fIV%$vmkuIaL>z^xmGWV*mTSx6Zznx z)q05$>&pa3A>Zg^TjX@c(AUn_d!A(A<$VK>l!$EgXOdLN+3yOO z{>(6XWa9t!2+9vS4lY1aF4wmCNe7cW zae(Blbl!!p9;lhUM9=R`X*8eBuIVt0G=7iBjEiGi98AhpDxG{(>8Da1m|R;DjGd7v-z-JDx} z-oTNt{P0a=yaFPOfoC=Q2;fL~e)#4GAHET%6Q^bPN!-qQQJ>Mkd7?*}vW~if2vWPJ bNU38=>VEA3o93K|S*r`?ERQ~|bHw={9){St literal 0 HcmV?d00001 diff --git a/.test3.py.un~ b/.test3.py.un~ new file mode 100644 index 0000000000000000000000000000000000000000..a91d82ff33ae246125e91303416ca3a0b8b87ccf GIT binary patch literal 72606 zcmeI5X_Q>Wb%2E|Y=JOHAolHPMnI2dVHOFAfdPa@1_=Q|5@4wrw_4LJsbMrNb+-l~ zj19(HoH+5C%{F*T>|p0d9G^Iev5&y9V<#uOH?WE06Yue!_{9DZJNK)4_4@Wq}- zagrZ(&)j+SwtDsMSNB%c+xo7`fyeKh9IbwH!NRM)_^Y?=S^L;?Pdst&KTJM+?|;4d zl6@!Nyzng}$5xO3eeZ=odH;e13w|QHwB9HmtVbi!(5gJiF>(oV4I)=SluA5ItG+ z8=|0CSvhd9T5CkL>Yi$&R-CNwt=10I`^tyMCn}|KaWX2_qsE#?3`(|VeHs!Y#u>C)zp ze8=!yV0p5`<)YsZ1x-gJQrR2jqRE4O#Xa@hRH?FeZ&!5PNHkFH9g4c5VcDvet&rOO zs)XuzQ<*f1llybgRB@^tT^X5OqpmI!13F|ke3k>@(@UGX5A;gb>tcVWJ`gLMa0cwl zG}I4_kVSmzhxPXt*!tnHeN&EVT2Zjg0JThF4fKrJj{=@^SPlI8<<{XwzB^~$bQBT12$!uG|9vPWarC7+hJQ~uq|r!xo^nE zU|WXIb=pwd5-Z`fSkws&SBeI1&LUZ+KHQdTcVhN0W{&{tHVyHlTu_!}V1i(0sGs`bR)sQJOmxLaIISi+BPPT+?TvWO4AZ_UMTwdKeE zS!8y!pgdER9?YQaV_Arp#9!lXs-sS8H~(AHUh1Y_O1)hv(y>D8opPvEbzq& z8N`S04-DTIwQoJI1D!u#1DZ>;5~Woa38>4}X#o6XqCG4Nkg-Ar@qm2nM+Wj@3z_?# z1<`MbE)-pFu*tvDMC}f_=HBR=s2v)VbS_^yny-xI`^Ti^HK_qf^~+z>BmeE9!LhL} z$;4(2)!m|G%|K|e%i3Jmb!+LHxxo;1;cVt(p`K7U#>k;=V1z8t$KMgcUM~ z2d1Zgt}$VH;_$acTdx?oH2`$*fW^}eP5`-A)HJFAo-<3zsRz7Iz0trs)dtD39B7}Y zgBSO3=_&2lUyde<^+q%p73JxKebq*zJQ+<@iczstsx&Iq$@rQB2+vmq25(iA%Spi> zF+vvcLHd|My2K*I^oK;hBRaF=;?@G(`6R$DU_KUL)K3ss2Rbb30Gbx#oF5HC_i2Jro&VW_E$k~--F^_2$di>+5q$)S#j zI;d;hc(7J(9Ij3Bc-Q`Vqd0zFE?+pBA08Zwx}(w&5h@M_UhSP;Nrg$&{W?hF0K7td$~_aAaleDPG` zY-e=y#%&uZhVe@9yjGNLT8Er&4cMJ$0yJVi7W|p2!L{4~7$am655Qk~lL5Tc!o&2h z7o7=@HLnxZ@PM^K)JY_Xw~3ChAb2NM$RHl@zP!P}TV~;5`rj7)fheBWdR5%5{l2Vm z-WN%-gZWs1`F2tB*iZoI%#w2I18}DScxHQm7r1Wh!CGaqkt-K!j7I8mqr~-90mfmR z0P}Z5d2layAV$a{J^&vv0OPg~)Bm364@GBspj(T7Iu8WcO6FtXkiRP$JkVJr%hU(p z>kPoNtOq(o4&d@>9$2eYYtHw`{4!NKFoG`lo-#`6qz}3eP4_*_kKlV3x1#GP!>*$z zGE>J8W|y-^EbycO3=Ew`vP^v#epoZ4kAnFT7J|{d~s|S`G^Ra-8?FN|-n6N?y@xe4=Fr95Ny;BbM zn5Y{#n9HZ7o%X$0cj0trK`x5-KEVINo}xS;o4DU_&){(L@+mC4RO#W&0gPJ)w#qVT zl0IyA>5%H!x*p9ULaMn?|fuT$5YdS=MsIp9&qz_Sh$veJg zgEKuY>WG@xNaoe~Y4&|U*{4bkX3&P{tBjI5>4Wxd##zs`&N?0K5YFm>)?Q_mZf%n+ zBnMQXxisUP7QSDGvnM?+!Nk0mzBjgzi#2Env%FZHLraqMIrwk%XnTv9m zAAz#zN7>t49qz(HUwwb^U|C)0vkTm{J_ueXx>gi{?vtY2l@5N35weH}(P!=V4OUp9 zAD5$jLeyRBTd}pU-#kz$qtsHRxG$HNZ=?xi6gxmG1s4xv2l|eEkeK>yG#NUoo z9ETE)aJxa36{dlsGDxPR56AyB96M8S985UEZM`b%4U!HVl|eEkeK`Koa9o*+a8+L>ZA|F*BgrQ z)!W5#s8dDVsAFxZyf+#x7faj9BN*Iu7r zW%1%!OGKUXZs$^8^Oe2$-gea1f6dooMi1rrRE$h`lTRi?GEpA}ijuGm>6_KbQ45xf zcCaiozE~lH_>g~}aqMnO-hGb8ksrjd<%cs$g_?=m1>U&LMcjyK25k*CiP(VLq>2vY zNR%f516YiZMSQ@1)PU`=V7d6ZLezo1u^rfgc?P$hOPXUv7TksUcyXdU(%;wLza{|< z*v;x(fSwdDc(Afenq*>0*%{X{w?$;iCt*ywwD~Ka(;Y8%;4w}>FBE;=e|E#wsM&sY zgZglbs1xc+a#o>!IJ2ajCYF@_XR9B7W9mn*4Foi-D@A#_@FdaZbBAsXK-~kuz}mum zEP&*`K)Ai`ERtmk2j|fEtV?U>{%-@X&%(P_HsW%=gSXM#gOw)^r#I0_BsX8kpf6?; z^u|nLtxL!Ut=)Y)*xoAY1nzv5;|3N4N5u*m#Dn!$?QeBlX<66gU=2~nx&UjWbfgV% z+b0`w9kY?6`R&`g&4(LnHccI%IUh;*n@@DwSyc<5ew#W^YQ)o`rf!B>pe&On=~D~r zoBi>1l&9nXl{n%4EDu{Jm2K(8E!&XHU;~Pbp># z%dMhL;0)W7SrEJwD`XHKw)X2|v6mi`gK4%`5vOx$;R5pxReV4P$5jT&l=OkS`+0L* zSZ-70hjVaTWsposAGW2r*k*HFU~X3@0BGP+tPqtkLKg9XyU)Pww>{`%ajJZ=PGYyDc_fyL;vp_$ge>9#_iGP!mWa`Ts-%hr#^80zAeoXr=r-$)&+)yki4Ig{ zRXi{TuTuuel=MNj#h@GU^}1%j1l3+uJTP)!2+s>`9Y)9^9_W7l?*`rV7Twu$v~xvW zz+AyVLN41%#N=^_s8@cQGU|%1l(|7^_(qevYH-`9iVD-fQ5hst(ubqHgL=cfIj(Nu z2)F&JtS}86l|eEkJvjbif$_)n^X53v!Vzv2RaTfD6{T4XaTOzE5f6_4^RVvCVEUJf z{!sKJ(dOeQZVeIFJ&ppbdzp^~kZgAf^WnA^R>&Ye@E&ak??-ab_VB>!-~sDC=3@cm zgQ90LAK+ny4B`XtopZr6KeK&sqS1G7qT0yq%n$d-BO_)Kj|1T~p-Ko#_?e$E3;dL2 z(jxXc$o_qohvy@Owh@dxae8VNn-6hZ#{I@z*wbI{NOd z%5xwc4-O9u_O09dP)DD9M&*F~^wpI8pvn~AQ>j(&?{W|D0d!K-39xa{0N7b1%hU(( z9~;0o+AgZ=z&OAc8n`;ZItLx=i9;;Js;ZFCgy1DC3n3OOWDp;MPa1+7EI~~Fkm!#^ zTl+U|4QyTi23QA~j|GtIy@>e$4=ZF4A9&9hcpEJ|MirPJ0iO9yr1FtUBj@5JfDW-b z7T^K)LgoW7tdK!Gfc^3!-5^enmzT~FFFTHOIEqlKsd7RTid^Ro6fr^;@u7Ih37`ly zUN&$7Q7S~B=q!?D>O(Oy6kpQXcbVDpX)kpxAFvLq@&WQ=qKjA-0x4F=AOth>q>4;w z&`yu@y2~vu-Lmjy2Hs5;-k-^eKNofIUewtcHRMYRaVHZx_lxp!2?9B2840wUB~nfk zOUnK_4J{)=>+L#VwxhM9NeenhM5pZDhTM~q4wpP*gJha~LhVg@VLXquO|u@EC<5f5HVT7FjCJplnPOOPcc zQL`k51|%9bCjexd3s?|BB38&CJnQF#bQ>pI(sEPCLHmhp%+PH;BLSo|QM*IjtdR0 zDYxU?J3r8_m+DRj=zzYO1;L@QLI&{xZGXN|#ateQaSpw~3v|qUZkLAaL+V_(?8Bk1 zWLY4M6*7nq>6TyZz{z-2#*sE}xk6i_H4jTQ6By0^wVa4Swe(Q zZfL;r6{_@bhV2zB3v97M2JvBQKMS_W_ME1(%{ecgoox$F@NvV@31~sQhy?*BR>&ZU zB_$6mYpg2Mb6mP~%aYHS)_1eT$qwMaRq2u$nk^3iH1AJ!?2!wuvd!si#5VQ))%$Z@ z=J)Dc1a>apn$IqIkU;WbB7wYPUp2XKOCcW-bwXL_--nT{vq+YyPj#@r6L71o4o}L_ z2nh~jGO}G450c>XD$$2U5!eM@#uO*up9ingPB-p*+i`fgD-rN{RFw>NftNB!rlb$A zI}NX`$KmDt3qG$_Wr7_?IhkdldBh4C#D~`b!z&)MOmEg!(5`hR?c?n28r)u^N(xiD zK7pe$O6sH!$4SkR9q4Mfc5NC*o{*c?&xzYRxV=`D6Q*PoI4Yy0PWo`H8jjm-{KSP^ zca@8RXC(e;`=T*5D7{XV3WCY8LKIb&Ns~-0DLdl}i{ebwAma=hMR!P|N8k>bgQdm4nh1YQ8k* z*3j8?PiFz^H<*tFkhq+Ajwrx$W=T2K@aX8Y=@Bg*nhV~=^kW%THY$yYa;{@jqg*RC zD%Hv8!H1G-r7(M=Dj__R{#RhAER!bb!|+jcu6b6z3m|a?Kjya7J!yS zhnWu$u|fvX5EIvs{M69otPdH8cUy?#va&4dE)0wU5t;dviF*2=-A(CunR?I!w7(_l z1nfxx18QfMl+(nLvj1$TKV?wA^#8{w6#Q>eCrj19^TXpP$|$LmKGos#raJ6u@A)V2 zaTLhDS)B>gKPwt;YAU0oPI{1DzQmBuThf0mhx(kTi}6eO^@F-RhcdJ(PjW22Y6zyc zsA7Q-Y>QbI;x$&tAU@cZ8f^Ep$99Ip)=CXZZ&l@jU~o2NkW5J*YTbs~SbJ)TvkkOj z(~d?7K^U-QVx@NW!8T&B6^?^#bt^VTw@!Gr;9=3HL@yN$F%lzW5f5xjerB+3vDl8u z(ViA{O`G>uboHBhysg5!E}sxJ652XviImgClCnQ(Zh9eD*`(!-qW2h%@ul=9WyL2& zc^`#q2^a6U{rF!M-zjO-%LuZMUQ=*!a#Hz9YhDLl*>cPa|Kz2#HD;q_+oh)~8OSdm#6R5|_jrv!t9}<}4}GD^yyuwGm>_vc>eLiaNHIA-IY9ugqmPk4EVR}qQeMgStLC$>tzH=Hn^N9RyvUV$*iLm9_Fh<&+s_Gx-H+s1YxY?^!)Ol`g@AIVq2qU)~iTcbV;R;b(Wf)(m~7_2^K^SeXxAkHJ? zXFl_%^6J<)Rh&3nuE&Sx(1Z?z&CL%Ysm*;3Jry5XH!tLMF8LtttT#@T$K8Q--98cL zjc>eE6d}Kh?4kMfm-z7J$E-_*@#>Vd6rQz{%|+P5IHD=8+aunPYij|7vG)EOex>zu1Va#BrWeSuKvUvIpWI|Eks|CD|I6gq8oMHZVV%HNVoBPfnWC z`kG|)b(L9CmUw)jV=$W$Vd<}g@deh%Dn9*{Pn-VAP_qx}+0)c*A?2jWqlFIlL$F3x z@gZk#Sgy9@++fa)5lpja0=#?@HZuLa`-fwv)4dZ4N|%OCWk82DvWgEn`x(kL7TxV~ zMEc+koq61=6KMW-uZl`rT%f_u3fib2P$;C4E2fErT;10ucn08SYtb;KS-XsSH$r^H>(bHCD(VJ{91exhlXtvsHln*a@owAiqYP zB-Mcn;%BlfQ~|7zL42w}Nmqe)%faXSE&=E0xTB|mrs;YQYTkB zOUiVXX8@nQL$~Re{%ld&bQ>A;5{7r(G#2rLA>~5t(BWdEE}!Ep9xThVVyz3@b7L^o z0&fly7;CGfP3uAW70#+M)dTiznlYwlCC>s{#(GIg#sqIC_%uPB;Ju86p^JwVGKf#` zUTGL#*uFjA+S$Iu)C29uPSswEN4fTs=GR<#hy}AeEC-%sh78zkL^90Dz{BU#A zG0DO_B0 zEvGZMYD@P(k2dEJn{pxXDy+-Q)1?nWL>J6%qjErSu$_G*cfFnF^VnsddYHw$=GIX8bjWXZDZ~3L366pBkUIJh|Dv>wmHHq zA=eDn)DdhG(e#IQaomO6wnvG3^sdVnpTBwSFN8m5jjU6j@R!%!zUkrb0+4UpIC|%X zjb72uw9M0^-^~3b__bR&OYAFB2m;XX%$<7LEK`xsbBDHZ&wK*Q#=V)@5cb+E^@@5b zpti|Ef?k`YCgYi5X?n~{vTmEn9A%!F_4J6Bn4^8xZI^n*JM$VM@owg6&l2u#p+X?@ c40kgRFiW(%-DaO0U_Q~V-9gqo^6e-77ZPe>0RR91 literal 0 HcmV?d00001 diff --git a/.test5.py.swp b/.test5.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..7be0a306d4be2236ca7d3487f9c8b03d1287ef44 GIT binary patch literal 20480 zcmeI3dyFJS9miXd_fs&4O0;eUrDwNyc4qeW9utS>p1k(BWq0q6-N`!XovzvGyP593 z?w;2wY68Y5f<^*j#6M7sA)twnpd^Bce_*09_>T#YAciO)#xwHJpwaKIs(Pn)Z+6{1 zHDJ~J*nO(&?ielr;HdXR8NLmq_VS+BQl zMM*|tfy4q^vp_4XjqEy88!P0+4Vq4EW9OZ_e`|Fl(uoBU3nUguERa|ru|Q&h!~%&0 z5)1raTOjmK&_0PCyj}I;i28lon%{S*>vygrcY;d4TK#@X{YLeu%j74qKw^Q!0*M6@ z3nUguERa|ru|Q&h!~%&05(^|2coQsOTAKD4ob+#!1CRIrk^leCvo-By@N@7Ta3A<0 zxCI;nC2$5f9sKPqP5UeO19$>_9t6M#hrk|iF*p(Y{!C4K5YHo(9er)k3Eh{m{%bLD#_VlvM zInpuMkuKCQ23AY@M^Q?ijn)th$S~>9D35`gS)fB&T`U z@|~b4%UeFvYYo>7GetISFV#cVsdL_7mK}Hvv&!k?5n0Y^^d%>GZGAyfj_EOlQ1uN+ zl8*E*iN7gMRW0MryH}S|czo1?YzamRuz;w`w%mtX^5pFzQidnb{7TXA2oQ4%D14 zMutYe9)xD~uwJe#my3l3Hq5Lpofs%q7S}<@z4F)sN>f2P(ou0LGbYPuB1dHIa~i!! z!mZT;9vU!)9WeaYH2o#pF&p+W4T;+dnb~LvQ;DIpxW^sKbgDd9snF`8V-`29iqETu zU8h0{>8xjVNfA<4PD_ zHY_Vn&8yL(y64Mz*xLq^3+UrA8)4RR*yGchtNnN+}-4tr9$mvlY*+*;8vyT#`36cSzxHlU<7u_?(BHX3Y9?3HH@;u zg4kpsRYhV)+M!=lY7Zu!SwhkH8f*TXW|S=@ft z@0;CYKvdmj0h`2?8?tGG1upAgEuuM&#fLLH)W{BWq}f&6;XYPJal=`>ZHvV)x&d%2 zy0|HureoLKhNV#%EPYbJG@Eui0aNSRv|8qAurDu7e{^=5)mlzfEOib0Fvlty;D+{T z#dW0yu}+lO6xO66Hd&dP+&@#9ynOE!6PJtT=F2%T*|SyG>#4hNURq_D`);7?g`vse zyn&m&pzgFuWY6p!E{O86E(Z2e(_|iQ+AvttGgkB6CgV=Ef#n%JKGqT)JFE*MVQ~z( zytSZnIX^tJcR~I|vz!*lG;5oF#qve_eVH6d3K^_KX{`V4iq(ioiTqei8%g!+f^}4T z4bdJ)3u~9g3io|1XP7p$aN`jnPoS!tg`{I~X0HKA!Kq5!3|A7OULXTAQQ4f#YtSEM z@|nHJ9#aOtqGdNM*76wdhFH6~MSV4WYz3;EVUDj%Cm}D^Y4o)eDb-IEBd>H;sl}NY z675PA<+`YDl1R1wM3|Y`P%AN#YO2T9O8FcVEf~@kqHVjzbfpU`l~|6Mjuoja60qVj z9Jm+V5!Yjo$8BfXmUD5)nr<6&h8{feu`xZb(bMBC$&sP8o2pWeL)J&GYi}I(cQrUvivhKpn`4OllX8C=rFFC~{?WR72<%q#cpnZ)7D^7A~;{Cb*B9 zAyw^{ff&l@Fd%I%e3oIOxGF$yLM;cf9Hw}79H~MQI}Jz<92v3iqVb@e7Q;YHpn4Qt zHHDQOx|z|g=p@}tYEpDF?87vzw_~HO%$bK~dUvQhx+4Q~(;596%@=aA+iA8R^V)Me z92*Jl+dL4v+Mr20$F9&)^tnsZV$~xBs*SBxOpP4F9fI4$Y zr^R-2hIX6lNTbDc8q2|;gL1CiH?d~}3C)I6;D>ldF1r2i<+Hq1ZP-{j#Qq?Rgm6QX zf6%ZO@eMtl(e43GM3k?bpa2t3)5!mS0KV&s@NdcgznUCB9M8e8{}Q+rTna{j0nPzu zgBRh;{|ejzZUP?%i(npH1}+8TU>IxzCxF-C$G--i0p$OG7u*U0a2Sy9e-Io1`@vOU zH^67h+C|_6`1uckd%$PGX8^?kZUkxYZg2{C4gUV4fZ_oUf_s4jYM>0R0q26#z^ULA z@GAWNr@>R;aqxAp6PyoThizU1uY#8V+3E$59Ek-I3nUguERa|ru|Q&hx3&dhVPv`0 zr34X3?)GG$n2D3Ta(VjMLAV#t4I7u(`0l|Hmf3q zTZ!ey;fTblA^-rtR}~_&3!6lhF?DRI(t&|z6>wD*9aPcEcspBa zqpjR|RVa#n4vc&XTSXnK2jrh4Hl(X$>LG?SN|hGTL@GskR2&9l84I5b2%H3~Ms<)6 zwl@Hq0&`=bGuO6#l;4E1kU+Y#v1S~lzB~Iks zr!JrlqG6&jC5Mz*9WT;0cVJBWZ5sZKS3Zn4YzXdO zc5EtU62(@18;hdnyH=|zBkE+1!(QCPVi|^10Mkwfi!pp<(>mif**sMK?hKM52M~o!0YhIkAgpe=so^#aQ-kL zfBr6Dg1ul8jDYupm*AH_0=@vQ2k!#sfj`10e;ND`+y{DqeDxjRWN;Gr*{PcL1Mm&d z1}$(MI2SyPc*j%VUT_1L0y%IL@9XadUjx^I4}lMYv%uf+p8gH+EJ%*T0*M6@3nUhJ z%UhuTFg=)C`y3SyYWbv%GS?9wAgMNCcpT@V$1$W<*ET?A)q|W$uJ_3HHrM9n>x+G@ z@}FqAj)nBHvc&&D?SI$gv3nt5*yGjYIGe+ZQXHEz?Pf&>*SM8be61IsqU%kU%_=sQ4oK$46-tl!^FYQ0IZ6-O-Ax#Li(zXoin@Ro$dB-nZhd}o0p zHl^2GuANPk9Tyk*gVMxTr0b6pnPj748)mL7$5J~X+gEC(C{AJ>TicTX{?)+6nyULR zRHNLqc)*2fUN`9SCN-OVv)YCKx~UH+tvUIvjWV1yry^MveepVnuLpXSMN@u%CC-qF zuV`}%LwNoVlRF)>nn=hOkz$x#J1FH4{?Vx02O*nZ`6OcX#{)9DggQ!0exU}rRT82G jl?9pj$81n)Qe@MYQskDCKB~=4&xcKaVY=ErWS)NkzwZ$x literal 0 HcmV?d00001 diff --git a/.test5.py.un~ b/.test5.py.un~ new file mode 100644 index 0000000000000000000000000000000000000000..2f7fce727bb9b90dc902f491db8879b629c2402f GIT binary patch literal 7643 zcmeHL&2Jk;6nDQ;3KcD16$k`_L#uV;ScyYvv525*X{8jQwoa)M%UW%`lX%H`ceA@r z?3`$Cs3(Mg8=N?_oH+CbNEHVVT=*vtS1w!&@AqcLSsNEpLT-NY?0P=l$GqRXw=?se z*ZSgGa6bGsx3?PKS@Un-UA+DK_w}3UN1xxk{q6Nz;=_-h{@_dh*8KzBTrT$$l_P>^ zJo3|0(hN7O0yV8sIY4C(mB*-n@HQpqUOIYlKYGV<_Alrq+NWOpMAvaD`%(Loh()0? zqFwNSJNMOHhGS3ek7r5#D^yNU`GE?cI1PwnnYQCVq$MYc{I0#$c2X-XdBM7jQ&mG# zp(tu@r|5QzQ}x2B8;mYQ0Li^nKtMX6@&YO&bm4{FBzNxqH;ishp$peXRDfvLwaPCtu zeL~7Uqk=sSU^?W+VpdF*rcUed13r&XF$C-oqNAK?JhGE_&yyqs5yM`k_c8OI@H)kK z?N@k#0pSO{5Ppb04!_6`Q){7Cp&dyPujzU*ztqWNqdE|xy-bTxHn{i8SyXcHf}E8w zZ+1C=pF@@2AS{hh__8bhhsQRS!;x8D4hQ}ve9!3c1wM~vECY7X!rP!xy3Kgzzx>?> zUPsR}UYQL}Htb$T-0`uJl{)!fIe@E)quDA9!RZv>hBTFpgs?f12H_!Ex}KN2A6YSZx>%k@)hC&h|S&>Y;e) z4Dxk0`phvAXM4VOK^E=X*5F8ak;)``T)8aXcN*c6=LCF*V@F})rCu0VxXdXE*QXK} zD#UOQ4EcPX{$9b~b73oLr&6R%Ddw~c5iWDxND&Ph6b3R##fFzQ=?*E0WFr-6$itvR z#sR4#p|3*dau^Fota$4(5F1S?eG$50OQvyGw4{@?W7&c*OWRcR|SeYe9hP3v1aA>0YZM-jT~R z4K~X4lE`-&Yz)R0cx=2i_Nuqie9&MTpF0eOt9+xz*0O+%ofR=pZk_4OY`M1Oq_Nk5 zwhR)G^&DiaZ4|{?hf0^qCLL5Tb@UQFi2-xe7DOfXf>oo|4YY!4WpR@D=|Lx)Nx`)) zYJ@#kI;v|z)i!n4B=>PG7P^l|5}WE{Aw7|-z^@lc^}14QRO@kCh8kyN4A-5tShMw6 zJj^QAe4(dVnWzjlvsP?IwUTJ2ruMvy|2NH_UjOW`UGOO43r#z~Pxr+XJ7xZum8#6gSNz zbsDQyjqIvat94oxMz*oFTv5u2KX)7g7W$^fj$^Obo5BmkVsGt~F?d{@bNoiz2js&t zYR`D~E~((4=G8TCyK4rOhxOE1=mzy}_y6&8@OOO75-LH+9DBBJ+ODx~=+qggE)cSp z99*wlpQ7xtP@Ae7FJI^SbOjMlelI2MmgRK3WOfRgpMll|jWD*B0^pdAMcsk3gXuT{ z4#{?6Rd83iGE=7%(6ggfh6oU+WogG)W@-`Xg_o37o25m;m@^RVYShhoQO0G27fHL~ zg;i$Ja9Fzw8UJlVKyL*xcOzUk4&2J~E__)pl;*`-ne4Ay$!7kN6Q@zk{?D>=$CeC* zFx3a-Z4HClh+cv-@HJn>VyD!wBCY8nryh5qz!~IC3;`+2@thFAJFCC8I@El$l9p>q z0Egj05N-GR-@WGoSdT?ySaaeN L!y-=I`0dVLxvZwD literal 0 HcmV?d00001 diff --git a/.test6.py.un~ b/.test6.py.un~ new file mode 100644 index 0000000000000000000000000000000000000000..4d7438b478dbe17239ced7e632811ef8931b9921 GIT binary patch literal 20100 zcmeHPTXP&o6;_;^?Ocp=PY9tckz{49*3ufsj))RFjuXcvC61+B6Z`e{AB(g?>v9tUk`ro z{3UN)J#$t5;cI$&dR{}kMRO8`Bxz9Z zA2B39M&0RCk41w~U4=7hB~X6o*X~Z$LbM#9(%r0pf*hNbhNso&s2WmU%~z69)EPqW zqpZph2kBB=Q?3S@?mofdKK0;ISoPIXT?MOYQ1b&4^U^>q2bDC6QFk}%O-w+i58~+- zKCR=SRxhjvag^k86B7f)eyZ?|QdSz7m;fib%hJenqW~3$SYp_3D&T1BFi^lyAh~u7 zR-$Du4!v3>P*F`Sc(rgQs`_Z5Sse!@vifnhKV5ENc6^|ipTI>p-e;NOIW^XJ$a;Br60U@2Ug^Q4Zobij$m`O5RGLU-g;v z;c1gNGOZ|Q;RORL4Gn;0eFf#91nKrE$foR9QSDB4*{C+m%2Exo?o$vVs`*4Xt0+|* zdaV_+j&;QbMW~+XnDiLVvhzOmNKgx6s*~75rR|~es!?q=15VAv(SizUm1>lP$oGTg z&`U!=t939@D`7gP(m7C}YJ&RJq&|kh5J^1W!DpJ?hE^8$j|~jxGu^yiYEVL>YQ0d2 z>T5ZQQYJxC@v4DehD114!d= zRfRQmZ1l`$CeNsurCLQ8uZHu1@>H_8V({ghL@;-yyq+f%lQ>8a>GFo&d%i;om0Ly*t+!?D`Bqp zc(mNh{M&8*OcbkxB5br{ANSgF-gVpkCDr@c5q1B)g+nvX^%l?&^3Ro%enlE(O=OzH z#YQz6_MTYws!Ks49UroUH&1j~h~CuP5JZEDCMl}L(rhd%+a5w@zx&MS8{**zud~e9 z;^ih`+uW7HB=h&!+OZb`Voo520cLNoYqCnJ`XLu0otovr&qrO2JCNiY-8GLryx76HCoT{sun%^->5^2`+W2iC>*% zc$QU`L_lL$2CF*>${a8vNZ?ArX3Dfdifk`o)h5<#g0dX74`)lmYCwTAvuMJ8d2#Hm zb_>~0NmBc+-uvyQ@EVgGdErhk@AWnsC;g~FEA~HRr_p$c97j5rF0hb+>Oz)uM zj-3EiJ>XMRIWC2M+~10m=ld2UQ9F)58~en>h?wP)BnAvZ6XUXXIM5<0&2V#*!R98{ zvWYP`XJyv!We)W$j#j8?XE{Mfn8{$O=6egzV!xh)l^HG;jyOhUS=*RpQPOBdwhmV{ zT2ihIvI;?8X-v`Cf=VM*3s&qhh8n^dH-?kB^1A5xUBUq_7g3?c{4+ZXrLd@^0(l(x zOc!~{mGsoZuE6LqTI%4hqIT=HBPV1=*_8S`x(?xEcSi7ZdU#qkAl%4|%7%@*5ZTS> zN3$0>ZhOJFy?IXY%2FH$wN$go&8cjBW%6UYqqE}(3pv*mNJv(kq9s$qHng0L(9S#= zq3|lK92_|;=H;|))u$e>RoCohH=3DA0t_pi3$ZFBSf}Gzu94w7xrmlv*s4`o!=)oX zsAJ>H?PLOovX!aNl7mP`4o*Yw{8f}^E0ft-W5&*5TT+?Nl~@rwAy#ApYpfki>7bsr zXs>tiQ-Gu~*R?w6b!=VqQ_1*TMV@M_$WtGRBFl8)Ho6+ra#OGa)Ns*my&*zL(*{Wm zsxj1%4foSSER}teI?!AVRrV3Fr%_`Vg*h0EmaUfTZ&6Q637ezXJEvCV9cPV#31HFI z+*JfsW&NGPyLJM)Q>BqSWKR+ZN7$WcCbwfN+@Pd*!+}o6-Yni8^iIyMAbK^aL3ybN z_p|L9$(GM~F-Yg64@hG_#yCLulBETcIXr^gytf)AqeK1uL|^*v=@IkQryfnY4GxzB zXeoAQm8B{-#oX~x1%tT8$*>T3T*Z#E<0(4{8d{PTS|&V}S|78NcFm`7ICeAnJYZDWG9hy;t4hRW-*DnIU;T!I!C`K+uOV;a$DU!<&=4|qF(bqy zAEZ>?XIPF5v2H7KVKo5Qp}J3+(kAFi_bXBtJ1DBIX$|PMB|b3(<(Rw?T~`>)D;kO9 zQf%qD69`0Xxom)WwbrjCB(9vAfhv)eI?Ln>yL!I%~G>`Tx3TKT2ry zYagccen-80TD@t$JssVc3yZ?Tk~jqJ^*HjEDtu`Y`$&H0Wt$*-+2K4bs6W*&I(~-T zG3YLN9e^=x>36wW7ufKw;Zp9XLM3%YW63i$b!5N)7(kS_^cm9UcN@V*(9 zcu!Q~G7awY=;#H+KOz#`-9{yPdwcPu>wF%G7ZLx2*sK6-N$}n@C9VRn1yzS-t^yG7 zs}XIWG8F7XR{^XfI=pX20siCKg#G9!k9Z!D;BL{mM%Hz9%J<;k8ydJ7)gfhq`v*i) zcNK&!4wy1mL8uVdAlg7>8MY5y1+kLo@V*HJxv)bN!xLXYx+Tb*z1UZxf+1!ZyP<0^w#FTe1p7*4FIv?*0lt! z-e<>%(tX(~^FH2PdrhS#2d@#GX|MQ(dyGE>Xnc0nj!^t?9C($v7T=a5ww)ziUYQGm zYO^oI#sg>Za5&h~mggnnLeT0)LdQ+eFs>uVTbh;O!e*Rn(tJ5wkUC^q!vD0%x(!(=I#I zXelky*KV-kcm=iOs1X_i&u2|D&!EhOCMoJXxb#rr6YAopO#QYlFm7i}PB6-hBV>H{Dhm0BBeEZR{nvBgI-4kYXFvGsz z;(#|82XxEx$%6fX5gb(MrDs3!wW)$G?lMHt4z7RDetLn9W+SnA8<@G(v~xXovV)2n zOkq1O9Q)F95l0-;Q9ljX`&t>}to9qnYCt1T_m*Wif`fBOCr^#rVeakPwsI+#QU^am!7)*qSu3>eCORpn-? zk(Z+FSTKXZaplEN@{)Shs|bIrZf%htH>#hZpXo*Fqlq(&J*KlW@-sadgC*#2KO(<@ zIJkOHWfF-$?DW>zLdGLq6kb($Og=WO3bCYl3N-H_7NZ8z;%a2Yqvniy}# zoG>un%77k>^is7l(5)>8ny?+HmX`h@3|FmPW+a&%vT&Pud&<0>@NMLJL>u^~Vz!w|twFmOm8s~@6 z+et)=bBBK1feFp0(lo+Bb82XE~IYSh4&4C*L)~%ox3M!qX};uor|)Qv!pYuiRrD*P>B0w z_PL9-l|+Yk7hgB+V*RFIeXX9#6#W&5uOZ5|N%p)pm)6_*!xE_5_-q0}q=oM;uvQ}5 zxo2+%F-Lwm?c7EKWXJsq6 z$1@9@mhne5s!3rsNXs3qweB$ZqRUAy6Q2cw^rcL7!-pdQ|J1voJB``PJEkjv;m`|j G|LA`|2gd4&{N^h8HgJS3=?;w5iv#Q6V#z;vZEIMf3NhCy zjPlcf81iTs6;5rc%I{3|kgdw?K$X3SC2g?HjGHt=gV=WZ zVk!riPE|Ph=NvonL+)D-Z5)@q;T!)UZP1_I?L3a6LveM&MR~?N7|@&Y*7~mxB*euf zYDte9+9o5gF4OR@?Ox)|+~udN^XaS-=Kyxa6~NUES9e_J;>yGo`{|*Oo(g6u*c(33%l;Q z_xvuOXRcWO^mn~KI6Ua7UUg~Jw_kj9`jzK?kW#qnj+`$J^g22Ij&;M!9{X$MsHAB# z56|B9)S;v7^6p741MLTUMmK`_) z-9W=>7b~dJ51v8Ze+GIB8rtdd-G2u8zapR0y@@-rL*Q#;M8tu2!H8VR&{ioSKcBs`?( z@lL*DBw>W2|A06MJBpsH=syP}-5F%Izz=@zRQ5Mcl=xK=XzLYy?gUBbq5SNq=-b6; zsA*+N{x6Q5Ns{ocvOie)*`)kwRPuMKIBX6|LX)D;02F?nD+#rVK2OotD!Sw6cx7j) z8YJJ2mkRGV^fvW!HOfKz+f_wXDElc&erpd&cvR8f2c-N#WoH27_~~m(`r3Sn|D@>e zs5q>hD(SqZ@bh(44~bKA6^dzJs$1Ec}R|4c>K+O(6K zl^splxm4x*jiRqr{y6u8pt4iaCO(#vud1&yWk)M5U9h-%N$K*MvSl@;rCMpx^ogYv zmCGs@R4uQmTsD2;m_^k~DyNstTU04|r{|QGuPQ5@U$vxcQPoutykzk5swL$W8oq%{ z%E_syEUPG8R#|>U^^%;y70XJ?%NCW_E-I_3EUhT4sL(1`Ej?9kXp9p4t6W-GQo+x( z>{1#ouU<}_VU@Mzi>e^HBqyh8$%;yp;>y~x8pu+vwLo^+(xr=5$MA&+%U*s(Y5Bq{ zO6QkVEjq=KfrHvQQd+reS@p8z@Eo6#3azGW$--0Aa?X!c6FEz#lwU(?YpND4&lx;! z>P7UR2Jx;cUtU;MB|JaX`GMutilw!CtB?NYSblGUZ7YpWJjTvWEG7EKfAB(&&hHOp$tYrrgARbDDsg{)H&mMtrt zR#^jqswE4Ad_iT|qD9r^;1w;YszL9FwB^#3%TTeER4YQ|pzTR8vAUvGWIcJ_<(1_% zrQ<4V@@s0ADVrs$$CNEy4uR6?tC!M22ZdNkb=4B|I}oLf(lN^_(M<+|Ku@REE~%+n zTp8=@*y?4A%S1`wcnO?#N+n&1h(en_RL!fcQTphn=sHW$hFkZOfrFf;!k)yovaGV= zOr0t!tb`~ZBfR{|Wi_qM=ft$cDY7MAdD@mZNOsp&nX85q?e)W?P}|0M8UdBbDHd`D zs}|oXqc%QgM|#ESeI4TTidIHW%`2w&wDKoskkfs|P*+k>RYea@>DrN=t%i@G3o2_$ zmsc%VTvoc2O$P%=?D%n}K_()zsA}Hg{>!WT57m$=m#J~ZMWe@*4(va0m=;O)9}-D( z`Jw6J&rnduI!sbxzs(5M#Cpqh8i`ox|D2Zj;zkxH=j7QSgl@SFm`h7lwAzkUZmtTu z0(ayS6_2>&TY}GdeQH%zl7`jfc}m{d7vS2EpJUx6JfznB4t=YlZ(b|;4&A}SZRjsK zH{9!6%jYTFfsUQSN

|ezTf4%xpvdLdnl?>}+X6Kc*%yPqd*scDA>n=O{b-+R#h5K*r}#8@gkssSSOs zvJ-AY->eqPC)>~+J6qKRpUp-WIm)jmV(6GkMn2nP=xT~9c>7}Li4ke+Q^nA|G4w+* zbhcmT(-cE@)(qr@W9YH#pJOrf4vrDPlQHy+7<&3ziO_c=h8~EaV@e(QWW~@iRgHYI zW9X{O30`gt-RT2lg4BZogE$fiHdMd>5=cnh{FK&ZZw!!DL!Dl#luyN#DY&VUrR|tlktZ9#?bkQ8yl-w;%zOHK#J#CkQ zkbh9f54ne+_fNslvEYu+Mg@1AG=ut{;LAVNq{6@qWgwxYX}*ZFqtEuXc4Q@Vwc7J$ z1nWi)grpV>eNfC6s|z!?QxBSoIVG-k^HIOyb?_15AowZe|u}Brp@m+i6 zi&+R(1szRZlo<$jMyOE&5Q2@@Wab7NYcjK8A1arjX0vt+;q9YEq{9- z3<9T%48w;A3mS5=2iF)>^vuIZl>5=f{FgfYlqJlD+L6D;GMQQM(RllhMI&BJ*nSE3sj*i^#>h{zSJLbFgjD;%ykGHIY?OO5ZFmb zSnCirDZ-5oVY4D^bO>7%VUt7HstB7M!V`+H#UX50gzXMtpCasY2nQA6phGyM2!|X( zlOi-Zgs>un9l|k1&^Y>`3hPfQLV`o!rZG$FcL)iJknRxtiV$!J>57m=0&F@>da1&< zs3yKj;K_wsDYR7*3!exM+l^cE^+)+OQ?Tx)%#)ndfLMD3#DkcTk+=^K!$|eR0kk2& z$Jqe@pUwjeHrzUwps_eJJ{Z~;3_Ty*5jKN$|2*kS?)xkhg(lm5FqHai9&lgs;AfE? z;D~1f0``428xYMLIs4Y#h7z@P>BvXoeqY>BzY4DZJ%QqljoXoahSSL6hKCm-UEFa0 zT!8SyJ-}|LUy5|F;jXm;JkGHJV={_w3AcicSEmQ-_ORoaf=Hu4ICepV9uo71H*{gj zU*7}+Ip1&)L1Df`7;Xe)Se617H9ox&8bys0X>bg_{Pkfd5D5@DrVw;SRJ=m6^L@#+ z*+rp3Kg@1|8Q_aG;CT%1W=XhqE|^=HN2qXVF!UXUioMnjWQNMwt_SOOW(W6TvUL7nBJ$xgQK`9t)tY`R&8}Da$L1g_FH$EN^<$X37x{I|~9Ks!>06B-= zFAjYitlO0r-jC-KxE~jXJ_%pfiOKK4DGr?o=b^fa8h@3?T**HX?k_9w(qr&<+R382 zy%^a1V$8>_Y#;7a&oda4$rg72P(Kj&FHjd?zL3>~yZt`_F~`DPAJhlgS-3p%tSwiV`*m-~VkF+swEloSPWVe9@K*bG8>_{t(ahiCBqt9XeK2_wmW% zkZ9gTp&!`ACWgK)4jnHHVXiD&dShJ^I%;8PF9^&Z_f<3;+3XpoVCYu5iBdYZpZ4Fd zg9vJV+O1>o}UQb-ZBMvD){G>UIZ<>Yh!{uiG1!U$@6B zzTke5(Ygw0*SUX+*dDnd-2O{?fqLV7vMBT|T5jk>F!a(!8jq*lI5c6j)RVcjM~mTj z{QNVUCx@a5fJ438QDse5fEZowJGJOnzY_MT^W_n~GsC8imm$fTg1P+3>4((Ld zCt}IW*CBJblGnq zC0vFF8@6PjW3_Bt$o|oAO=d!2&i?!-@;QkM?Rk=&tkZOsJ2zVH$tZUo zSBYqckb00(jYIClllEXkZg~7L$3&-`?MHSy>sU9$_VxsfpT3@@;{DXQD`?J=v#MG)n}oOvU=odPOJ-2F{~am+weNHh@!f_ znYwS??R1BAgYbf5zbuH(hB zzV7%;S*|%(*1TPq^Wl-lqxA+fJOe^U?uI_^DnTNzM(Z&bcylc}qT*)}zeM7~=h}y< zmQ1yK!yN&lJyx!#Wqr4UWBJor~ zFFDe{WXC{p!{+~1@5*m^tw?k)-?|2A!ak#k){O&wS9^+I!h~#JvMZx4G!D7AuV@_Z z+7(4?9F0SMCJFJim9qWR<;K-c3)Zblh^s9wLbpV-sl^oOT7UQzv=9d6Q&H!lc^p8p zNVb$ei)5tzpwSq3(^)i{BRR5N3}aReu7BW-TK3}`jynDL0%4KH`}QZyd4%em9R1XrAgA^)rD|^e&1{5Ii|P%O;*7qf(y(4s%#Rv0gwnQfVQu zBkzW<1Q7R={EKD#TzVd=4J&ZjMzdSB(JXmmVH-vJ#qeH`nWe_`EH>Ie_!lrIN2F5J zKLY(0D&T+DY|oJfHaQ0V7tOXpnwW7$6aTK+?h(UczBJM9j3&}g-~B|(-z!Y?lqL?K z$%#muQjkC^6OcZo^P~t9qOWx9jkwn3x_$L8vbD<&G*%Mhef3=17B!6JkQ?W#zgIL_ z^dn#WCczlT?lv_d{c}O&kS)YB+0EJQeDxVf7Bx&p&$}qn`zE48_`?G*Yh)LUr%$rq zZKJSEejt+lF>L=zqy`}Mv`C3=c@L84mRF3U0><(q7y7#9alF1e3)UK3qrqUm{50(J z%W1M-URqSwU#}@IsvDr!Tp{~tZ`DV$V*4oUO0=(V>Nhg!lT1;)PIc;wH@-}B(F>T~d4l)ZkD>W@i~Z!QJm z^mi4ej~Hz!%Eu7Q_V6bV9V|pS&yX>EGa|R{8IeRd>wQAwM0hJT458u3?}*Aj=*WvX z6{F>=e;peTEXE3IJ`V)(I1ye*Y&I~Ci|}M7@$)6lcm;`1aqyOKF7crb{&_fycsr%v zIHVinae+V)57ZuG{l`F9OmaRW(phmnATnNYUL!J4a888x5*ZF8{322@(|bAp zb;he_dPc@8+%ir-jmqLQ3d7a(%)w$B)n?Fo7xv|#CHt8x6RogecIM#Nfh*Xsmbb9_ zw|zIaN6W|Kuv6xxk)GS~dQnIYA3NC|8(goBJ^d(%$xy4l59!u3Ti?31ob)!hZgDJ} zGJ3QgfFeG`+mV4J2l(pWXV!91dJRc2;??EGW5&wZ zV&urghO#Z^>5W5107F^78%>ZKzUM>sat=qE;FIcKbC6Wi%+Vq#<`KO_5`8|Iouvqh zk^4Jtd#x4+zWOQf5#vnISt4STK|hj>;y+Yr&7a`k&Vn=D4E}R|cpf!0z4g6s!3KAZk63PW(?2 z7vmrC+Z5j5s-k}5kT<*0T5dRz+{J>6I^cMG=mStLjmQs^@+C_CAK zUE7Y@cYq&VZ^)w67ebD%Tuak@P~qHkgpjg!%**qB<}!Ysip(ji1I%; zO8Ea>K>9zPyobdu6Z~f;>7X2WTHar&oj{2%M5cm&vI+Pb5@*g~;;TfXV0??D{l6;v zpOQPqv7hq|YVlWcJyg$!CQwM13Ja#8OT~n6Zzzai^ji&$6l?azA!G(a zd&4(FOH>^;L(s^<57z(7w{DGWxCzX7SYd*%{$p^kfsL~Er7<@2V91r5r)f1yglXR2 zTKps3csve|;fGecxMky}I8CcNnFLA_D8BW3V5Vi`Mo`(OegIZ?647}B35qlY$QR4;=DF~W?cwBmC~-M%=W4zY1`eA~q8gj86XZN({*=hPaY*+7PI2r2zxPO3 zYruw5cmWKB4@<2JNNpUFsVaXPsmMELJ2wE(o*P_W;K?&29#!$aLr9>+wc8kgD}Ww( zRF>^2FFkJ@(gIPD&IkL_50DHH8`DO1>{ znf12Z{hrlCFMwlPcs3sP&c+)9vvjjCm}&V*OVqy4+&egJj=ibAiknV^ZB zvJX%c`UsC#!jEFWlso4fV}FTgbJrxgBCAbAWoL_>^Ic)r+wA?gU$DMmGz$)6n|vnf zaW6JnB5#n09c;K_WkP_}HB&T%0=_@uAB!T-9CtDpLV)q!g+JU?Wg6Y8arUfl{m1_w z`MrO}{CdRZ2Up|q0!7kR(Vdb}PX9Q(Lvb^M+$*Cv`@-gXWLNp)rTy$EM zsdyeb#_@HGpEKUryqxhQ|FroXXRspq)!?S+3tNa)rTw=sSU}kZUn~iY# zC$mpX!k5I@+9%z-QG|dJWRTF~XOEp@IWHuUt zQjJ1m`4!1c2!bDzH%P+A(doNH{fRv|ykUhZd>x%-RjUrNFlRe^ARZKAJMy#edEbef zY;owD;>L>1yl^Lhe}g`W&KZ7DRD!7So!`nHx-hb5Qfs4!t`a>IPrAZoZ#w&d$iKL; zI-R4y4=|+e7q6avFuR zQ_F|$xH|{}!ouh79aKMy8BCHmm^e!=+&|uk>EGP5JcGZdY_u2gQSmq7ThSb&{>Ebl z_J8B=IOT85I7EK~QGZ>n{JoejJQXxvr{`Z((6~&`pHUb(oVaX^>8^OZedvW zqp$VfdDYn3f`Skp=6=1VLvsmcd+PZ|-A;Yj>%NnfuL&)Rq6!Gu!; zvC75xjd{nRl^^1TFuV-b|Df+@+$`j+AGebiPY0$+Q>@7G_;8MyvvQH-L%ICj||i zGYcE7%yEr&pMu_>i*imZ-(OU|D<8!e-)KLtO3c8pn{7wG+J}4+Xk}e9YDuVu_QkB1 z%8xas#>-gRUqZ(nEPo~HrW`s7hHbBXqfq}||NO`X;jMl&)?vAcg>Z={sWA}?qGA%l z`(ISq1uz&_2$;Wj*Y* zxYMZR<4N+JmIVlb6zP3?PoH z85Ro}b_RR!nQgH5j$qy4W5HoBobC;&7iy1Of4Id5)4g8{*1zJbXWzlFg2=lr!%^D; zj=aaiyHJl@C0XDWHqOusLZ4xutT5;8Lf<2=N84Y1=vYDM&HTDuI)>|l(7wXn`wDs= zi1LHwXuy8FOt6z1d3@Q*&(XtN0mvS_i^^TYPk?k?1u3-r$l z^-l|j9jU!dG)`=h9K!f7-}I@y3UB!|skeOaj?e!z48hRB9x@Po&R2ssI*P567ys;#)uWxKPwpaYK<#DwDZU|XkXq~i2KU76GO+a+-{t`Hz7at zspy|E@3rV~b+*=+$~m3Q8UJj14+kAF2=U!tWW~a~S~P5D?E$>Zl~9CNW%SR2!=A5w zLKf!l=)0jsnefKnejdh>g2rq5X?S1xD-=?W|L|pHK|@96NjLy+3UmHd82SMHzo>jS ziW+Pjytg0}1`Z2ex{xrsv2y|%Td@4?A`GN4Wq%)GXSrwL6<-kqjIPOg!LWn17xE~H>UHE!$UiclK5qL5~eG7Y?R;gK<&?#FT8O0P1%QUUR`+M zuO^SI{>%C86u;@2tcy>it>|?Bs0`~OZ@)+19re`4G5=M)q+Ho+8ui12U%WDLUdgD& ze?7kW#Gb7e-f=rW4~~+sdDOT&@5W~G=cBGp{o}X~uBuUb33*>E{O662pZxGb{8pv- z)z!&b*|G(JoWR1epO2x~CA-FWk1G ziyzuNl~P*ON?kS>4JBDtwJNX@)kDvhS1zvVhhML)s;OF08K|h_PX*UhLbi2bC>r@W z)IhcP@liATe%>@tvk-xC zsMYfWBHRoXCH{lGlK-8(vDnWq9v(Qw&E5hwc4qlSRW&t> zDwTL&QJ#v*8vKeZN?lPke?ESjc}b08FR5ISSEiK7RF;*R6VsFfB`_hGu8C>mKMH) zHTRj8mL}qWKLBpr(b6&)?_8DaY-yPZnEhN!%Z-4W0q+F#Ki|^A->qK@n1EMFv=>@h zG6C~mY-yPen0=t7N(X~_l5JKWN;h;+ak0R#VRX}J$@F5nY@n*m<{^y9_AlYnahGw~A4 z+>f9S*aTPuxDhXtJ^`4A_g}SmOmTb)AMf+5OjxUp>Nvd5pv>-6q<#Ue zrGJAQ3F<@oY+MUL*Ql>Pq}SkL-HG31pXUwC@+N3_#-!bZYZd5M0ct^Sz$j1jCKP(a z|C!hV(mUX7p{=oAf1@$Un|_ly(HmHAP4RBk&GYp{Zy?{BKHBRa?M)c%fmi@n6RzoK z2af`3gZ$i+c;f#aEt@2}#5x@Bknf1oFq`0vg%$u!7*TkFR>f+6x zxe^hVd>CaJ2Sa}IUi=~eZQ@gcD+t;T4sE>Gf3s2OO>Z>EdIL9E1>UUnt^#j%UECFk z-mH9YV6@|Az9-+C1(_&e*Pa(%dgSCSC)W*b$A6P#mN z4uba@c*6i$-t~x6$z1QuvEI2;y)*N@CB|K{>|IA<9#zccQ=i7EsnlG3x_`TaWVQnSW(<6gcG^ z?TBE&LH@Wh?+3Vww_3YTJZ!i+Q*$5%TB4HZs zVcXgUdkbG_X?X{2|IGICy}5Pq1>Uv#Tpxmr@K8p4NLvWnHqb^W z8s1&kuAzO<8c7p%g@DzWS~;~%8;f{H?hC0XW8p4HbE2~-B{Bodmm)| z@BL?4=Ff3=I%J!W<|h}|hoA*8Ca)m@dEIQF{EcjPs&9_-Zq`}AHhnV>;sK1i70`XC zwXW#b<0AcfoOiB)FtR1J?%rZ-tbmP!{|y@@XRyJnD{%b*c5-nK5&uI2<=9}1Xa9jO zjaDK155}1FapTzD(dmt=(7MN*(z?fb%r5Agxnob^u^vOtY}%FEsCLW ztQi5?A<)GC=n(C9Oj2CI%_h9L$u*%a&YYw>!={!8`9+Yw5%)0hze=Xk|04Qd)VlwV zr~l?Y{S^O%Z(CtwI_`HIAJ2aN-;IFtd*#mWlk@f>KBzx_9Gt(2&W|ktI-E=-Dg2jH zWg+f;sII(=GAAZ%2qvmSQ+`zq&~{ex@tKcqv(Yoc!?UQux1> zgB(6B3U~6w>jQ#6RPpiBmB5{RrPlwu-_HNBYwKZlKvMD)EKzW-f=d-#tKdcjH!HYR z!R-njRIo|GV+x9Ypr&E`>xM6U0t!kD_ph~1>hw@QJ^2)B`Tc$8_x9WJo!`}Wen-D8-}$|K=lAj3@}1wocYgQ2E#LWld*}D; z+w%WYVaJUbGdz$rV;&ZmwSkGY)|C|hx{2@`8?R$Dx)57Z*1~^VPJg@LjS_`C2e_PGP)1G zkeLWwE;=Ri)Qoh^w;f{b>ha~e$jwZ%?m(5h)+c5S!^rM>C$V=|5aR|W`OD@l*Ng=| zWZnfqm=CKu6PjeqSPn)9xWJ<;IunX9`Nm}2EKoXbFz8Gu#sn8MegOU_GMG?|ao;0` zoSyR_moDb%GLMn`-&xHN{3jVqD2?1XU>pX{O$wa}Eg=Mwb*VWB2s2GXsbubwbFq0L z<#F-%fMoUweQ>j|mYBZ>pw9THj^JEwJ`N6bcsO0@Oh;zc_2%1niHADZMRf${TJvLY zsKY~yO6QLViSZaRt9&kuXqa8ug0gk<3qX2z znWLi*=43$f`|2jA&@33wzKYBge-NCo#^`2$_(%QUMD*VPrkR32N;kQxqW<3_`hssS zs$QU7qz8Rcn@4a}t&uTRUw{FCYR4Qk&76;Fv8r^FCoY+z2VGd|NLHn8{to7-)srkH zH1hxk3+o!)d>bTcjdis2)uNn&ze+dzdZp@oM^#@>zP+@1rFNtKnbKYt(WWiQU8gr7 z59W4HL|5iL7`XK+b`T&+`KKLi%@nKyy17Y(=a8eSC2($LJ!r1RT#`!1BTABUzj+W8 zW?*B|DNC79MV+rrziMhd$q^n(&KG7UaHx|P(J|Yj#8!fC4#YS|*-Ilzl4a@UQIM&% zBC5q5Bde2co>T)L|DTb_N>zp6chJp3mEm6;RaGBXzBx@vD(x6}sG|Uc4 zYi88ouNjvahM5Ax)LI@jC|D(i8LwD3M-2*A&@j6y)`L-lTR0#tHOx*hMuWSf1_kR1 z!}KZE`%!~}Rc@HQ6zjXF!EWdQ)_TL7fLf=)_UIX^$bxl)VLqzd$R&~dbRWM{dW|)sC=eIcq zl~uui#4vABR^M@~DqjWvA;U~U+ob6q9Mj6-GKTa;!`y@JLw;wBwZgQrFZlaWy%?Ry zA3;9DpzI6&vxdoa8~L-zXDpQc0UWzOG0e5dm;7tm*cbeN8s>`_t;xT$jeWs?A1x1U ziTrJC>|YDN(Z9^?;F14M8~cL)qha<`74kzH`-17kD-G-z!-DTFHbx`Z!sFq-rxXcY;QEOjRt20Nl`7U#~ib>efQZW(yc~Dg` zNx(WLrmfra7nf;Qxr(91JkKMSiRhOmL{_+dp<2wORt8j@9^epov&%dW11Hs&w6dd_ zg8y@u`7lN-7U1SqMl`b*d&E61GYLI{`hRSrFZjQ4nU8@_{g>M4??+FurpKGN0aE|V zR{AOwLZ~F(+=5E&kJ?Q~rqOPz#x@~T9B(dF6*Q7U%rg3=nL_9 zAF-0vk1S@YnfzrSYj&LJL(3s67}XN2nQ>-k#VU_#m7(^nC2{6?@RS~27u6E1%j3)o zz+x7+N44%^S6Ulqeu@rDElwSThssUCzb4MS1aee;%TZOn-UHnFWt=$`g{J;)(Gv9~zqzogU36;O#-xFufP+f6WL|?{gDsbzmIJ3$r zbt`?f{t-fdi8G%>HBjx|Rz{T2acnPGFU6VT)qwqX$C73W)^l;@uhppbmZPtkT+Lfe zappiZ6nquc60CRP%%dPNS5~Kr8uyy5<8kH-D(VBs5~UVf2K?`)n)Ml?3aeC|?5N5u z1+xS+%ZfMoo5@tGj_At;o#1Qn=62j+E_*Lx;ltKWzZc@_wG zljjBj8$CSDZN%T~`J;dvJi7(F#q*hfzw{*H5r7eYnhl$N=1;B_=v!hAH$Y7%Ccd!aWyL>?0WMBAN-{NVR9~oivvtp7 z@TKKH=RV%dk*Udd>#MBo% zS#moI`6Ud4w{b@N4XAePMe-4UoE~?9AiC}b$hTblm(V`8skj8!CulJMhY9@FN4O{Y zPzv~OJ%vX-qZ8bT$O0BdL)9nJ0kaQAS_q$uIJCPDU!Hq?Y_IKpgWJF7K0o!_eFQc8 zbnH_jC3>ae#7rL{W@fuvEcAY{(-7Z`A!%}$6Hdc{af z@v$PAptUn0kTlMmzBIQB$wK$vPy{!3QRDpa8$_5~f5YGqXSv3r27Kp0D9-TjVoWUm zZW!*gfI-hK24ig8@bp5cYKE_;JrM~)&Z`Nz)k(;mO+s#D5^~>?klU1oub0hTNkR@y zhA+$Jjw2!W7Y$!;o4bjG+&eUUeQfR&5^`VA@SSIK1CWqgeTJ{E&7D0$ZsZxhem3{* z2)RvX`1;%2l_TUHoZ%Z_Z&r}oYlbh|=3W{hH_i-Sj?G;%LT-wQ`ZRn4?F$8QpnaKu zgY4@R{EdKv?Y}F?eJR5?#O5{>A@`iz9Ni4xP@B67c{T4A@@2AU%t(a4MOf>5OT}H@Qt<~RFIny#JTfe_{P}WW+3FA0wFgL z3}1oG-2y^x4G?l4!0;8?T=Wxig-^(pyx|*bbHz^B8Euk~D?P(E&YrE{H45G-V9?&C z;5!QbAYhT*8TVJiS7eV+aJGQs?Q0agQ^9QlPO{%okSj*RH`(U$kdSLZ!&hQ+;YY|- zp5dEfb4f?Y^_$_FYICth$d#Gln`UzbM##06;hS!AX+_9Ili{0TbJ0Y|6_Vk*$mVj0 zkZT{qcd^Zd4k1@HhHs|L)e9llDTZ&BJxReO0$yU@tl%F7ywrY4L9Pc3-=#LE{Dhp< z6LR8i;EXOO=!Bez8@@R0VA*Y{)ufpbBlaLcj!&hl@7D>n{qv4xxbACw3$)Mp| zU~|$($jP1ITWE6g2z{_pUuMFSiHm6XA?+TmqB|=V)4BsN#hoOyd zfPjnb$qH5rxWwL|Ag3jUuiEAugpd=Cl%Jz8ml!rj*)q%vbbe{>`S>1Z?uCO%rA9kK z3UFc}1ri^@IPcF8%Pvkc^w%*|Ybi~jUasqu<)lMVKLWK{7jrF6K_oS?A9`EoU10#bRO zl5@S3dr;_mOi^CWbA*D(OiO$d?WEmOfvg})e6e7X@8%69xlt>h&=sCu8g^|Qblq|#eRTy`Y_UOW=^H&1dr*lfBkAT-&;!<)~h1ewx*=VI}U*YCuD8;DMe81APdBan&4}RSHo(% zknsKnQkj)5QY?$+?txe&a^P+^S>(fck`!W;w3NHSnrEKFn?I*cF;k(G2f$jP3kqjb zD#OcBl}Y>4I7Q&xs;!%eUfk1?Uh297e9pN};j_^vUE}3FiF2_iUrW3b<4@9>RNlLa zTC*mMgjT1Q5up^{&#+)AW|vDz_Do!nqot&@JC`Fuhr6JY)Ek1G_hVq~jeCAl8S13l zI5Zc5-GcF{=LZlaruh~^{@e>t&HdhVGzUHaPDJzkV~9XRbHu+e%zn>??7N4Wl`u3W z8P142gOe~fAXnr$@h7w{ficgiFF;9ZzC+C=(40BJ(VTM+L?W8=JSbU2bHT-kh4eNJ z^0~_^uhf=wW>OEom#YqWM7isTX0H7oB3 zzu2c~lyi*5Ij+)q9m3}orsxy$&Fe93nwI=7%*FR8M6w-|?jF-7qVpmZ2jWC6mC1xo z8seF1{20J<XpZ^x%53Sf* zS_!j=TY@&Yrwyl^9QU80`B5v5G&$))^qo|1Vj{{H4_b0lPUT~_kmWE!AQTSo>)?3MDu}=HNT(q=X z5IDWZb`)(_#MtRngmj;`;ilfj<{PW6g%GPJ5ti%$u!&EF1e$*5E9as`f7)Bq4rH)= z7+}OZf$>L4>O-qpAR%kbvr0QKjD&GO@<}Ms4iu0uAIMx>@my*gm`u`*KyM%^3|9_Z zM$-L2@5a^Mh3M2FTUV9#atbqj2Gqae(%SRwlgB0NHNpB4)PLd1=md`Ia_#jFRN!0x zdAP6%`AbzImc!DgoA>I|Eqy8gp51p~OW4jp;1ezKs!Ubn{i4X%z|aa@qR9J2k?#h2 zD=rjyzbNv1KwcrCMB6Wl+{wVmiYw!5m_|XK6W*49QjDvMsl2+R2fdn+be)zE$V>?I z9F)0S>kc=K6(CPBuAyTc*!W6L@sg_XccJ#Toy+JgfY~x!aA{i(3G0EZC84}}g|=;k zh%itd3=s9Ot%#((KzEQ-jP|x|CP^OxZNk<5H4WOx1@8Y{xc?KV-{8{PzmKnxlC?vy z2BK#B;>!3G9Mr>3Q4c=@WeqOW!=F_FREbdmGf+Z+nJ6K9&C;Hf(=_LGE&a~pXj!6! z<3$O%-h3PvN;qDW@Essre2Nl|7bP?;O*;Y7Iag^Dsczn~@v5$W#;7&RZ=k^fU42eT z=~Y@;JArMz+O)aMR%cb*~d#%1klVpfSG^ zBNOFcOTM{gJIm63KfZn?{cjZhe+BY!Tmz2u0}CHzL%W7jmut6)_G2PgKhi)KM@&CY z`VjF@YkxEN`=#xNgzao-W#P)W9UR#DgRpfmC{u93o8|cWUTSO=8p}XmN{u?H@h72i z9Vk~xjX#2(hW3PN`is!m1o}quvN>_!Uc-~P1o9dZd}Bl)N09ggmv<5JX~sQ}gcXBju91Ap;>dLm!0N&~rI#-LiGHrO&i(39pLNyvc|KKhp#F zr(IIiSe_2qxLek)jyo4AF@kuI{h=}mYh}z|7{Kg>vMceU&=XWQJ%Ama0=1h_Y`F?cE#X(Rej-ip(-pAc$K#WHQg5K_(sr7N!Z0%S5mOb|u_J)fi< zusC8Or7i%YRm75I6J-`&6Q`lWRfm3!y%^q*Pc*8Dl`nPit_b zhC)KTo!XPOnjBkBf*pmQQGK3vH1eRqR|2G6qo?5G4Lrcno&M=ajfX^#Qe7MgPVv}6 z?ltdE>5s3}{#Yz`;Cw`!Km-s6{s8qmr=SPNb6D$<$v|BKLww}His_NVXkG{GDnVJM z^%z0QCSbq7B`T)JIFkMf^f8iHF+HY}^a9X*BrQt;shq~cK$~z4$~Uq4p^%+`2_7z2 zP4z&nmxy>bpj~hc;=$A`3JnD|kV2d&_7*}Dffka)Ic6V0S^;zkNvoD&*O_|11@z`kka zkQKH64@exMl&IH_m6YZr5~Y^bH~Usc<3mVuk6iOsC~4NhQ(&Xk;%+&4-R~0mTlzeg zs5;HtpoDs%SAXaTg{2V2og3F+&@gXVy9RdyC0Wb@!K5%JBsK3SRo0IJh=}0L5c3py zrfywRfG8Jj$O$u1ZNDcj@^K*Q|5I@YUgx+8;&K90(}Yu zCgLg?L=_SD9ZFPl5?*ll>E1U9LZYS?LFIB>T8<;cm5DY*tUWL2fO!N17kLEKtF*KX z&xTT2B&6pdoyoK|^*c1CY=!tgc0!7 z@?+SG8x%huLYkFHWT<-+(h1fby?~rA5Wh7X+ZJ)T0!g<{;5HIBOdtX4nk*p01(IcT z4gk48AlcRlA|nKnYgNJ1xRCvnX=xO{<>SY0YOLSV(ea)d6k(P1H|k7mHwDOAYa;Fqag%(Q zjcYep4>Hrq3H--xbyhmXrueFX+-TiP1GAFWLTsb;Ibs@jX@}L|Y_cxJ^TD{;8FfH5 zTPLuM5;sS7a296;E;|tBzjvV3Pqch;%le-o@82H4_fS^C6fJl9A#tI}sbMuj= zdz>p3V$hjnvdb=w=uA#wTIrMsBmuofJhyf8@uqu#m zC5pcl2|e*tCoJHvJsGHWBk?ZJZ~-@a zW(#<)r&_@KJ=X~MJI@9IAMiXP;1{lyR?r4{(YKD;6J400e0c}6^}T-vK!UgYxE2ZHF}c4geDmB3=B0!MKscR2F8|W zU?@2&q9QrZn*m+Zs3TsOX9BZe#(TRw14AY8!o0{wveX$E3iE-q^v%WHS6iKdp|E&i zUTO)JIs-#3@xr{ws|$BxZE*&Mq9-HnNrpHBL&0Q>ekvcHfw9#Y80zGZ#f1KRXL>LA z>I@83r#PyL&oeHzIs-$sD5PmSbxJ-;TafPo`Ipxw^1Fzk!N72lY$kDY60yrW3$y67%KHAiwVsoSn3Q6wThxz zJmX@kGcXjcaI@87&yXcXS;wv~*1R$(Sn3Q6S$xY=dH8F_MV)~m3qJ$n#6_^w z85pw4q6P&^oq-|iny5jZX0g>77_xp9H7Ho>3=CP1MhyyRH9cxju+$kCvZ|v7 zd4|PSXJE+M;22a^1z(+kA^#D_s`6Fv)fpJ_4>+ck!#u-ct1~dq(gdK7#dWC36?qoL#<9^F`>D5(8X3~V5l`TswG(J3=D;*M74O(#a3rv zsI@4nC0ObV47Gk1)#4c!Tb+TS)&q`~a#Qft85pYWbyTIVU884UsNLjfYl0!qz)SnXiw9k7bq0o7 zYol6%rOv=m>(@~&o^ipegW?Pfwf^R4DK`aQoq?h1+m5P=N%Ra1wSQ`*ElqT#h&%&B z1Km(Kp&R|uTn}&vRA*plC!a!0C@%zGoq?f|vQ|bk7tgrhg-3A)hHBTh(HDGm28Q}~ zx6$XJ6kDBvq5hs$`pO9*q|U&ww;rKTq}!^#D}>Y;80O?h3y79f2F)de)EO9NmrbFV z;tIYx14APvt&C_co`JE|85rJ>uWgUR%c+C+1*hs!BS^nnBlgl z77x1E>I@9mR&PeN1WTQPA?tWlD-}j;bq0p4B;1lz7zIn6fgvl4EM}^?c+kaGXJF{z zn5dRusWUJXzAUQ6gD!ZBRh)sL*6OI1V5u`O)cR#qiw9k7bq0o7e5Fo#C|K$Y47Hw% zYVn|ptI@9E9*b%TmO2ANt(PKNgL&@5*V(0YA1rtG7w+#HA&Hn&xyPDG-0Bm%k8O)r%r{!yc%!wN611aDe^09LkSQ&G6Zw3n)%~YrMx0xRQNFa_f$y}s zAMZFEd~PYW<#*#dt!}*3%KW+4CZMkOqNkuDp^KD^PAY75P%pJob!j3D{DSW;{>%PXz&PGq8e60gtp>?lGWf#4)HOoltWs7a-)bqSzyE(PLS8NNX4wC0t zQU}{&TRL^9{SF#iieDVkF@SQbmXJHMgxrWF5pbe?K)^}%=K_}4Y+**~6q~!*NhiAFwHA+_`XCyN zdjw*YHZS9HEOFdNF({>7k--NY?n%&0t4XZ`Jw+ZwbMv@XhkJbtzMIFjI^5@H_ehaP zn^NRCrWAROX(Z1vd2{~>^~v7h>3dOL&B*8};!7w33n&5$C;|&80t+Yt3n&7c(aS!- zfB|wJ*~rMUxob?wJz^uHx6K`4Lhk<>8GUT-_7ZY$*T^`}<|Z!TP67Mc+?_Qt`r6!# zH8T3y+wzqGD>VN-U+!< zH!`N!T$U4Z4Q^yiwYlIXPEsIob+CgcR#$hh3*9GQ^QU?bxSn{!@5PH>HkMK))%gq*q> z8H;UBQ3*K}H8PgioN^L!YH4It+nh%da?bpx`~&#^dQ4IyXeIYhE7FYI>Q<3G>?>tkyH zhVqVkg;=h28Au)XB_9FEvpV2GLC5{coqOVut;NhbKG#0b7amym)4&Vfso>1C8t~om zU|J7w=32Lr^KyD0APX%IJni^OhXFvAT5-s_;~U<~Aic`^JqptC&E(nedaZRE9?Wz+ zB&^+N{f=U9wev%4qvh)k^mmvqNS|Ty_4BGlJs_*>#o(k3&{0J?v1+l zP3rpf)M_}pQP;9Kwe%ZR{#_`GRRF}eLX=js21CMFltM;=7JnH2y36ooEH>H7`tHM5 z?{s6iza9xTY|+S#8ZQ}|bpb_dg(<)0{uyY-3iB-h_efN|@kCk%RN~LUm(4ohrSnUR zr+!~1-Fr|HKgDJrBS_o7~nzxjSa$zM@& zKC=6rBdNL5nBBHCzWEmaSMu2p_eA+)v7R=bZvP7T45M)8h{M+@t+^jY*D{{*o}kbV z6k;arVOhFEA?40T;2Jx;-N1|Qi7z3^SL;r3{J%Id?ea~aWQikL(MnQtA3>8bcKi4q zVtlP5#Qr7C1>uI~o`~*XJnOraLU%YqY@kv|*p!k1dbiL23?+Btt2@Ub`TmDHj3#C5 z_rFaZ-#P8hkw}%Qh}H32`xE5-fG-gwjuSG6O~Q@ktcmB_vtr$w&|Qred|42Q?}slD z2970B1!Z~=vwhLWfVuCZ)=TZ#h}_?^)gEYnIW6!NdV2%RbNozb3u76$6U#x=bHtvwoxfG3N5M zlM6=%ojoX;mFBiMVSlrINATji;!F6$!bwTdj;8cPmpA4ZY3vOby5=Kn#??kRfa56; zOt=bzi8gfu8swUU-t=Ef`V>54jbY}2|9@C}5BRu>t8M(2oh{mxR?jp-x-oY0GLAaqCw5aO7Sm^W{NA%Q^Xfe;dUNhl5k!VCF7 z&zYIMtF;a9|NFlE>E5|Br_7l%GiT1s9nGzui`$H{e))N*jk-mfmpNtq<5I76_*RZn zHbC3Gx>ZZpIAsHMCk+jyff^){(okoxE*m2Ima0Pkg<_Tsl}MM+qqL~Q;;hK}(3!}m zYI*2`-Vo zxJeUWL(*E4Cu+cnq>vaJ!hFW$&nJ2tZZ))J0jd*wnZl1N{uU8-;U)^+n?{nS2Cx$v zC(<7ZJfX@hJ2ihHI@))^+_nm2 zM(8_auuWLEgnmxhPM64n&|R#JGbD0q=y-DbmPFQt7P4x#OJrLpLY18<+;)X%9m;k{ zZCnug8S~jGkV`{7$?Ytmxhmu{vRfkiLM`ZHWoJv|w$NS<#OFxlp3q$C;9M!`{?Ogj z{CNU77+OtLoiC9?p|2?Q1rm8OG@q<5l*kLAhspXPiM$%BW#l^&c{|jXvVB(~ABKKS zZWl}Bvu^tUxkR2Fx7)2?y+=xbk$e=?`+b36B!2{YyG$abt`l2Ku`l;;Le+GiQFdki zOrX~EL-L`p{4V8T>$4H-$DbpBshSWG8k4iEi@0hsM{vwCv{m z1QfZLvVBYmZZWbgrV?*8vJIfBZcA}&!3dj2&EM`ffF`z=RdQ$Px9}X)-(1{V@{uPVDc|8C^}Dw0CSv0OhAZ91VE=J#W*+E57#d5=W$Lu=Teev-EqB&AO5 z$CUnFe=lO)^ULnfe-N53f}0h(nkD{eQD-RF3H`1Lkq1hrA%cC453x3W=D!b`2y>3G z<3(5>5f(f``ugX9R8?LZrDqqq9-@_ZDWu=*go?ndylcU007OH1uqfqq1+)?Qp^L!3 zyk5{soyagC^t})YiR>c79?({OMLeGlVQ3#1RwTqDb?TNc-Q-l{CVIm#MC&#(l9w2U zNPgXtwTqpKr194;MboXw*Y)m1E&`hfo&MO%lqaQ!G)i6Gqk>sSK47jVq3zaJ_R1gI z8@X~WP}$qpZqgXYQ`wN51VDah9qO>MPaf@KX^6`_m3?zrLsiab1`(3S$g8rS&pr9| zJ&8mjutVaPW`oDd}`&?d>`crZH9g-k1IM3G*0Lz%>Vc# zby^=%U{^U!B7H;WqVH5r7h#5m#zIq-GxEPcVVXjxp;9YnR*>1`&?Ah@%BQ0-BXk&T zy7Gkhc@VZG)X02hC+J-)a3U?pF2e2eVvMWtpc~_4Na6Hu0+&w3Wq*SJv0{{?B3jJ7 zwR+S{Yy07s^d$^tM{Lv`l?y_`CO)-q@Qb`jH=c0+>bd`_jU98AcJjS z=R_v~>PF8(LA~gkxckuypf4x-6z*%elOXjW>}uW)?;z%Ov^^)f1o&=LA%D+_ zy^Bn1J}%yhwA_vmwPuN1(hRKJSx`*PtgU!fVRXg7!yjuxV-Bhg$47LDGAdn|egDLK*iq5pXFdT>re?*(mc zbSn7dMZ-u>M&Cn9esmc)6h!X>&%)>&qLe$<2$T_knW7l~eU92i3%|3;+tPM>Ae zH1B*0X@5bQdx7CZ*8{> zj2m4iRk#<*@uDZNu|-Q!z)H3GjE_V-EALn-N0#^NJA?vDHZnPDV z_$WY5aLc}jXD9BU9%j4cS2Dx+Hk4|v8@~>bd?)wkP($r>H@OVan)SH3yg88)+;h7U zIK%C5HX;e8lbu0eE)g6v;dGe{{JZcVd*b0oUPqxWaEpJAH0i64<3YcAA*z$x6D6#@ z(9Qc35!n6?6CvFdb$`tLBdV$P+iue756QaYrdhC!W;{uhJPg%SC|&KvZgMcGW~8Z@ zvAF04trp6xy~ItO42;A@V7a~>s*`&anp5qSZr%ev1pXAQt@bK6@7u&?X1AxYCI563 z|0MukxerzW{~9;>Akb=FZ;vaIWEDcIdN=tIsqzQdVrCI&+(#(U58b>&qra`dbw0fMSL z_hWYH{ciGIpx49(9U+kxkWxCiqfqqP18%Yd&}s&yaoZQcWp-%8RLn2j2-?$gZl}K> za!WOHTo41qI)Y&vRH*YX4Mx9sP1Zb0+7bdH2I1UX_ ztg>xni>deWxT_qiY-?FnJ-p7%fMS*HFrhuYn(2rxaP!`W=(WAP&a)B4D%+fTMEiSE z$aSvMBi)%sV-(rJ+mCpoEr_t^MrhC?Y~B&J!Y*~l zhnFz)uzJPB5lG-=6VD(zTVjM|i2RvPY-AC(p4>)?JkaymH2Oy%aQ;a-J8@3auhA;QQrzmC+443FRhL9r7FaDLP)qCi8%1pQ7k zXo_EhPVu-#n;btIqCVk?<2nPwCF|f1o_`0Za-Zh7{gT&-vPCB1HsD&cJpWrbObn5j zU%wk=#V;}$w=Q(N&q2Bxf9$&+g8yrIKk$$3;uoi9hV@RjUI#NvbAa5skMzNmw7>~$xA6ah5j zi2!Fz1h+6xlzE^Xmkd1NEXbuiqoyti|$ilEgfuA;4o92jFbI~`HW{(mWd z)(F(lZh*!ErwLb1%UF#w5)%73bz?iCoo)ukqiJIMq!EF3NJYN`Mm-+}TKECn=77@) zxOBE3rYXBK+b5L&sLhs#Z1L2soKv&1-NI}s^K%B^rk@H-zW!q>QrKwZ-vB1-$moru zFiKu&Bw#1$2ND!4=5GOa`6cf)VD_)M8jN!L?(CTV{WQ|+28kVXqe0q2B)6}VyxQb? zFM!ty5VW@~()@jQrb?hf@SQ4Kn(sin2Q1z$gXbg@<1_`?ykfzh1#H|=PO>fo=Sz#T zZLubFlH)SK6=)<)2I{4Roq?Y#(EToNhXH z+s>+YE6`8fq7$Hap7i}=TvZ=PS~=6+LHy55`=_MUFs%kwun1Sx=aSZ)X^Rk_&9tv1 ztuNDVL;NzPT@UA>+Rdc}I*j-SOuJFiikKEnVCIIa>Q+fBXIcf~rA#{+<*s&XnAR8Z zUQD}7@VYZ?JmO8b2E5Z9%Byi>RG+`+eiRG|-CP+wTY$iA5LFwY`Fb~p|BSE_@#VOR z7NDY^XweynA|64ai^Kk++Ry`-$U+KxUuO?M)ns# z`Hbam@f2nV#&*01*jwa2G>iN8H1~g`xnD=_SGuvgE%&cL`ESeJ;whZOWVjdP!kNI8 zQ=i5COmgo;y?>tOZlBQZ<>y}I#%jlya@2rJ6|OSYfyGqmCrcw5>jk_X%r%0J%Ac)| zos39*)Q{pLO5@zhGM(VY&aycT1?50oQri|UBzVGoDqxeyy`@Q5q`3$6F~D&5oO{WA zwj2A4<$ek%=UeU;PYIrIUk})7a-W>VUFt(LHY&~CKBcrEjyuPV%^7Pnwi{e_;S!Bm zOy$@oOCz~{2Y44T*O`X5)tJSa5+BMUW*h5tF|?AOCbmzodGd2_ zbk%)e)bnbf>0WS~L3SPcRBDl%+{*6bO`U#%9C=8x)TzY`9YG_y`48~Eq=XL`-nLFz zD>~PMX%X#{Z58eqH+F-~HI@gD4wvL=F_mMVERE!v0$u^GoTsyLmEIxk*Ft>9K0!+P zx#Qf}Gd9;saN)m?X;EKIi)x?pEzuOWvU!40P(29haEYiEQ#tm@(uk=2f!7yT&Ofq5 z6$Ocz_%NO8KiL49-Pmn5r%|9Bj!Vph#ZwOPg!@dujwkn_OVyRj2&u3Nxm6E5cz zTIu{T8mG#l4sk1gWl_%p+D=>|pv82Lpb-JT4ZI6+<}w#NW1rHw&T=aU zO)_e^99+I{bG4Z22pY-t2H;)KT*n?Q*W}^hx>%g|Yz2R~$T%f&wm5BT7it(BS^5+{ zPlUSwK?|KM-);5xT(uLsPTSdYf<1F@%B^{HaL8eVP z$tyCzPgw9P3#2W9x~@q-k^1izT$-jnF9V!trb5~=zuJH)Q+EO55K1C(*7mau+R2u- zWs%Mga+{9AoR?ehESq!3?FRe;Q@Sj}?OY(q0ucVc^f?S(FK~J>V}Ry&1FRx{?se}@ z$I23?HZSxe0{_A1R$R55+q^J_Nxw$)AzbC0+`K5W8*fh&V*Q;LWp?B3nT*%~=S7*_ zczb3Pa02runZNuEgfHVN_<%_=eesf9_(T$?FMpER3-=S(;VR&)PzvRo?xJWNT=m1L#`s?boJ(=#T!7U={;ZWt zJ2gKs#GZ2wiA!AdS4+&@%r}vETNd$|U?e&JB29b=iA!D8={S?~0T4bw;#0GTw}V*x zl1I|S_6ZKW{M<5EO$8(Em&gG4k8~NYVNUsO>~`kFS<&OjZll$*)Dz>P(YH{1_{@&n7=;wguC!aa#~D2s84>=sWs#1roP|DSqtpPR*;1ll7e5i6y2P&CLXl>A0Liih0m5^PC4!xPQb> zwP>dRg>`R@FI|%LekQ#Tz6VhF3$1iIUj@cY1L*) zH-l_FN$EB4XUj^{SHX$xDQQysWCxIE)kR>VhYztn=NVMj`4YK25_^-maPYVQIq-i! z#rjyRkYI@=xE8Q0apk;iI9Msf7z*$2rp1WDyEqgZdxGKpBhc{+IKtavDTi3X`(eNy zBJY1?@fIs1ye~`hPJ!yt*j~%~8PGjxd0Q;y5KDN!1=wrk&DD1PtlX?KZIQ1@^X>$y z$727sy#EclPc3hYr5s`jZ~pgB3|CGni#ID(^WK-{-5pfFi_M*FbW#Jl3S6QSi=`Z5 z3GY#W4JGdvvUI{)*8^T(ldJ34C*aF(P3$q7&s?O<#wFI?;)RZ&kUSRvkN>%pGcKz< z!GLEWzGI*4fVVF8rOlK74SOmst%4bbndb~c;kL$F=NJ`i1~WjVwMe@fm#DzvDaSrp3d!?k#BRcsvnERg(iCOPw-Dd4 zPq6#)J0s@IHD%*JdfiRV(t5Y0#T*Y6?24Ua(S8Ax{kTL07E3wA5^??j*za)VEIOJB zg!kEL-qS&KR&2lJ{Ws9PVtHFEPV=@;=neAQ9qTpE6g6A~ zyN*lLYw?t0pDcysnGd`?Tsix))GNJFyKx5MI~FHu@;oQjX7elqk5XJ(y|<;sW+=QVy|1oZ*1+U+r?XXQ@D1n5g%@H1DOLx+qrCVv2n{==jg>!rNjg zhgiaU0bnPQ_u4Gpfl>Qqn)f3X12(V(aA1gKs4TnZeO{efolLV)5v7{c|DZJ63Z3!q3TFULt z^s~yrDdbQ&?PY(B2IwCkB)S^QE*$bzxT;v@U`piy;>Vlv54m zQS$6qJyeUv4GbOa7%h(I_n~$Ev?Ch9Qxl!as=kuy@Mu8(-0N;T$vC1-1Bq}qD)e?- z;)phlXVPyF{S~hAHk@5QCP4zu_S^75fiXooHo3>RdTgku(6Jdk4%Q%6r(-QWwsb(O zpN=hnOWMyFYuwrWJH;m*CqC($$m11U;zy1bKayWM<45Vl3wzDT?mGP;{XDhyMAP^S zfsuzRr>UPVm2HSy5EXyuT|??Q_Q@{vx2kKvCc_`9Gdx^pByyP^`;@uRAL@!6s&Ps8 zwpby-lI}1Ruz{3f#!;kjlBXFF*c}E!g_#SO_bt$JA2~BZU-0&{IK|&J)RQzNyTTo| zOk12al6usx(9vp*8)A}HY&MZ=gb1rq2TblxNA82=PcIp9zsY_e*(D?Ht&wex3k=$u z=|4JP{Sl#(uh(cnZ$oLIT@EUq9SQT?BvplicBkNl2%k?TG3=_MMb6+ z&5(9eY}$>?d+;XROoQ&x&8UMkqw|mp_kGLMrh`mv9zgUCCUJ&RA}#ARME}Yp&QMBZ zhVlmrpj0?F(T13s+A40F7ZA+jc~S^n63=Vbd~RK&X;a z3@QJIIfqwi7HPVjelJaGpRC{BsK$a#Mmv2jE#N80rB7@xb74EJMh=y@q@7x-jhH#&hoZc$|08Uo)6eu^8Uhbu*%s&-ZGl^ zHM!!|fq5z*48NM#nl@90mEf@gm-bN&9$p+|QAnPffwvJ?&S(R*c}jVb+>^*3``wSg zKeOLGzd%5G7~=SYVQ4>xAz7b5&ztNN|H05dtZCWv-Zx1Ygx;3aqxQVw0;7X30?G!f z*ey;C^5)`yza!T)I@-p^-EAFh6^dD(Xv(O~Iyb|`*t_=i(FNJ61DN%m3r&xV^(4Ys zP!RuBUwUM01d}dD^b%as>2i!&Z;?)y)4>?)f-pw>yaX-59YDPeSMn*77Zv)E6e4&N za}VPDi6Lu2$-F%aoR04sijg!yUz$icB9#yl^%3(wz=QlcmKduh1#FvJ4ut(mZ;j(x z*@BIm9RGllgGa{g0`x(}vW&a6v*Y|i9-U!xy2HYHTrC*Bb{(F25W^YPR>J+eoEN0Ni@BNHyJXVScy=Ps z)Z+G!D(p44pL%c(_uzjwxKV!Fw~u_`;bT-3f4lHXnLqnAuj4BCZzG|1F=gt@bL8`I zj{M0O0=sk%od6rtrALTnwCfLH1;*SDx??_*N) zYaqRe>wWTS$jIo2kcB`Wv@u*7cw|PdQ}lD76`qS*Xl{&|R$hbF6*@1ca+pH+a!w~y zrK9@i=JPE1u$(2|1SPbAtIG#R1LQ3E;SgaP0emn3IZHkT#61M?!2ske`Ob*nK>!~N zK+ckHK=juH@WBA&EP0-w!DSzp4+bD-$vQ0lX%eNtaRH4$^f~aPIXR%2jm&&~4m@eL1~dZE=fIOjHX2DWV_c&1^*QjQ zxyRBN0R^njfhYbSY-UDDJnr3>bKpt*wk3A*1t90Zlgvd+)D*eFIq;+?BY+Q%0Q5QV zq!&VeUInbwUc?wfPqiT{A5 zc6vP~q)0q&FP($=N@T3`* zrtx{$yKl~cC+_Stkp`J_;7PSMpyFiCH|M~U>Jm$3szTuA9C(uc*piz1;9>8+IR~CC z;W10^_yRKLz!UTaL1G~_$eaT&?FY4L81h7S-<$)_ai*LgDZ4Kqa}GQ~{CJyTC?InV zJV7%9hSyRr<{Wr}Rs{?NWX^#n==^}8fXq4Y1l<@gE1a8iOC!GJJkf|Smn{(g^-<-vt8}WQ|4m{zPXYm)fIR~EbpJwqFxH$)&@Mp95 z^F%V=oC8m>KeYTEe3=p;a}GRfEDp!l)EW{igK*bYYeRB>xsrY4Ulb3+ZIq;;qJD_@j?be(FPb&Gi10M{jz|A@E zB>lT3)g{ag&VeUU7_Pb|6o5Vlo@AW~-~%#a>C8Fsq#2&3(I9gUJdx)FRDY$M<{WrZ ztqZ6GWX^#n)wcsG9`^2=bKpsJOF$(ca}GSIxP#qD$aCI(a}GSI{%Wa=P6TewfhVbp z35<{$odoB=le!C`djWYOdOx* zy!+-Hc+%gRMK5r34m{}}$)e}M>%KV$p7igxqc^G$By$cttr>UL2Hn=!HbFAyz%!@8 zMB+nmb9_NE=fE?&xkTbaW=`fDc+ztFXC^(*fyX}``7;r6K;C2N9bZ7^9C(86vZRjB z!`^*!4m>k^B%l(IIR~B@a_5$*8XorUn{(hfFZwc|5|B9uo}f}V1BR-I&B~kuPtX8@ zn5p9n$eaUD(6oSxhrRpe9C#wH2&e>P&Vi?d=LA$d?A^xM{njof@IEtCmA=TXdxIgNFQT)!8hl?lhe;EC&w3%IR~B;f3)Ive5UNZ0nZq9)x>10c4;5-N3H|M~U?9?>9 zINZL#orr%BgDmMUNYiUL4}15`Iq;;v$kl&b^Muh6wNvCqc!#Q+bh{@r#k-MRvt`n2{GbFTMurb6(`a_(c+aCw{Yp-;ML25-)Ob{3!`9iN7V` zo_GOP!@S64@!k?%5g#Yv)$vm#ye59SgxALRN_c(zmlE!azarsH@sA|DIsTP|x5Sf` z9wFRB<@*dd5 z0sgWy)&OLeDROiAJ&Q;0O*Orz#yc7gRv038!&6oIsOtW`kVPJjL4O83JB>g)%jp{T zB8TF-EHA`$8D5L)GQ1wwvcD16vcDDAWqLc#G7R8x=#giAo`+6)S@F`#UdS&x45d=~ zTeB(}xs5{T?`SIhSF?!lKWRN1*ewqPa8GqX5MD`fo5lDw>Orit$R$sPT;XKM1x+v6Ey49mhFq=mlJyC$O)}(4q?hcT;JPD2t}=Sb9to}~GUN)P zm+YC~QXxYw3VO+2_>Ptix#WjK3=&-7W5@+PFWHdb`W-{A)_KW339ijCX1upUb0_;>uC(Rd={r3y=4Ey5J~Kxm?z!9k(V5n;F1tSE&zGS;R!DHFy!Kn zmmHDcQVv6|+jz;w1Q%%-az(~Vj!tmpg&|j17;-tqOX5FcVW=5$p@bnW(&&WcV=n6J*%A(gI6VBXy}B*du0M2E-Zcq1$WzB$8@>J+9jYwZ=L_{|x7a)u((BN771%t@F} z&M^C{36dKNrr~i8D5*cg9O5f8q^Ad!jns`_nVIO*sd8Dg?7}qi8#B51#thvpU51hT z#!N20F+-l+_>GxEE}buz?=tbdO+vRM8}QtNsUi@cFbpDt1a}$d{-l6Kq>C27HTML+ zFq8Y!GLH9j-Ll~+Zo0zL3Fbs%dtjgH{t8saoT6_7zl{GB)BE3+vj44s zq$!7d2o0nu8);_$$%b6?8&WO>qj3WvjO00a8hisnCC}r(LhF(k^PKg25NXQ)ka7(u zTh>_0lWzn{nsQMbB}-E-p9eK+X@>#7e&f>h&YB7q6vw!)Te!hlTTa6AI*Wi}md!V9A#4tRAxL(4kaUgfGcSSWk?A<-^s=cl! zRy_!2QgFj|c#NIfK7!=sRha-madLhG+VvOXHtcB7ZpeD&OVHQ6qe1_H>RPw~g0E`_ zb#l&wEUmxB?ZPZTA<||y^n$&}0*pdSnwAsC{)sHWHi$N1Dac-I2QbpF0d!O!-2Qbm z=qzM3?0rCs+o{CRE`|d8+>as*I2!adWZ5+W+T+?mv6~KLm21%cmu3Ox0y*U(%N^|j zV-_IIP2^kwjv4jh#A$z`e?gVq(~Kwl?$iPQ8>a>)d=CiD?!@Z+Eeyafa1}H&sTY&} zh3E%Ns%Fw~CUwTk$P!#*KSh#zPCl7%|7zqt!~cP<5FLpjoKtir?z6oe*emk6fsXHn zB_9LbA&flR2rw0pnHZXhAN_tL|P18A| zob$o2-~kY9lX6ah^rLYVJjf&|C(lynhaCzIGD*sLBcj*f>ab#FKj-v(^6>ZU+Zh>Q z*uRfrhLG64m{Sb&BNVgVK(mW^p~2bG1@+#JLr}~+4Ng!@Dn*LvJ5lzrT~kn0{C4U9 z)k%Kg4LDzMeT`Hng#RyGNb2vb@57{55q&`?4RF>sGAW9!PB^~V=>WP7rj)Pl=m3%p zCA!SJc6L}lz}e6#t%0AKoO!ft1bIRO_^0$atm!k6@|z5BT^c;wHiV}Qn9??DaJreW zlDC7!D+cE*>sblQT9#NN_bTV(8U9wN}@G(C?LlqR#Vl8Akwp?X}>WEKh^o`yaPS7e$YW`p2C z+<~wgOPyXP87Lb>07yT+&-~dnTP6P=Aj-4vBCi-? zl3ad7{_h(o``uCVzYzKFGDw5cUyywAQCd zKhs*D*2B`!=sr17Bd<);+zXoUstxO%2^B;J7f(-Qp)5;-R2 z#I%mc1Kk*-Cl%0wtY$O+EzU5pUKLX7P#bgyn$u~IDP6VwmUny z)#)=p9%qi*vfgp~ifo4<=mA_#ltbh`!;hAoKli$uz)z~9Ygf_^E5lfdOWI7={!E&W z=xkiQpD@I<8=3k>Q<%-K3Pd@~t~(+JDn!^-N)F!wtIaxxnNFqTa2=voFo(T{m?THd zf#db7E_D%B2VO1xSR>h z*bPVj+5_jfA#QhX0#$zQbzHj*uW`b%u2~J5N?a3XAk__bB8j`G;0qY4a4$v%0mx5d zP5N&joMXgu?L$a2b=*kd0>EpT>m*=Lz*YMkBD3)@3zswbTEs4}^!6cxe#(9_xEr^H zz;7ds(;O{>&)2~Jw_^6`wdIPowuN|I$dcf3k@Hm-J~|Ctq-IZSkN9SQ_@+jjn%?&M z7UqN8_Np*(D3@)oy^Tx@jH@y*LP@|Jj*8j#TET6vF>HJ74XqY-5B-`!kI;Su`DSBi zzS$U>V%1_}Xbv}qda^O}CqO$3sV*NJ4UmnY&mw*e0emn3*%*2$;`b522Lq6ep?F_frF1DcGDp+wyo(9A|=W@9L6t`2AfqBn+;=DvU?V`C_3{%C28fEgP@ zN%)Z^G)f9KhLSkPvjxiuHinX{mH<9Dv0!5;DH_uh0?->ni8v>q2sVb2Vog91Yz!sE z`Duzs#>P;R{2)!DA$nsdX&y||$nMXB?r_XfN%BmZL;$~VS3`DE{5_!H&d<+XF2Iu_ z?Ax--ZqZNNDFBe7GXZ>Xa)J$^q!^l}&;Z#GO2nCI3fb`4*Zm0XhZJiqg?k_Jb_CkX z{SW#n$-ZmJ43wKa$GHtiCGDMQ+HWDIw}Os#Uk7K>KANT#Xe`(WO4`3!T1NnSBPhwf zuw;(x_FUl}fO<$#1ircj31F#v3+DBtph3{ukWHZ5-ItW6m})89x20^{0=muZm8Z#8 zSTgr8p|M~CD04eMP0N^u>J6aG^5!%xV~*_deA=adN9 z67UxS#PSKCqsLbn1bk-s!RDZLhkH=~1_Drk&`3bQVDEEa63~MH&5D5jUWuU?M*wAX zd~VsCyVqnMN24_bBw&Zf!&^wvg#cYZZqU5m`y(oa zfRO}9yO8~!S9?D<6mtVsq`2Jc2JMhyZNQ2fGVk+#Y{dPpWo7sg`eSd8;diIyXXGRF zPA?a2jZC@oNaQm@ax3QJ-fz*+34JSzGog=qCFuNwD)?l=)Nm&BH{KxVh)}-A&E(8Y zm~VNzkV@znLRowxGoi0}kE4$hDmz};UJPeK|Kfd)`X=G}taHm=R$Oz4+h zol*PG3C-Y4=;z*kqvGeYICJA=xqmwD%$KjmGG!*T#J?D+gr*S75Z9v)nF_(lHyNk3fY#~ON{}56o&%}?z|kUzK1(067jSS z2pFZV$DI`Th`cQkcU{g_XQTE=F)E-SV20v%mq{@%px|c9Woo$5!DdTgbU^4Lb&1iz z_br*xL9h{%xjoR1Rx^kN8!?&hi|rVgTHr>@i&amUIdb_|J1%+~=0)mmSQ;`YMlpoU z&~lUIjVc#yoU{W7<%5x)(7ozDKuJ3@iuOtc| zf}7q~d0b>2I53X`?eZ`}lFI|?KQIH#hzBxf3Q6d_itqHv;L~;t^xn$H6gORRSWIH! z--yOdm%mjf8$dk)q}N+6|Ew-I-C#^W!3~!$svAu=;2Fe*f_o}IP|u(OIM>)1P!RB* z+6Jx!@Qh$X!TpqO_*JNvfSUsf0=`sdqDTbrbY4Tjy_Bi&0i%QG0}29?;U9sH;(r)W za35t|n8$WgYdnJ1l$?N?@L~W+QA2<(IrmTw4X;5{A;pM*f`EbH(@h(i9Z+!pWOJAu zpOdN80R;gQ!~X#V0p|r2+&g(vn1@Iaz+**?R0Onyd7Kmh`vVH@n_Ls_2@xpOQvn45 zr-erVK=I!VD7am6SNL6YI#NVY+|2eu==Sh@+)2h$45j!+2iz)oS$GywNjpA^me5PX z4h{gD>ELuWu49_v0X>XcV>z?oA4}@2kQZk1?W;16X$^&5@ zFi(=#+c7XG+#~r!xY;$fuZ+2&Hgzf4Hyzn9=|m1< z3?uEqG_8hmPh^KkKA_C^MN6wUOBO~d4H-8*n6hy{WPOCoQl#JuN>erhxp z;y$~Zl9aEA+wAl%yQA(%Yrh$-SZ_vC=uuVJjJ5#zI9}bUaz9J%T!QiH?vwlP<^G1; zxoqNf;~I(Ajq4#^J=Z?GdaiSL-MOaWb?5qp*Mn;nUJtHIcs;rN;PvD(gV&2|3SKWR zAb7pGTHy8O(ty{%bpWq{bAGQ6=l5P8PUgM7oVj~_IZgNaaZc{_;{-g974P-ul-uji z`L#EI^Js4X=gZze&WpW)od0@*IN9|Eab}yxy7mThE}KWCd4oB7^@ebk>J8y+)EmlK zr#F*8@=J2B6`C)9rQ-Xrn3>8=Xs5s)On4Z!Fi)OQ}af1M&^y?^vi4F zT+3_X#L8>pEXo_hDU&yb^CNEzCqv#?&V0PFoaT6AIj8Z)aRTFw<7~wn$Ek@op7RiI zJSQFAc+N1q37k%N6F7J9CUB16P2^zbO{CB7O{8z{O`;F)O`@;vO_B{{lj(bVlj&o7 zlj%!)Q|L2$Q)JuN6#BqkGksmJnLe%8OyAX;MjzFiMqkvMPRG-mPA}7&L6_2-LI2U4 zNoUcUNzc%mMK{o!Mbqz{K;Ohpw16hklngmrj;9mmZZjkM5H< zkG_)ELZ8TMq3`3h(!KFo>A`sO>8W`0>5+IR((~|6q=(_1NGHNOk$!@AB3%LRBo6uB zNgUd}lR1uiCv(vDPT>gcoxJ7I0Mc7H|ml7IM7w7IJX(7I7r>7IE0~ z7ITdA7IQ%JmT>g)mT;)@mU3M3mU0mCmT|=KmT`FTmU9^KmUFo9PUW!Rol5iXt)Q9r zR?wV#r_o}2r_m^TD`|nfl{B~BD%w_W6%DDkng-KbO~dG|p#k*P(9n5nWh>WOny~6~ zpdPnJ;gxtswelBjs^PAPgx(c#7}j4LET{NQ;KcEnco@!!z}WKV+#YtCxI!(?w(bympJTZ8Veqi0JQe6n*K<*vgmse(u2#$30O}qI2Z;o6+Hw&Pln<>Q{jO1XuiK zBV(;dh>1TW44>vKND=FQfbl6VC;pj1>u1oKHQJIAqLpATRWU9nc_xhQc7j$oD}@7h zi&fz&`5qwPyGjVS8*C*BoZLe*HOFu1fRyV6=X}8V6|CG>4aV^n<1}YOIkV-)uU`ol zC&7k!=`@Y;XAC#|x!0A$v4XnCcP9ELKz$1rlsUc!HP;{ejC$Y_WsV=jqy>o1Vp5AU zek>DiN90;u;aSeqe6sroBCq3$A2PY2t;_Euya0so6Q$VY@U}|$+9SShx(1)71Lqcv zHcimDxv3YfT#I#*!Gflyix%bsI-87~u5Bp8d3fB8tMquowgDo&3YKV;c-0wo7Y1+F zqD^R<+__RZ$5bAXb8#ILc`FV8S#6O2%6hM3dm>pk=1$q21bcP9Df}5o;Lp9TkPUf_ zGqjYd{sk+MC(ky4_C?-roWDKt42DFxc zAzLVPSRpwsLFxir@smx?wT}KhO{~+L;T?!|1~4|^a&m_nG!}wCpo|oh8>`?$;zFms z$l&}9q6fVh2e>;48l+22gA2+?M3k|&l<^>#9Ka>z>0L|l|BUF1Oq%8Nmj3$*A|K#N zE=PGD0X53gAmu5nhDLD3Uog4UJNkDMu}*XPh_Lm*sKMpr?l)+#Kk@@ge?gf6a5GVy zf}CTPr~6?V=CHcg7-sukuWQ;cJqATV>~ICku?hT6#f7qlYpK_J5xJ2GE1Yl-CVYy> z$GF06E1XD-De)ROtGL2#r#X=XQ+gv-iz_(+h2IYTWrvV`ZfOH#ZA1ErxSWz10G3?{ zKqs+OS0M2+TsE|pntX7h)$X}**(+UnPM@LbyDJd!-S>IrN5I#c_8|33KR>QIhJMHF;WnB@OPRRDoLx)dyHMmew}6jhm4X8ka&Thw4KPLeP&h=Zn{p+6%Xnt95N z$A?4py1FPvuUydtlTfgs=zUIaB%xv0Brt0bW=QKmN>r7ujXrUF0iaMy(|4eh*|g(+ zlO47c42DuYco-1qPgJVg`#|&<-2kP}3`$uwQK!`j$~U;L=&%A(46zz#)2YtYG7Q!F zV`G)pRFSg^njfaK%Ss*23f}E@q+}!5lB%kG=F!L|-`H_Y9y{L10=H{kD(-hK@65vG zqfw1Q>!H@sV2M83G$s>mGRl!!(d_`^jp@nog2$qFLV6sOCrwaVJyv>(O^csU2bE78 zo?$w8$d@xY%{8N&Ofeb|QO_S=iv(#>lIyD`>b^HBgc<5}$~rlhJwA15@R&#lSJ?3T_^O`^4ZA!&0ao1qX* zr5U5Jfhh`Sm=V0|Gd3<-kFv2n#M)by9NT^4x=Gh+14I4^tL)tNm5^ry5fu-`v>_Ro zxP03O6)lO^TK%)oylTu%3xbwROQ0KaVLRls*+~WVyeJbR-m0`+DrSDH!w!5n8y^P2 zGmM-WI!v2pVrgb#prVepr=<;_(k3GixLo%TJJP^(RitInxM_JSB@=C6GVOV%_5^A1 zI~)A!1bbx0AW~(OB$_o!s!kUnqe<5kOZjV$Hr#cwqe53}+6$5O|t= zM;D7j&?NPv3x?4IU2lw$y}FJjJw1?*we?-SS1VNaqj9=wd`g>3lQaHEYdk^Q(}{tF z#W|#AbVr7hX-}sZTZaNtD_o#3*m5F@{t$|pMv>|BA#MPt1 z0_ie_99s_!hV(g&v8cT>vsjvh>2{c#We&A^|6)oFiMS4FNcgZm`yI>St2B5@2~JK0`f^y;tiwXGS- z7>|M;@ik7jHh0B#2FS5?dSt%Ev*mj>~^%yZrM?MTns(*anX*ceNP){ zINI&3Tc=EO)A>jbwMv_K>yFYxg}0mKq1I%XDU2s+6WE33O;j)Dt!vuLWMQSj z-Av8P1jTxp^;$Jq{$zLQ=Hk;s^^KTB(D&?NN3EWA)as=h8a(TC2NRzowf`E12Z{D8_vP)eV`%MHyTRAIV{tz4X4?Jql`9c++Xr! zKWI#g16z_dnoiiU_dqIQTda+7SVXx7*QwnPpL>4}f= zC&sr!(gVnZv|y&4W)8~}Gc63cPO^SY+?X>nU7UQBbPOumOK7(4@YG{jsOlVPSeeTJ zM|6FhKENhyy)rGm%CJ~c;4F9~yL7rXqSmq2R_iE+M%%3;9lLligM;O2Zvt~Q4DR>MhMKJ;*k+Yr;jCt>Uvw z&VQrZyRQ2Mrbh@|#w3B~C15&;YZb0@ab1n;K3oTJy@M+S#KE|xQy z2`^VA;iM`$UX{MC+~ultigKr_DBjdp7O5U!Gq_pxXy(0Fvl_Zv)itZ(xbIe@nwynd zq=tqc0#YnIHROZet1j|Ent#I%7YPynO}Ci|{xv&x+xT82#KQh{J6x3y(x&57{w^fk zpqj!dHLRI3hyA)sA++j5u~m&f|2fs?ES0-ksdH5SDN0RMJu7yrmEj9OUweZppQ=_) zR<(Wf1H`OB{1A9X`$!f;&sOEjRQ^(=EQfHen%JW1KUNc)RTp5y!d^|G>Vo9@7S;7M zRli77R7JtN`b%~r0XS1rsg$U*oa!`^5v=7c-`g&Augbq3L^D(s%G7y=%J)y-t*Z9$ zv1*7apE6aYaK(-b{{mp-91FLSrBa8ZdmB`4*x%T!DiAMQt}4z_Wm8qr6r@g7)s(VX zH8iXI=G`q&c*0d1!;c9EUE48R+iIh~$(52Ms#w`UbQ3GUKm7oK7qXNM{uW(@P<@#x zhfd!r=~D1g0HiuV>ZCd7*IlmujJBf3ww=<7)G>I$SG z;PE7t2f3^Mr1Gv&RhOx}9Y~uhX|eG0HcX*4P&uuVkn(eOtIj=Do`1Sm6C}sNj~aX% zK1MOB*iKTHf;vBle%wAPauQ5Y!lfvXf1;}jpeuH$7S&mvY|7cHO5*vvH*4T=Dp%5W zX&9tJ)LW`57&P)0J_N?ODb~BnKUbB{fe4pSB9nHs7*JIS^#9;a7PQl0mH!B+MoNQ^ zz3z=GL`!-*CB~*=vFdR=qOGb1RJq|Ft6B-4H(|7k8X0z5RfWH?MfLO(&8qiqRlOUS z%T-Tc2C+V2_iR-QqY>UCw6HkqFQuT+N=j@)q11S^+3QsZai(fmL3Ej_jP3&&+DRoi zR)yc!D!g0Oi*8)e1~ew>8=+H2>cmE)zt`I7&)?djHRy^4n~}lU(JFM_-mY2{z9EbT z9Sfhs{1>5ibqyRZjoXI+9hfT`xnw?1=R-z*xS97$pWwhgGHfwy z=NZ8ShHMdfVN<_Wx)?e$>`dcsH7SfiKfPYSIY9AbNu-pUT~% z8i3aYig;bA9Ii&r(M{CNn~^6;Y>1z!GtRp90A3f$WixcdL3z-Z5nyWs-# z#qJ0C1*IHRkLDL(Sws5;7h&wZ5!XS)=?nY`&-4%IE6``4zd%31$E!E-4eECQ!+-8z^xa=t#uG zOW>JfkvX`DUlE}<5vMm1Wxff%3-ng=_ATDH1Kqm$b zI+b6bn*B32!S;s_V_X#~rMzy1@B-NBRM;DqI$1_QP^~Ib-F0HOA`CV~{&_x7{G=63Y+2Rbe1sWsAHTI-vywMx8G658Ib{8O!{HDf3N7fjwzpdjzKSv8hEX zZlk zZ)Ei&lhyZ*ofXgqllg8m1JuQ1DBGm4e~tS(E8}uCX)X1PR%RMmv?_eIZDT{Bd|MF% z+C5*XD`hGxWp%q}x~!^2tSUSZ72ZzH(mcWWA}QG;I4>)sc}i8?34fT)^S4KV-DP0E zISTAY26mso+E?SR;Xx-L4)k;?JeRQRC+MlXAsPLU{ore>@n*yNrfjQFraADY z?>ZWW=@f#Ia~I5dx?|vYCK6wFuoi2KL!ey3|(~DomG}woJNIP0*$OPG(=*rCv6y-~UF;KO4;Vj)~c9+RZBl z^WAU6{ENYS=a`rrDluxk$^p@jn{Il&=haC!O?MpAU!VEr(x9Pc_Sa{>xl~yc&wX?0 zvM8Sa=29B@A44%sf8W1Tclh5Pd$>n7nH~O%?WV*3w~(Ye{KIBMdg$1k(8|Ef|Bey# z7stlT%JW=nWDb}-%~A=*H0eF}ADffO^Kz5tecymD@wKk7CF^&_tz zc^}J=z$FLiF`P&05$Ss1Eg*mXMU z7zC`RlWFo58^sN_S1o-`Oyp28k*ZQR(tR|mN41i+%5LAOF>g2~rfo2H7|gxjh$h8%ppJLE|n85n=%D+ z_zB>Awo)Brfamgzx{Kqx>Zoh=VJt=mL%bfUe`0igupNwr3H$dN*yv0$4Z6>OMjZ*d z-+)GDf^=pN7*J1w+D!zf%HXd1@>4ixB6B(ym;&ALKTkW0oGJR}xqAg&1HX+HVJA(h z(r?15r_4Q%SsOu<((9xC##VxfxEL zGZgP0lS2Fi7`(q2%y*8BnI+{5R?4@Gl*UYB9+TD>)Om?fC#c)I9$!}tsLsxNgI34I z(6cj{zUo|hj4DlMqpR;jEsSmmPh(1-J@==^wChy|w5e4grw5 zqkreN*8!>apN$YQQd-}&+jL(DF9QfGzRyS8%K=FFk8B12%XdunAIQPEUL{k+H%bpysYGuuhhA1nzuUdr)(P@R`7cFwt4R2ByaFgvDV#U(3*IB) zD5Zw*GH&@l#@YTDv08Y;+X0D$i$EU<`@f1DP#quwX!OF)_e~+p8WD1{s|14oHuOG& znJrN>(wX^14SdJ3iCl`f!fYcc|HPIwdp{mLdpP#XeFb}$xMp}Smcx#^W{6jz__wOi zH@{1ib;1t8JH(^CK9u*0|JUyjGu|8yz-pd7;H^YzajG;8jxBlNj$EYk3*?cl6!TcT z_!}1f6qr~J=4%ta={koEOeNVT@wUf4w(3VX7p)*^6_Vrdl&^{(Qnk&h<2=>xY}Ez& zY*tD5CAedC9O+XIsXV%CC$dAUJa#Vq)`Z>%U$v-xEmi0Tr&p;V;adz}3STu1uf`?{ zI{g=->u?`mzO(?FYnS6$A*ho7AB2NRXiqw1OOwKL+T6QE)h$!~vBuw`u-rXNKkx;q zs%d3P%{rmq6YGHSgRT+`M0VO2=OiuOa?V;E#XZe(m-3(!h5;AE3Cg%jR4A}R*?n; zqT!!#fe5TL3)Ix`FkYTS8<5jsd1ZyyX2=tLL8<4X%?*uEB3@dk;&W8$Ts4I50Pt8T zL}T6Oaba({Jf=`xcujzq(6@p%`n)FY@QuVB(!^9aBx?vqUzB{NN^dNfs*-1c`BYVa zRB3#zM|lL{02WCwu`I0eIm%4s3bD#(i*2=!!0Z=(&|vlp7pRgxs^1ho zvK`Kstod4xnPMS%qUq5M0GGoVT#AHCk>*llxKJP8z-2`E6T^k&@6xO~wD4Zp z!k*G|uWCX^+{-S*(qy2tun!%9()#}Z1qvDy#vl}Bp1O66oY#owR(3B{yj)f37RqM8 z(lJ%t9c|u(xBJWSTy&0VnyiZEtES-xGz&CFHn929K&(QFr>TNtQmxVEss=R3CTWl*!n-7cH!OnYtvjr)p;F;p`Zc`i+F9OW;cp6S3x6hz#!)Ri zc9US&?NKbe-63SRwn*XS8=RNo>HI z>9UooVS-ZUs)k`I$4^BM!G?G8`*1YQ_vb!`p?>9o*D+Ef3bGWeI_=Qe(()_9s6x&H zqlNlK9$w#_jcp-#1G{Wf18jbw3$J7i_Ivn+4OLaUF%|IFL$RkJ58uZcuig;BEd!nX zIhZ-heg)Q>w!KqTC$K^WJ~~TBhG5-^;RqcaXIU?( zM%4j5r)L2-74&T8y|>(RIWsn|J)?WbG^IvJ9tE1)NSXKg!&NC$@!FYzAi~D!x2^da zg&u_;=A7Iw-2`2@n26JRX+@c4sVI^oIH1S9y`C0nK zy_Q_oz&p|vYiUtqIbhj;Go{5h0*|G@d#u1MX@MI|E~1eUXlTfLBzEZq0`E<~ME+WV z@BZHl%yB~G-K!>2T>B5mupW31pK8N?iz-!dwaGWSSydV#r7F<^CEEU_I9Q%++MPEs z#a4WmioxBi3P*nc)ucwMVho0r%V4&J`VrYp!WJo&)2QE&W2hx`s?KqlhHb+CXCkrL zP`2t+P>NVBnsT^~jk4?viEe0fHIAukyhR5;&wUQ^cBI8=XymBtZ-x&;H?+iSf`4@u zl18!|=%g(QeIOq@p#1n<>bUT^rdqjq>A0V(F0JagDfWH?pYy9hJT+CE!tR3bCZk7; z6;g7%BV~vYP@;MpfUld9>@DD=rC7FlR5sE{C~bz@T>uS*AJi&1tosdeuObWSc8#ix z&nA;gO`g}Af=f;uJPN=q%;ktO?CdGggv>c-71BQZ>R6-hCR2#esHQTQs=6`Qt41<_ho=MGDKvO+z-WSiWY_icQNTHgMzm4V#wA z;{Y5~8$2y@7V@-NQVhT;t_FZ7OSfXpsrqs7s#P0StO37e3s-Gi+P3L*L7vvHUxqa8 zA`@23SaL$&Hv9?ue*IQ#T(xu~zGkv{;i_fiIc;!T+q#XLRt;OaZRz68n^vq{(|=39 z{zLGIlZC5REnU^Nc@2@5u35ZvN!z-$t5z&Ny&ot5Tf4Q*B2CyL%m?CF-cz;k^0>^| z(zanCSURhg@Nn8?tJf~kh$yW^yQi`w=G<^ zZq?~Jd+HX|vUc;DCC;)XD^@!zHm+H_VfDgQBG=HxYuBC5X0X&~hA4R6y7<(E8;&jJ z*Vn+YL~h%-6@o3K0+uY@v~a~LG)FY5K{#-?pJ`0;+?TRU1DEA%Hn%O_wvAtAoUm=1 zBnFD^zj*EHb!*Yg&{#GFW!<=V;i~_yv~Pirs=D?*GqWe}1VTa*d_Z_vzps}-fS~s4 zy&95$sUZn@ptRcKWM=ZXCNsm#1W3QDMtiS96$_%MC=m6kU`vfvtD@A{g0BjOYJH;S z3L>?rsc-$Ee*d-h-e=C4B(%TZca)rc)?RDvwbx#I?X~wlXHQEf4lFT4!Bs{q9*u{) zJ7r}{=Xb=~qCsCg7-b6!s5a&H4|bq$gd;JdGZx1W=s*C6rIwyRzcvfD^oh3iw?wI( z8{_jyscgYpw!xN7e>jA4L-FdCnwB|LRsNMN%52Y26$*A5fvAbf z`MWz&15?U=Rw%eS?rWtQseXy$!DZGwq-3|GRGZO*GFBR`QL^=LBnZgu|WxQXG$V2mkE{KUnGO?6x{Hd;qvXpWHYJUqa9jY|HAt2K5xKK4nqkq4MNn zT8++dsI8d)z^2Le0>u!4F{CZXsw6iTYS`5h53lkoOzO3*Xf-k+u2!&KJ+=2l!f{qe zZ5fIlrYa#9r1R{MwOT3f)e^hd$vaWoxWJCqqT?g z=5_g2R|l#Z&TBFo=hFXx&W9)U2aL)Fv!-tDV#8`JcpD!ZwA0AuJDa#lS?GL!u%lD9 z<$QRl)?j_msAv18%Fn}r(5m&%?1;5?ggW9uX#&=xRH*gXivArBceNNTv7j&NZ)fq7 z)lC*0UTKw5#!3Y+1d^5>-C(725?YXj+99eTZ8&KCPWnAKSReOFXD^#O&+f%+;}$f5 zt6mvBe&E#C5eg`yA9aiv=}6~mN4heI%160ts!Eb4=UrRF$8d0W-@&^W5=OAQ94U5?%ROVRr~Asy@6pyvK3yDJa6 zBm3+8)-H_ZL4$g;8j{V{&af|DI`>RjcjRCIwWV8)#SP04Hehs&#XJ168=qxq9rYoX zJ%=f1%(k?p%y5D714^Is!tsW>^D+u_6{$4tRlVX~{)BAgZC`_@!t@M}YWHagO>xAUI|lJhu&e>iD%&v;EpQ#+(3Lxr(kGr?@h)(VBpm0I8=Vc2zy=qI_es2CVS zbyunMm7M_tcI%9KRKOuU7{YB|6k&YaSX|p&T=D(ym!45vT3Rx%WKQv{u6TDS_^)lj zP%zrz$0Lni|GN6j1+x~+FP_z=|F4@{Jd6Id!iD)SnH7m58X%uP3*jKe9zt#3^jTbtwC!LKp zt0_Ix7UBPc=%0fp>G6`9pw#9U6G1T?Za4~8VL58VA8>x`foOzjt#387gDNKVk16EH z-Z#>F5Zf|tan)lujs65**J{KtnTpGRPlZ@XRhX0TuZbFTwZtg&lS7dnVuP?GJ=x;Q zsDVd~BV}Bm9F=8S_h1r4nm5KB-)i>L+?=Mr{SvbkQxj%45B4reO6O4M1_^u!3xeba z$C`hlmNEoGh!b4hfk6&^h62D!vue>Iv%b8cd`Tm7mvbE{20}AAE0faNi))n>aOhV=1zDv9>B&mmL?;I*Wg)=#N)`-GUhOu=StJJGH8%HXOsnU`Y$C>55!l-u{N)R z5#QfQt2U>HFlUa$qyJ0Rnz*Z(ROx(YXjs*eSi(W~q*+Bw`FXBfyCaIAh#r%;&Y<)? zG9u;}8s&AZ%sCgR_zDfU zq?uXFCtFoSl$6?XtTt)(;Gx%kXh8`2=jhllSDJwiJn5P9=}I-2!~}w!abLnLl!LR} zsh%kh}w5-0Tw!5n(7+n&Kw}%5U&Rw{?sfrU7_02#%ueR>|TC=LQvbwz1 z2)Fz@{znwzH$p9#53mo$;;fp)8u5sUDSOl?ombzpu)DQ27_A3x%ce8h67-|%%}sii9j9o6@gN29(T zvo;+1Suh%2gxMdQTxZZ1!_qJn&!SSDo2r*oRaVtBm2=e^%Bvfz3=@UM;9txjOv=|~ z#^`PaI!&?^tV{G%V_6Ohpz^jP9OwoV()nUQm20&uY%mfvxFXPvFWSas);FEoP*q-u ze%n-af!WwpUQ<(5DfQdjSXsW@lp-LE!(wX;WjR!_Dhf54EvSZ3iRJGGUj5dMWI_j* z7+4**RgtQ)sJf;~wLllCl{6RYZiz>I{y3#qBXFWMQLI#9iOw)lW@S}HL)9WQt1OF} z4{I(){qn_CwPr(AQ*%Qt<5kx(UMxs!H}GkQxJaoBWmT5cRaP&muBu#AS5s4Wes%3) z;B;e!FWlMP6*6MMI4aXclC28*F6qQX9Md8|S=N}@#!f9&IJ`XmnBIpmn-iV*Y4HBu+Jp23!4XDrP(4TexDI z<#vH}2NsyQHjU@jH8f#eJKjoW6zjx%*x8B=b*ONYSzB+}U3q;qTM?r7OCS~Lq^7QR zab;ceLbQdgAgI0z3W@YM1`!z^c0`!4!bVAwvJ`CaoB}gc5{}%i`P%X(erzU90fSdY zlrEqt);rp{39W86)HT;unmGHHY-JU+WpaNcnd=t*sH&oglo~+yYVE*K;Hs+({FZ!{kU)V6p# z^#^I)QZ-7U&Z;b`sjF)s^R!j3qN=)v3=s72p&0kk-jIWP60iQ+rKZ(JHYK?LhECsU zD$_(I5?+m57I{f>S=2wcgOju1hJl*^3=@FFHWkguur6(cXqQ6!s7Ajpw1_RMyTwOd ziyMOaGGwGyKz-1h8ofN)#@LXatikB&gj#)VF{%z6kkSsdCH4WZWfYHsv^2IJ;erAVsYElF$m;8K9byE{87B=IHV`j+}3w3wFUI|0>^M&OV=bc~P zP-##mYI+{m1Yu(z&fz5ulOvZRei~Zgq1~fhkVf%Xr8yc&ZRgt|B`ngr* z^^Mf=TYBO_UMeLM2?g7*WQfocqk?j!ow4?gR<19cHj^r=gzWIK=o0YOHf=4cYhYz@ zhmiv%j=GL^tTrvLgMA$q5x%XI#@4y?XCD2TPk+kn#%g(T6bB_yGf_knl1-HujD3jz zN*CzX$MCoaHV3Ow60+^uM4~}KHX&)AqS}}l?25#Dpj$2<-Ssu~*LbhT}eNAzQlw!?0zs-rj^ zGqI^_ZZaSV?H46HF3San5RIDkGVY~81Eapl?xl-|B$`%4L)hts7epk9C2AVOI7p(H z%_ff7NaHq!eeSl>9?LNpa~HQYOx)K7vO3wOgtn}%y3#UjINwG@e%x|2i!|X2spZL@ z*aOREYK?}w$QdAq1`lq4ikj*~d{7ydJX%`erEOs;3aTLH^csLsI=8;35!Gl=kq)W` z?=HtI^m;iWaj7UCdl=-8FqQTN$`DMTC!yn7jk~0(VX>?$dStS@DLsPB)5qSCoII>1W{_8*H65-R_545wdOQi;X4d-h^q(ZClVzcb|UsdTvHz$s!qZuua$1)u1!-Hb`Q?mcb1)W-g>@HtKDS{Fd!nff|$rd&eMv zS%B5CD6(!s%rZ(fR3Ei-b<9&~ibZc`$Xan+LerH5YYZ%nap|1Ub9(+Iz_Vu={b89OYbqF4l(I?1?LKwY zh{FjrL0~~??g2aya?F^BFKA+gsDmcPiSWUy3HqJoaM7z&1*Nw{1%jPwQH@=f@(L;! zq%=CBnJK1){mJR59Q`PYz_LnWA#PzcO=|Uk2HN^C2SvO*gXOOv_&|qxG>!2{+Ldtl zaGI+yRxtVnYS{-Bhxg| zE#vN{*0-=2MD0XFn3_~O8CmYtFy)J#3HzX)RRK}hJg{DC+x)g|%r2F0F|1GaY$^u;Y~{PUcIr4H)3dQlz8wOsYRe(is+240Iqy5kJ1kIrDZxxv9XmBU0Q0O z+`05;p2b4p88ANU1rNMbMGEI#14kw2Nnu9tR(ph+7sQ&EB$sW|ROyA^nvAZ%jEY7+ z6rcQJmrc8t)@-!azT^s2Xho^Byt#OzBk?i<>Cz#y6WR7cscth(4OOYeG&-n|ZeBid zs60`WDnhs1Xw8o|z@%7CaU5#3EJ2%rRx8{9W)GOAphu#QAuJ57#FTC9eIwhOzoql^ zeg(g)Tp#G@fUoI_*vJxgm9F}!vSBCxFv>G0p z-PRGGjfs9JMl7y8+os*K$=8+mBasu}7_+-$(b?FK>g)~#XZyeZ z{n@3Zv+=5RY_yEgU?`AY)3&pb51kz?v)las*?8%}TrhuDXGf@e^(?$7O9iO%98@C_ z$CPFS%drHWO|N91p!Ty%N@iPc-uweRxs!=WgNeoLl6EYnbRr;b3$v23k%j44I}cej zAs_{^Vt|Ov#sHMT1QgC=Pb>;BjaM{5#I!d8+YDlq#=GHou@`y7i;D;VE)(E@1XO}f z)!NZ!0cY`QY~m67hxD!q0M-^ShSyfjl_s*3K7rM!&ZYrA$@&rn&-N>;H{~)Lf(PsmVTFPf zKtm+&lSp-RgmLc~jUypvNeCk8({G32=|W`AIosP4G%1GLo9ZvdJ;Ku!WIK z%4RwynKa^u@pC!!4YNCu4b`u(hZXYe&uqT$^iWFB3F}moU(tcvzu($PZYV9 ziYJO*A*@%5n0l!#`>i5ZgLn(nV)f9a+cbj)C&mSg0Y0ku3uLwwYPp6k-zE>chG>xI zi6Zx$Z7BG;B5%Z)H*=eKu4sQzDkZ18wu${kZ{cAzKhQUjMDteB@uCS)W3_S0^gj3Y zva~td%TC^IY!kP&$3xEB>1OS+4sm zLVKzJcf)M~&s4xOt>)jG^JR`epPV7S%-J|DC5qmO^i31?PEcuCqlYIP$ak+YP}21i z-4P|;rinWz;@3>Y&WU>`x>um(46!%o%^b_PT;k@uJMz+E#wz2K1?c~GWi8yK7bcw%B{G1-e=M#Gi(jvxXXjl*We8Khl$xStum-y@WkH-`8 z$K$Web(d}vSLSZcb{!;~%kP0?LzjwFS%n1AevobT+QD1B5QMBw{DM*~hDbpfFL}ro z+~SDmh{w_rv+Z@=>q4dObq%<{ZNN3`a&KrC!>+FZ)nyr?*M$SzTEtdlQ|mzaK*8~w zE#gaHDi9U=An}1YQ2IYXl+t(kEJ_nYl_oi!bUjJsAV*&U2X^~J(HyXxa}J4cP5{Y3 zw>AbCm=H=Nl^54}f5%UK*h4pzclFHsX1eOdho^mZ8gAEo@A~h#)Q>ttH1Wms4Ko1V zFymJq4suDFMXIGswqnp3z4HeKU5W@C(BK zqVTh8lH|#yJ9+?u9*JHbR}7WR@_^(s|cC9ia>aw`0C`fr{HPr zDL*g9)6a`r7P68KGe0R#4Q}MLs)JIOm(<7(up{G5kf~P4yD!yhaZkwlqrwN|7 zQ`K%K(M;JQ+b92aviq{}VtDFp(`XoUQ>zdVLBR0TFQ>X!jzOguakKz}Hi{chM!Ai$TmoU3PAi@<=U=vQj`f7nV0XVc>5-Gr zdViYo<`lFZPNzx+G1em|{gGO5%aol{&{&M+1ToehPufq-wQkCmDQFVLa)KCZ|4FY= zqx4Q$H^p_4#Bze5h1X6Zl_OK9*sRx_y75#0h3gbkJ~nypWawh|)O}N-3kL0-JUAIe?wj@|Y*vB>C%-Wn{C7{=2m6zt zHzpsMj4JJ%wi_lTK}RMJPlhSnHf<*?f*M=)7HT?`f*6~MA1G#h+ENb`KT<3$MD;9^ zQuZ;)d4KUMAQIP1-Ar0wEjvMA{7Uir=qf~+NWEYD5i^F?j!nCo`YNPSDUe(}o%=6H zRElg$^rt>b@$RFkFJw8KMSto*DxAeYDh@|$7Dr{a10GE~lmSt%&U`Kl zq9!hJEbTbuAE$iu!OY{CxE;^DJ`2F>vw%IaM~eH>A5Ta213r|mEJxxzf6C-l7;#m4O>D0qeO-`Z{p<8hheT;4Es*DXJ>YJG#Wa@_A zkZ~JHw=eTeNGElFTgE+9>LZ!^P^u){pYa!2$D4_ejnWBnQ?Y-^I7qy1&b)_sd8uWb zAjUcIu-`eG@*M=xppe za~{Y+{sTG4zX_^ z=Eq5Cew@6FT)f~Uyf~VYliDcP=H8GCmF~-bGhZ9!4Vb+^ec$A-BfYVY+LpT`7aDmY ze_y_KTRUxgQYwT@#)`!%5S1g4ifO$o-T` zd}hKcXg+C_P7q^#n)@{g@ydjE(PR?K31Y0Tb9<>h-ktCXZW7B0B2i(Vy%Us{cagF` znQ$C8pi}TQdLBB)wRv~u$&R5?z`ZkXd!E%X*npP7a(0q|a>sCjQ1D}U`(d3_Od_>E z@5KZYwjt({s* z^*EeDuj`jCIE7!jo~7((Wwvw*RH7l)xi`7d4K}&|;)ap^&ArZp+XfE~Cg+g!HuoRg z)G65e{?Yv$A#L#7A#*`~m4^xLkOb^koggk`!1Jt!iuc@|>X2^0Gw6YIgPv;yvab=G zZMiHaeL=h}Am7{KD=%zpOUj-U+@4K&nQm{U+@1=H!^L%B{0-i1Uf^%@ev7H3#9s#d zb*Xq-m%23-d0SIKCIfEo8(ufMG1U4yO6rOp^u9->eM4j_czDnIF)@5U<(m|yMcsc# zKa@vOypNmgm`)J4>24C4M0k@3xlNrQ6uyom;y^&9xGDyII#Oh=a%jw$0DVoEgN!+p z!MYMP7h)px2$b)f^e~hDoIN?f-jj1+9ArH(?!|GQOWU`J7stIkjv0%W$Gw3Z!sSc! z=N!pF8Aozn7zeRmka(C5GhQM*0N(pK2#ep(**^}^?0$)dwK2xis}RIe^k&~cBhn4o zx932F+jH*BVG-`kxjRRSaCgqHki*3*g5PCBgx_Uv%Yg{nBpyUyJevr;*}JkK!mjMC zIS^s1#DfToCq)pwSr5`^`C!&}j?jq2%Ic@_vOjBpqLG2DJ%qPM;@NCaa##uupI}56 zpJaVaj8MwgKt+q{OZ2BdnGOz5re8;q#&sF%Gd%wRO|M7D!qrrWz)1nEnC%+~vmy@_JOO%kfe0PRbKN)>Km6?w?}sTa&X_4ea1GcfB<`IB6A;#y&? z2S>IxiMu6KGaCXnm?>PvO!Rtp604o)aQ5m@i+Fc_{qHJmfjx@%lHWZ7dQ8JZnW7k^wx87i-0JB2zvE0Z7B+>mthn zv;gut9FGI#ZE;v+Fat?)So~F_Du%j&``rDsyw&gC=Vo2)bMJTCYl@|-U%OGyUlT$c z%2Wu6rWt{CM_ep| zIO6&M041tIYXaK4E~xxni3XK38u>_|%vfM8C=H)27A(`NF2;DQ(2UR3t1iS-7-?8F zN@Ez-JV7r+T1sE>W0a{LT>JoBp!H4Qhci>1zDx8`Fxre@^g-z&h#VK-_mOkDkFuBQ zY^&DD-bwJCl-;1S6Gq&Zb1%W~rEF|^Nal%+w)Gj0XQ0r>Gk!sC=NCB}9c82R^%-k3 zQTp1B}PG4#KhcWGP;}rCn>;u`E`jMC&$UbDtmr8JfYF#!_ zugktSJ0)UVN~HH@Ka-t$sZks;rX`kvB>{ZZyEIjPH}$4;gljjY-zr_MxHWy4ocl1Q zsDOWyzJ@GiO$Jx)SJi~QDlQ6M z?AG*8X?*w;MZwAd;L>1aD2)M9RO>H_{W1k+^<~P}Y3S--r!gaJKHi#sM>^nlNJaoK zBkYt)MmAGJ8@`_USt{)%eU^HCI&Cz404cDi#A47h5#cV)4r93z`C0r#ocKK)6ghA)F=njj;5vds74{T zL;oPx4XN*@=5)iRCS!Fht@yN3;J%ysbz07)XiOW78YmfWIQ^^iWIWPA5*`ulO7q}n}*Owz=c zUYx)EV<`xX)_Y|NL9a}?E(Q9*e(E-HUCO4E)M&zJsh7U$eT!JX<^2d}_CwnrfzGA3 zsztxpMN#!GjHgr`@4dF+7MXXE(056wO0!uinoaMTiEbnY2OE(C9SNwF#IUhe?JXb_q!fbL)K%iLmmJQc|MSH z8}WhXE@2zPRQthq`B5eRZ)qg^t!tOdb2)UfOR_;Pe9U#2<~D~t$2^>KO!7kx^OKPr z@mMPSchQcNsy3SGu+UB#o}XP#zJrYvVZOK=yCzG;=kBXKK)A|t zi$^<~TRabWw6hUUdS3IO%G~rboKqh7Jc`@9z>bPzMiN3qQ*p7#!VdHc?Q;a!;`u1@)7intM5cUZZ~`E3qwEemX* z<{09Z@wbl04(;Y#Y|rk?rOjGS?nd&~@w>-kk9Tt-`SEz(66TFw1G~3>$rZ0-s}@UO zd0X?av~(~}3}GvpHlH_56wge2ssJMjUWyPy1-*ra=q>Cm6l)51B$Brwxu@`%Lh)ST zzCv-d@M_ffalC{h28xD|9Kv65v}o-lD|x)g7>7o(v_$h*akFPT)IpO~vE9>;Bu)B6 zZ|eF~Ebm~lht2<9Bxyz`hEj&11)8=YKz=bryqq$GXIhLDLz%;whM+}AF_<}oBrQIQ zfy_Z9X@ya&&%7B)T1Mn`MU;cVRNRv}0B9c;L@^XUmt_cAL=uDfL(l^)9*N$G>n9pe z?~YtCkUt10Ef$I4{9Zt5kw^^X4+BaoL1F+)L-5#G0pj%^IBhKR@FI^PXyJxea-c~p z*NFZJ0~4@R)0+o>how5vhjkWs60EuLYKdF{;Uy9He5{-C!Uik=>leIwfwg!nQt%Rm z+=CE4&F_Bhx>a zEGx+?I`W#k*L zUdoTwpMOV+${kMPvy$=ijKL)Q8vz%i$iHBMSdC1+Skc;oIEuUZdc{W%Bt>TBO1iR`9+b$mfIjMF6_i z0q!!2jDcQ$H1wwQoeF-=6%sxqZ^l@97z++Iqw0-*3fg5%FwX2$jBU5k^!yC)-NrcM zh6WoVlJr9|B!6G86aEInCmKUZ?RXe)!^ky?15W%e6d!FrI+tFraT$e%(W@cyJ_&HQ zfgi>xcEYCsJ^}5ueu;$tOl6;?;E_rRP(Mm;_!N9_k%V8O@UK*GL&4=7$S}48UaWBJ zw>=79{}4{D%6vh=2Np|!Pr*M@@Qahm9q*Cy>t9XRYC2QF&ry8NR(zHNE_ZqrK;0q= zzpp|9eyHGE6kPuX#7xLR*8^klc|zeEKazOAk~ia!hEJD(ZUsNaaP?rjrHawzJZTL0 z{~iPWf5w0>27H38Je~Y8!*h%|>gUD-Dr1d;_bPp=?rQv6!Syc*ya~Ic>(2^4R3V?& z$(!+=g6khj(Drr`mR`vYd&?!_w~9}hf=5o1@Hem)L05}{_s^8i^jlDL-2iwor<{N8 z1bno1zkdw)AI5;c3OLKD+EL4Yd<^`|6p3%lkn(I-^*R&q(d4OC_`TH<|8iB06&kMm zNxp*LI0m2pR`~r%cKD2f>z`!O{TdO}sPed>Z>sN{b7g@(RqiyvN0a{y##czT+u||c z7mUFtI0pP@%qPdtzYH~7>2nL<#kTTv@?pl;Pl@|8ich3o!pLvZ^#S11WYY0B4FlY0 z{iTrMIYzxwWI$25J8cp=N1WM+Nj)714LLKxWBEBWSmo_-fq&12!FwH=BR~OE4 z!N-Qy6TX$iX)tzF{{DkLvax?RVg9(LH0g}&`ZLraNAf(>nlX=%PDZ3}w98pGK92~T zN1U{pOfq+l?K2>G$iCSTNyZxGsQ3{mbM5DNjL2PpZv*x5Rq`YYs`wc;sQMz^G#BAG z$tpT%j1F-neN$7!!Z@%a6u?LKX65qQ@+H+3fZ{M!v+7($aBd~O%`%&oRA^Fse7&%| z#;jYksIjWaY@)*-z>r$y1Rqp6J~b<~ePpPQN*?Viv(Y}6b21w1Lq4;*X$kbE4HVLo zc{b5Otq^jIuL2Xl$Dlu-a};Jtvo!HBA`t$W1A9p^wr?y)Ibc{Hm0{w`Q`=Xo4!Xn_ zdP!f@S-KnT>p1%dqz-nawr?37RZ=I>t)e9@kxh3=I3)bXAD@J_O z$|$y@gCv4Hf50Awbf_euVfC%z$ZsIW z`jvnaoKiKSYA5)Ch!J`i(@7=Hxi{PJ%@Z{ij?y#HHuj@(^vNyOAw#1dx;H|^B-e?; zl0SqVK{CQ8!Yt_`Z%h8uam0s1?I-x!7kH`>N1P^VeHEJcY`cj*O?R@k8M*4!()-){ zqs<-Z&tz4Xl7=qNCzL0wIJqZWhU!78Ya|`Z0(*BDI~{K60Ladv&QwU$2hPCy4Bg>D z=EyH?$q(3^5jnk4T^{{vg`>O^s5Nm&tBGG!@zF@ZXBRl=ak6aU`K%E}JIc6bi8*Qy z9^)5UjFMPS7tWQy9ly@P_ja8M;iT>oe9c;dgFSE-91hefu|RapYhYGKz+ePE-mN6i z69O}X?>KURbLdPlIw8pZU?LA^3Hb<7r6M>Vv4jV>5+qC7Z~zh~VnM%Af}@-9$m3~A zG|Wf-l?2;W#L^xBH~l1e$k0Vn=roG*b#;IlSQBSRNk@5>w8UaY34PN@XK|MB=d2*{ zh46)^e&mxQbXH4CG`Ldd;CtVoPD5!rNnkjO#B&(m$m9GEogWRg$!8t%{r}ug1~EcX z%-!Wh^J%*Dy_la8e-L&$E(%NS^v@`IeOJ>Giw4s($5oD}&%gUFtjix(34LFq;%`lt zT>g2W&%{4Xzgi*c`x?xf=%O33()2|H#6^4Im?B&Bw1mNzx|dv-*~mqq3=ahIb6DY zO|R>Jh00sVScY-Bn)vB^uTB40^|8v=^w$7JD3+Rv@jzEG|24?I?3b29!>&TYPG4Ls zbM$>YW!f%1C)D>1$g|VWnJSU>UE^sM`dQyMC()my==GhMYhv6roxb0hOg~K`>-F2F zIW}S&y@u{U!Y;pF&(rs8ji~O)`nylj>-IM;R*33eoJ64IR#?WvNKpBjUate{dlO~a zt|WHGUgX*7R|h4szVERNL&CNFX_hY_k%NEAOs#e1!LHHqHNC#S0km;8dcCgw>OV>U z9%xBKUA|r)9a8jzs{Yjf=+fnCJ<>Wap=kPkwV=`;CTzo~mpALLrq}mj+w{? z91T!+P5=EQxE4p>vlV?3nsJ^ge;_GC(`oQ2W6OUIfD2n| zjw_jd!5H+<{8VE8<#Y!*>&gyUsOXdRx8-U{fATClw$wF2WUgT>8H4^2`YmEy7bkUC zO{eb{DSAe>{V94>Vr*CbOlN62{oFMM{Qzw^;G*?y`;|;j&)WCc@h*N_Vn&p~%|K=` s{%QNu;}4E$uxuAe>l%Dd(uXyH%8^hD4LcvB)1N&oF)vLbNP0B>ABeri_W%F@ literal 0 HcmV?d00001 diff --git a/euclidean_wrapper.cpython-310-x86_64-linux-gnu.so b/euclidean_wrapper.cpython-310-x86_64-linux-gnu.so new file mode 100755 index 0000000000000000000000000000000000000000..a820d683a682157b083f40392b24accec4bbaf39 GIT binary patch literal 110720 zcmeFa2Xs|c_6K}R?#oNwP2NjL4<(QQp@(Wjz=Zlx#2}!cVkn_05FnwAD2!kUh=Uy+ zb+F^;DAvI;iekaBVL`F|hp`bXBceDsmVCe8zURF6@<>J)*0tCiyYH^2?X&N> z=j~ip3>!7vGEGAtwlTJ|_x+)DBi zeN_82)a8wV9{c5R4>jz@DXP5Y#-T*DTSHa6^d)U@ct(sKZ$NA->td@4@IFJ~C7lPDkFzDtRyf<>EWpX5tp}uR-WDpHph(@f2kfBkI|3e`GIqk)>o#pVvEkki zADn*i8xNWz{`mSayC>BA?LVD1RQKHT)#j=;|LFXeKixflO3gQ~bv*d!m8)j`^P}F6 zoi}DwQO8wT)vdlRT0G^!zfM;s4*~4Uf&!`xxj= z_5X0t+u@8qIIq%;RAVKb499M{8pe5wzPs2X+^y)nWPDSN-O5qVQ1m^3VyDm}sBmpO zrRWuL^pLV2Qsqujc5YVm^_@I|E_b#nw~P}5$2lG_f{MOb+3x|I$K8rvpeE7r9@$7o zf3lusqddYdN`9Y`->BrLDET#tzB#Vk$>2+S+j)Wml>Ey|ezLODSJB5S`N>K?P199- zC#!y5q3G+B{8lATT#m}hnRBb>Ro2u_Sy)?HX;h9JcT#25^o7%B&aSDQzHr=0L*`V^ zn?7#J)H%~VUelb)X-lV6&X_%K%ADE1gW&0Xrp=i>zpAPVx1*1pz6e;=^eOXt^`2He zZ}D^#v|!Pc+REDM%7xRbcss13YHSG#Z(3LhQ9eevX2HVR#u`0KwfQ*<7f^c6!ZA%* zj+GnZ$t`G7u4Kym`E!=V6naP{d-nE38nr{D*rU_Vshl?JoXQzfX3uF{(_=lYNc|46 z8xc?yJ4B#o&)LzQY_jrwlt81ZHLga_5+#HFYSKoO-*iXznpQn`es#_C|Jp@;wNRs) zG|?h0*L=71>=~7b>6waUV+gMTv$1FdMyNI&zmXoL#I!fGpBkQcq8Y{uC0tXZRL`M7_I448i~fj zc|CAab=4viRk7^ksb^20R$Dn@dTn`a?LuX-V%d->^J^ebId0i}N@)~g71gunVQzuw z*{B?{aQc+m>AgT;Jx^IQuXgs_Ml~H?y>RXnX$PuZfhy}Zc~yxt3fip0?5T@tmHwRB zQ|ETCsqWs-z}+fWn+Uqj#bK`=1opQWIO9eTB~Ryve=D8&mer0+(I z)a!vod9#zas`?Hz9wt^wpDR9bkDnlX>SWBGog%9#F2Hc;b+um4R;YNkORbwVJ*4O> z=X-jZuJP@0^fxO!x!rN}f(0I3Lv80%C10%gn!d7!Ctn&z|5?eG#nG)Xo_sitzLf)l zV?rEV+nF3k&r^10#nH=pdUlq^(Y2kGarACuJo!uF=qvkq^bK)zZD(T~y-eBJ6i+Yp z>}-jnYdc%x=qD;W+vDhE13f#t;^^AW?l}5HWv4!lUN+dXb1;ss?HCI^z8>Fc%8oyd zzO}z6mlH?Vb_(L?bCsRqIJ&`w7>?37y0%jmM_;DwgyZOCojp4f;^^AW}-moZyoB{*%C+BcDBaR?^brU z$I-W{1>CMUy0)`Bj{dl^Qy)j)I?}7p!8p3MW7K$j?LRLlJN`I&*$7WACyuV|Y_9hB zJ^(BUBgd8)x)Y(|`kz~z+1)P znQ?f$yc5U&c{FXjH5Iu3s7&>Z{PX&pX`xFegDbQa<(f zE&)^3NBTQBX~+IxBkUG#97Ik%r?qY2ukmx^xc4H zZ}BsLFYXVX`7F+DIG;uhUaY78@McD^`}QT>_6NsoMKQxz7n?V{Y6~P{D>DAnD`~mZ@@yWCZMo1%PTBYjSiiN0h#zYm|&pFK)%oj z8aZ*VQW;Dni1Rdx%p_Kc2DAQWVrV(66Hu$P!J%!^zvbi0$BnFei*5oJDX9vtO=w>% zUOlv^xaZc9b)Sx^`&az~KQ}ats{1Hh_pecPU)NuS-VUz?zbf3tlU|gJ!7iCper7qw zd*_eza5ev7v=|lkp;(Oj3ptGn$mxjzNlPe#0EcUWIKt2(+=hmu$rDB#4A-H9(}os> z>f5M7VL=z_pwQxN_0#`fDeoW6mUrMkG3`TD6Tc0fpR&6X{V5IY42|%^!O-7n;({aS zZi1mjp%FP6%klbO>u-d+k=VzZFt?{ocdcZf5LU| z$$0Il&p=a9j?H?OM$5s>#iUh*a`s~4YAkdH1~axS9Z#ArZ$CRLQeN#((ek##nUvB0 zsXX=%PKkKvn28K>XQDepCv#4W#>KI{CmtvOwRgOWDqbz_tZc0gEvEGMJJ1k$+A>t zX!%*&>U$nk>yvVnKWbfd4x_+NFr=OrZ#EqaK10#<4uXLm?0?r^j5?qL?C`p=InZZN zODGDjTZDc{^G2K`nbc{@$vgtOC2dHkK3mPRm|&8^U_u8hpTxRe`0tqc_Fw8-(5UMW zTSnGNeXoW)M(dl1XmK?49ii$Q6Ngyef@pnreji)kapAguhu8HDAO{9ZhA+{~mSG zEDghT&p*l)=3~4x>>OG5ELN$()o+WIv#MDOq2?@v>z)$}yJ2A@VtfJWo`HOy@TyXK z(e&`zVFhwGF1&V8Xyn@E2+aM^p(9syEi!|v|Hxuj%{6el61St)wy(ouVC1TVB9qUH zXqN>qyj(<|Egn_3n~_GI7bxoaA~x3<47Kpu()#NUDBHD#Vz<^E*7K7u9@Oi(y03xO zkB86~f5Q5Lo*yRirnhbj<5^V-d~c1cxrAR#e1eBdtrz`;YH3uvwLT9Zx(4&&t2cfp zqGG=`eqEs*Gky+!7CXA}+cvy83r945;|gW`5+dW5uqbx?5G$G;zZdZn^O207k43F@ zE`S=x@4asiWBjg$P-OfrArdowOM%CZ-z?&Xj^7xn-CBP-K-1&5w%xCf-yCSijNhs1?Cw}Po zy$&+Q?>&H~$1i}2{aXC|65282_Z)op=;G(9W-T1i_+_+~@r%yC#Mtrc0IzFy{?#GX z=Sary`BpN1gP|tRzkeOZ_>G59Wc}HiIMo(c>ECcn;pLwk2|vQ^RXyA|DYz%zb_AC z{H}&jWc)565;J~Ffya*DEaHcb-x#Xl`3KPS_^r+V_3@hn?U?Z!HmJGYKkVmUvlfnM z{I0?ukThC7A0vnV|Oj`hYb?~B72zn!1QjNf)5G2^!dcO0M@slq~ zqy3K}u4NHxo&EUJ6Z*pmdz87_v0|!rfOuYQd%Q=+zoBk{Wxm*ZZ>ZSVT+bK9`p+=X z*sbUOCbm23cM*Rq`o6iH_^q11r+y3Yy=Un6&#&t@5ij#_zMpO&-d^F-x(nw6BkMe} zrU`2`>cZNf^|iTPCtNrZ9M<4eiX9JRJ(a@1zWA_y41n6-_55!Q5)=>1|7Jon#{bGN zla9*&8jev0{&)X-qFED1F}kMQ68?=FOc!|}hHdpGTW*(_qMvk+|h z-`_tuTK}5`3$gw;fq0Dng^9=bUn%fd|0^aQ<9|8CoA$q-KL+d9{qJpxMf`6&F!{Z~|5j)N|GWPUXx79L`QIyP;(vC;|K8Pv=HuT)%*Mm< zzqUP__P=Xc1ma(b=YJ=BbhQ3g|Ifz$w~Kg;|7|B8<9}O#$NJwU;xYcWfq2vYcOF^O z5ZLr@qRqrVibeb{42!1{Indz)g%H>l_Dc3_Nu0FC@FIrT98Zx1wM{BJ8}?os*Q3T@yh;$O2S zj>!LB!EYJz8W36kd4&J={CyO&@v!0_e$H=l{l_8@|GIeocfyB9>wonhH1@w;#AEz# zJMkF*+X6h+|27ei@xKkkoA$r+$oh5vJC$M){|f_S`~zs@e{1lEABXk)oe9kt|0~1H zJu3feK%R*h_}~5SiDpe4k^h~9)Tc)89}_hp68{q7-#?ZervKfHpVgc4zibwP_y@Mc zzxR&T|7O8LqxeTW#{a^^WBjiac&z^w6OZw~9O6y;-_P%Y_3QrkHpL?Tw;dScA3!7j zOHMjW|Jwu282{UfnR`_Jw?Z5E-~DeuvnGzn|6W0=UZeMqcQqm6f4+GCOFB&dYumAD z|GSn&ApYUkXLaQ*z9s0k7O zON{rwcl87F*VcdddA!N^$088_z?S&8^Jx8V7A!Q1f5c<_FHAhf|4MXsIS*P6-yvt3io zA1v98LJCH3^?L62T=-RR^$KqfF3ca+j~(U@UicX}J-_E(&j&QdJ)v-&vjH=_cAl7K zmPkWrAObG3E}Ru$ESlS}egh`Js)H$@%mpQQ(ep6Vuzo$L^!A^CtvYB1FMONju6ox0 zjrK>xk%91TY|D=|Le_2r=Zr@{{jx1xv;tS{06?Om7(y*r0{ipA4A*fo(6w5 zetw4o^xRsX4MX*Bcv|O@x~}gN;v}W@_mGORdv0Y)$c**S>*-0Hz&^tM$r_PBix)k? z!p{Ku#RFd39>W5g#;(;xe&1FXc^k#n!rI3qt?T=pXAPC1y}k2LZ7`qrn0H2)bIBaz zG2iu=>nyJx7Fqo~)@2^+V#V6?23YxEdHK}X@b$Az+fcjTj{iUQz&`v4+2~lQu_+5@ z7W6EbHKnEipQ6FngQ^Ou@a>a%HM6Vd)fi;lUnPpU#pK?n1#LDuDkukRg^QvnLW>hblhwm0e_yx0T3Pz6~ zHL75~`fSUgUxv}29g6#^kumP%p(h)f8TS>V2tE3(q8O6?ERo@TD2RsDtumu9d@3h$ zx4?+`B#^$>;*k&ijL{sFivpvc?};ELv3Erq8RIJ!PKu*XHHt%&x7SGhK;ymG)Fkuf>;v z(CVt$GiKnMTJvfZd*1Y#nt~~{1q;1T{lIvPvqpWjfM1S+dTn*VZ29yM9!L51ar{G2Xjlrk5pX?V=(UE1O@JkUPXNvbl%8@cb_YTn|_aSoSvL0rvs& z!-|`+V(tn!AMZ&M088+Cyc%#H7Dk)N|3^c^2jpX+?#FYi7rh@sqQw(!y z$jo;W{p_nE@Q`m{EPbh=VJo1K8XBIOb3!n%#J|!wKCgf0-bL+5rv6ZzA@q5O1a**p zCQd)-n>7)TGPO7-V@$ArEC*?q;G6>*eifDj%TnV8oEtz}N6N6&&_&kJ)SOlJh|~hB zCOI{yJT+9F>Msw7&Fv8R39{Hykb^cqz?t)EW7^!3ZosYlG0Z*5A<2z<VEq~Hf0DTWuz)oS$Pht>1fcfY z@mml4)&ob`1NwW5`umD}1o7C7SjJ$h201pWbsv_2a_IWuw*)zo5fgdnz`*qk4^?d} zU_4xzHThFf?`snZe>F;t@cRu6!`g@-G z`+f&s?`_8O^>;P(cQoVq`g@uB`??>wIMaJ{>cOmt6AmjP^dyo42j`4i2*PFkN z7&4@PLGk#h*eF<3(6eXv-rY;O^;{%q&+~ir>R!^PlOjtGdSSy0I{MS#@9UTpS4vml zmhtb-czG3$?&4nx;{+A@EhHVo6yYAo2{qc{H)T1RD#`IDOh<sj00pQnSp!Bt*`l zP6=Z(0Xip)0BHXPVr2P4u#o-%s+cgeTNPw-?#2D^v;xHE)4@6q=PI1JomgVdiAaGv zvE@A>k9j>v8zao@%5n1zn&?njxma%S%2ok(`zx3@*9u+VsGv(x#PGDw@kH1Lq0exB zNn71x3aUe0$h4uGgwtalT99dEJPNV&0>~tsn#4j|on+(wqU2VK5&087NXFm4p!<5I zgr-cbF?=(Zqwq3xLM1dz-WVQZ{Ci;ZM-{lCWAa8ZPQEzJFj_$Hax!?M7$+`-MjPON zCWAMMF=7@N+$Y#ZhHMykWeofo3>ShQkii?JQTi+x4)6nH@Wx2m2a%d_ zE8XLqX14%`rFJ4michlfl(XmAF91+yNK{8SXWMUpL(xf5ov%@t{d;>jilfewsE%;X zvtPp#mO7V5b^d}bv9Ge{z#XWwS?j0@3VXf%1f;0=npRYuG_AVEu%F1o_*1!FD;ptU zY$*bRY9_|f(@3eAJN z`@x{b^oT~%Kj5qOYxc<)0jjKssCb;0?9;)a&UFzTdj6$zwfX+FZX- z>$RxX+2~OF2h-*j42$BD&1;V>tOKTftI~2XDyr9}FP(4LAAP6#pfwrN2O(kn-!G~U zj)`d47va_}G3}9<2oya{>zJqUe>w5^T}}ITtkqb>C0bSSr=t?~5YzrA>PP)+Bl^F< z^$c71$D8&5*r)zqBl^NmnNvN}IMr+y^t5+qZ9^ERnD?o1-mBFN`#21XJ=?VBsuB}m zS@n#trknO9Fvr5$ki{FrZjE4JFE{N5)z0I!mU)A;Q}|0wdoRKwH7d2Lc^CO9^Q)H_ zmzXYkfvr3*qAlGk+|}lMltJA;Ms&Th7XY{4H0_=6V#+_FwGCTXubFltNECius~SnI zF>&m>?0;fyNu@6$N*?ES`%7@BcF>op0HLmDW(QJV$N7GvB_^vNx-;Dx(I4b)99eS6aV|8Wh&mmfZ^> zi)CFMHFzov*$-OwYLLl#SQ}K;6#jjdU5~CIf2X#p>MH!ZE&DB{e?Xg76+VVt`if<@ zhBr|^6ERjyEBnHK(X#&zA1A*r`RoQ|U--{ic3(C8xAn*COSeHTikRtK`YP#~-w3HHNaQ42rZXsy|N;(nH3&rw=uMzw_XQG&fxX)TFr zC2#}}CfM6iQxxq8CF%7CWCQj~UU(fa<6J z@VRuEV>@a^GP98#!xsJ;$6k#%$XZ<7$cSNo0^GjEvG>5^S^S-G`oh1-vDab7Q2&KE z{gJ4gJucBcSLuJ*NMCmag(?#5YPc+CYZ`hpI&D>K6HB8K?HOu-`cX(aE^;w!5qiY2 zPeZd=T@G1Hk9qtD9D5W3B-Iu-GGf^G!ZGc?JN83>e2ibN^%d)R$KI+~_h?l-v(R|^ zL&vUBljen}mayJ+?3HTLd=%As1@`T)9s6kv4d07?j%o?(3&(DOjv*@tB5FX7qg$Ci zo9RW`WpA9|v$vzBd>ITt zM72v;!+rMaAd%I9EEa0m1K8v@>wXGpaQaqi@gi*_WZFtl^TV zmaxwD**Ag3BCd#P?c-Eh>9faR!cyx2t);3d{N+CT50Ink8(LM>bs2E`DxcjIji&zo zIDO%-_u2P?PyKW_y651OHtgfEJ#F9NvmZq5N$EvCZ&dlhzr|;FR#Wkmh`!fXKeGJC z(2cs)jr7&~j|e^DvsVLP zQmY#FFidy5IMGg5TJJ`+gjJMiw^mx;MYOEM6@kl81uJo7;BNvi3e3ZA6jowgV2!{_ z1GfuY7kFIYWr5cP{vohO;N^id{AOV#UKQvj@S4C7f!77j5_o-JnZQ2=ZW4H7;7NfS z1OF%R*1$IcZx8$;@Qy$bpAoSV?+o-1xG8Y5z`Fv~0`Cr7DDa-Zp9SvA`cmqBAZrV{ z-AepE>p7tx%-SvRhpc|snz9oAll8seKW1eK{!`W%z;wO~B#ces?pCV{5#RhRoz`ja z+NAeWl0tAu>lf#4Os=at<0lZZ~ZU$TXOq=mAF0NwPjbpYs1F@uMM9Byt;oH@an!N;I*kfz&7-* zn!VUa+-Wa^8S2Z9m$&VO^8DY!iybR*GTg)QC;lHR;ZJ;5>f$>nJm*~0yibC||8~vs zJH6qS0Nn{f31>hggDrLv5`KqYv-W~K@HnLCc?HYRdjpf``E3_YpKA<~+XN&12?(Sd@07B0emY6H&y6%dOu?e;)!VBb@6+d~^v~%f1ltlUul2yh3gv-V*{TW1JVk z2=u|F-+9z8v4hFjk_-fKIfhj##Elub7=dEorGbagoB;P*olxTKsJ;_&9z3pLF1HE^xhZG` zySm&1B;=N#73}76hmVjOdRDNz%l$h-?$%ks9xnIh2)Pkw1xsA+x)E}V%?kE(xt~VJ z?Xv*;(F*o*j}c-o_cVdM-6aZME3l9IR|UC)Wd-}X+^{0#?o@zr)C%@%%(TET}E+$nIldqBZV2BhF{x39nv z?sx?kDR{NOu=}urI~6=2aHN}wsc!{Gx_uQKFYp9+k%Ct%_^`my?oI{yZfONicKISn z$hSr-SmE*&k&y3$R&b2Vmp?+j=~=;3T)x&3@*U0!j&=F2M##4^D>%;OOBf;FxUArK zm#sW-kc)9Ec$UkRHzAkVR%*N+Le$CRV!HKa#c#mC8!mg?sC0J z$i<}xJ2ODE>~h!@NAchEh~7A z%as)&mr+)5j_XHgBPh!&dryL9Qc9E^L^`5AcD~qA!Bi z?VdhYQ1Luq9fiU{Q?SO7hKUvD*O34#qFBvVa18b_?nh$?2 zo?;e5E&c@7VpAwwPpJYA;4zc(ViuPOTwTRi(|sDxw3Jud>_u(4>NDxXPQ zjYau}`**~jloc6#cFk$b8dL_YcBjE5S_J=$SDWLz;ECQMEl{?&r_rKCdfo|`9NAl; zliC`BExRHhwu40KaEwXYJh+QsiHJ`fUWF(zBV#S(^9nJ{-TtFBd;JJbMDv(u(E}09 z0sn^8?=VG-jOVC%JPZx#gUU#mVXg_tl`>B{0ij(mmU#*@eLc+vYKEaXVV>5Ulmn57 z=G3(sqvp)6=ti%$$3niiX8HnSUQ0IAG>Yd>S!h(}v+kzR>2?%2zay&yhPQxwTR83B#jMD*u4#)Eb|Ic_tCnI&ekPlw=*38W z27*gxqKf$iu?!J0lK%?b1wC*%wka+XL(jPk{dHPX-0c{yDbJ(g^BZxE$jzLcvJr~3FcpT##)PC3*u=j2whN`_E+(ElBX8&%A`vZpL*zeG` z%tl?JbYF#TkIT@6-c509QTz7Hg&)<3Yb2ird#!FjXHSn~JdM6;aSPgZeq%;CCy?nT zTd){2E=GXy$NvuuS^R%-Z{AST4k6ry!>?-1;pF^BiALHtxUT9-(g>i(lk_q=ZB>7g zs)5eLIrv4Ev^qp1_T`&bB)-%MR2+}AN7X@0FvnZx;X2MbANg?aD(=vZ*z!@_^M$(@ z*D+QNWO6%u7S1k2yBk?poFg(hM&@x!<}1R^Y}_hHc43sX3_o3Scd=*XZVwpd4X49i z+S%yQrP9vp!1x2sv}%&1oqq@V3`w;lNjvug{Tyf3>@hu!Wg*(IFWS9w zJ>JWH?O(d7L2i!sH{V1Zc5G>TN6-K+*)D6*#k?w@|fm_xV{+S(xp$dF6_%1-*@h zts^~fwJO;`9TQO|dH|UK<2lmjfpU8cyF-LMPCLSbip|=d;ISia!a-gR6Hh9c-=l{x?9sz?t}@Ql`q)hm`-a;&R?K zS$-YLpR9!XM#^Vng7l?vZB+--i^g^LdeHFS0<8k2#Q?#>ynz(<`e>PFUaybttaTW4 zH^VNEb36c@2cYBQ9~%y9NkRVMSu#%FVq;h*5_$mXLc$VbSRWFG0V&6sRcj2F=wn@8 zk!Y&Au$i~v9!+)NlZA*IrD3W02H{n*m&DphknF zM$3WlCnD5nkksf3AeZ4pjgF7h=yGM31K-c<{3dI3x03T}#3#&d_%4q#Jb*r;4NPM^ zJ=p=9P}FTKf3b0_M6YLnJVwG2<5=0ikKR>t-D{@L5b6%DE??V z^F$^8B%XVQpG$(3s_X%gvS|zB;d=9MJZ81w_LWf>H$^g$_4; z{=G@wPkTCh6QXjMH*lBMH_!0NzUBhx%*8o;DlVq4HM`ZEn)VCCeO-xM2>S1Fj(8So zRjPWXz5zoHGckQK_=W$(l<=-K!4;G8u$w?_k(($ za8B^&VO`WcgyjK?kL)eCtgM`ZS7WvWw^NN@ig;^u=O#60Vq?M2qJp1!f+wb7vB=Xn z_5y588m6ChEaMWYZ3_!m9PtUWA30cGaThn?_3ZxO=Xu-7dEVA`xj)a_Y|isGoAXTB zUe2>*dwH<8y`1N5FS`fO4bFz#xv=7%UxfSX^5yH^h?@+d%u&#z;lcsA&2jSzEVMQoR85|-?4%e zIRBRthXx4btbF#Alwe}6qI336==Uf&VmRiqu{zz*h1*vt)@CxKRAyA7ZEOoA?&PnNG zfUI<0MEvrN4o(1afs@ZdPxe>B+A3#13mp@z26Blrlm;fItc2Kl=L7Vq?~Lqa;B0X6 zv4!tDGj|n`jm|Q*bdpqOlQR}m(RWr-7&@Dsn+kwbCe!`5I1@1~eUqhbTb%$+PxbTf zr=K<4WK=FOG52A}4Y`gT-zBx{A_l4o@ckqgbLd#BPIMU%!?^GIF6!j3xG{WsCQC}OK~qlpXdGbkmvpMkmvnGk>{mmgUBB*I{K3a z*!;D@Z^JwIYeUk&Byp7@{@#!@NRR}>k84!ccXq&$~%#Y}t+=BN?r$P`vW{v!`;_?@Wq%lqy5|~K*K_-*GK_uZf zh-*Rf-++rWe=}~($OXL$e5i0F*)_uPx@Z^^(sPiI{x}@MPF@jUv+d-S0XD@>zDUvQ z0=tBNY2aId>jFs_N;~jbs{-cPW7KMTAu z&>F*UCvOat3A{BhR^aV{$pY^PU{MMFoq;O_ZVEgo@UFm{0`CrdF7Tc}5RPFd@5@>u z^*)eQE%^6Y*9bhA^?<-1vXbC-cJhC+UKIStti1w%$|?fAfXV0qNk)Gb!^*85lQ)VX z$>`OPOGWRSyip8EMt_%%Kn8CVLz2;70$xT2Zxln4(cb{h4{W{wPc8M;X4Y8jpX}ZDD)ifF3s?`eLE#wfnd_NbHYUcJ(z!=a#3;*=HI7$klYWJ zjMQE!ZJ5x02GiMD?L9Oh^%weSOlD`T8%USxw_(cqJf^Z!j7gkIp7gVs$WE~yqk_vRN~g16rwtodFrktuv7H` zt!m(F8(>HRJJnv&YDU{=0y{N6iD(GJOJJwQ&rywN0y{Ob5_R+2Mibbn(Sr=$7;Tuq z{u+V)Bd7Uc1i>P=kmAp=^tD{=XPaHZOQ|FV2j>nMXb!zZuTCX)eCa=3Hd7V0~5Cmmx%=@rUYi>d2Wxi6w3^xK)ZPI=B- zZzS6=as2?()+zsws66T4Fln9g|BlG}9!LCeRnj_D(vww>7#>R{ty8NTS-dfPOiFiE z(mJ*H!A!3oi7CEHTBpWbt*Z1lvM&m~q;-10C0gI`2}>odlXWXu5=lLlN?IrDNp02e z(V<+Gw7vpy@!hCFVX35bvc8KN6qZU_Co72lR5fJ!xvP@a$?8m&*EnIRq;;}}k>%A; zSSo3qtjSS>Oh0#3(mGk^Mhyx}C9RWnP1K;Urg=&0WZfS%$nmrox3V&o&4V9vqMz*UwO*=N!@k}f1^o%}1~>M&jI+odvqmp!Rl~>3bXO&< zQ|ptcmatUPI<*?2TFgv$Rnj`O^6*luhFMrDX`Nbq$>NRSOW+8qq;+alM74yalGZ7F zPE?CY>8?szr`B4nr3w_jN?NDt-CETvwQV$Mo!ZZ8Z9^Dd(mK^X)M|#0N$ajkTBpvz zh>pinN$b>Vfd_?Z-8XT^FI<-G)r0tn#OA#+=odz5zN?K=0-!&>p4X_BQq;(dTfk_bCT;Z#vbsFhIK5vvhlh$38w9W_e z$y(p=2}>odlf~t#(qd-1tCH4P>V;7)VX35bma{Rc#msb9C9U)Q>G7zRuvF4IS#L+R zn3?XXq;;~siE0T;C9RX?BHE}LGBe#(N$ad(N3wWh_=KgB)>*^BQ7vYsBPT(U)+szG zswFIyv`($1Q7vYsyDDj&T31H3gr$8?szr|^8OrBsEl zlGdrZUaP87nUwCTq;=|Vj?)*uN?ND>j)=ZjH72FIDrudReR2B2S4r#C4`EM9idN+_ zAKg_+>(uW{K5x8>_g*AIDrucYPH$vHy&N$!-Bn5JG_XipGJL{PN$b)HS|1yXkaShj zI<@YOY6(jvtyAmys1}pbU6r&>t`eh2b- zV{#HJzDioB{_u#t$8VsosHAnOP0{*>Pgp8xovO>Vs^Md1x~r1bsm1?`OSy@#RMI-N z9*Ai5V4`-grDL>X4p|bC$XJCp$mhlIzk};=ACt$DR1z5lxY6Ya5Vjf^{S z+(nZDyl!pBG_oY*k!^q=ch*#y%p*%eA{jUBxX~tsdn4J7iDXI0Bx5zX`6en}x=X&w zBt@HT)Z$QlR(v&;%z8$m5l8{zLW8Arm*C=6HS<-Mjh1+?u!x-PZFcZs? zkXSaB60~ECWMWwo63d8{FtIFYyO~l$emVL1Of5@V9Ay7rMyk}1cZPoh`AjWKx<8FQ z&h5b{-?N|3)Uu?9^ZJ9&ZNqqeJEoQ;A-9a>b3ai8jC_?_#@x?p2cCIsqxUzGdG1Qfv z>x^Np>|AGzaAoH@Bkaon3Zd+(()n?2DJ(P;>|FeL06P>=Iu=km7En4C zP&yV+Iu=kmHn*eu8aoV-yTx{HvCG|ILhc6Jxt-h|3UasC&h6}ScbAa6xpr9S^_YmoL7Ae9N_SPj&f9OUUWg3|?_;a;d9-|6h!GhDv55%SH9kS||$?wKxMvIzMyW#>+EaT)tHh z@)g3)t#bLkK**N^J9oOvHvvK}`|aErZiRyL13`vlH*xv;i#XS-ZL z+qq}ETq6^58EogC?*$Pnb#@d1*`D?qIAzXr_yHjg$)p{S z;^F+<4#?j#6T0G+$hjO9%X>MsA2<`7L|pTBWF>(!*|~t6*K<;V%yRC>FARBaWVZk^ z-+7Ydyq!82(o3DLtlK+jWhic?Gn(b>5^I+@XYtYTZu)nq!FuQ7wm{xX?+l#{&TBOA zVMY$DZFG)7C*B+Lz#ZF{r`2u&r<2kd<&WFZ$smLN#6`4$80~S6JA%n z;W4vEu{wsC`UH5zW_CJ;GtV@G{J)Dz%KBW zHM5_lcchrwb(kN^7o7m+pKIE**2Mn$R9}Bpq9v+^S6_!*Kpa(M4h^gy{hp zYq9+|u-pUaUTaI%&$#zns7(gPfTzie;irCQ-nxU)bJn9-9dYmPii=3n8%5F+ci&(& zAIlm=p)p#Bt`rqglHBUG9uG2e)_*P~XP~$>TGDVY!L9W~)-~k+k$ld>KS%l7;my|H zG9MxTaq?No*EHXxwBcTdsbxKt`aXr2i718q&`3yC=QI$lr&Ap?(w~frNEYJekczK_ z<6GN;Jt)~nONJXs8tzH#;%9^7C^S(EaejH`!l<0#x|j~ubHQa4I$sOXL6s2iJjrQn z$M(>zl-z_%A>)wZRk6!o3_V5Ov*a-nsa7#F()xSm`{eD$MLLOb!Yg5eRHF+=;-yRu ztQ&%>TQ3J)xT!x47wHDZlBj|*eIJO{D?xUc+mc$ZX3~k=XX&-CWsatWv9wSF^Nb%# zZ#_GDN9H{8YslxgF^YI45c6K_+^5(*uX|SCX9;h3_hszcH#6yD?(GG*f6J@Icmxz{ zr+0rnBAWGf=36Y~U0n(zgUJ~bEegLJvA*wQ{z6F`-6i$O#*HT_est2!n4i`pD~q$C z)R}>9v(B~7M%iHq2F7958l%%N$5sUXNb^SK9M)@vWfy_p;SJcX$mtq+9h#X}DoByDoDucd z00*+z`2pqR^-p6lCC&~$RgM#+)VT=N$r~U@nZrMm$r~s&2pfJj(0zi@agaS8n(jd= zmIZ@ovOfbCae;2Q@p?_}*aL?D-xM#RczI|L#fRWh$XFH?HQcjU+>p#l3RK}D9ehDV zNbb7Boah+-EDY<(1!mr?&}dAwvpXYtwMU=k%?;&)V>tQjn0bQuogd+SdDVi1oB`~Z z`GVv)?_gN-76?+{%tC2-3+2&S?DXWrt|s^mjFvcW6#%Ifq||wqrWXlP<~+qh7kdu~ z=T!F365&)hLup{Cn4aL|Q*4A{}ANH|-az3i%s1=;RQX00y~WQUW>TGt7(%lQLMuMuRo^F5nzsUY>vK62Ixvd=l5 z?YT^lgY74y)_;(D!)%`f)0ayN@Fbs!>Rc%tJjqv}30Db{W8$X^R{LuEVhl~kio9z> zTQL&8E*RiD;8l4WQurt^oPV)y*NKwfxrDuQeL5ckA!h|5Lf#(*$#FJwfNzjaEO4f? zM{msJv!K|iq}WZuDRBnV^q)cu>!r>e+ z4BQc{8#iC_?of4m4sj^&PE|J_duLM%K3njFT~Bj&+3C=6&*G5Wol}W>e-$nnj2Y+Q zCK`oIq6oN9?pTobmr#3D?OBkV7uc?Qr8f;{HOsrt>sn_SM{u(sA?FOv!TVFkLM6v= zJF;O9*cSln7|MGnv^Wgx@_p~JsLYU#>~)F_%cz1C=%;-(=m_={?Yq`Iwugo>)F zrx`7SYP~)L?$I*jjl1EW$Ku~XyWF#I$#3C3(pc;K&MjHA|4o*<3&UUBs%xl2HeH%wunQO=XFtZURgYB0#~kNI3~#HF6pm1VaV&wK>Mm`y>S=#MyZ4|I zLahdds%ZBM400=MyRoFUCFXZ5hJP(;1RB6K z1K+}c6_|<|+W{M%WdugyY6k8=SyrGE!j}=a5nLoRiHYH6ZV!;|!b~y(1Es!$AZiB2 zVB}3DG}|0Rq5DyS5x7E{^M=?v8~u*#dAhuqYgg}^O3B&qJtNRkYP1rgX5rUu6y0ur z<{6-6^3T)TRhii*Kq~Vfe7W7#W(%&DD!#xaF@ZHJEccyI0wY^l*}!BNGy^UM(+V7q zn%RK`P)i8x!Z103-35rDfy=;63{<0H{y=+lLsEdx<>bI^@WMb~JUqz_tb}e#;04qr zHSjzd5)9l1N+{3)_i2F{u$dkhjIvq;zQh=11Qx(fW}qK>CoAx0baQs#V$?7vz<00Q zz;saZ#<1e3To8ScX^0CH-Z8%|l3iJSu9S^H9tt-D51^V>;5isZe=LMV;oUad=;`cT zfZA>p9mpAhy||izp(q;CHQ*I~WuFgrX`*ybvDp;^`!CARfpsJBpm@O`RK^Uvfx4K1 zrRW?huoHAU@J}=|A@CHeIYwr8Xci7M?R%h|>C*HlvyHzeavb+*abAk9npQBq&H3KUtWn_**356${!4rTMj>pC1#qj?~^Dm)K3oFd5 znIL75PIF3trT9XQ_p z|Gh(j$W&BPqtSxGwPx@WFbh+9X%qBO&zRiFg*KGdNoZ=}Wo9rB3Wa?lTCAfi(Un*T zomuz?vqd>1GUmbL_(r1m!yY#MS~K+#8~t!Eys&VCnOaS07Pc-TE#*g0!%sYOU;*T> zH-mqISmE}@vQiV#YJ6v87P7%Nn!%ma`Yxi?SWMM_1#5JhnQHb{HEM$!bBm?>W&_(x z8XiTsc3*|&Og`NT8GSJ7e14o^CCT$6bQ4OQYGv~kBNVz9zENeR-Uz*%(1YO2@Q~b4 zNBHSE9+DS&5v9-dko-^*8e46puv=P&9)p1e9#RnE{#T8M6ouA9XPMP<;W6--(12pR zcUUbr7AeUR2bi#_z)39~5m2ocmdV-Nz z4gJD9%+wULO-82+ZoJ>dr0?VxI_Zndn<#phnOdqv$56C!4;z^`(?9R_q%sd+Ru$f3 zrkLMyK?2(}~GPf`+JY=R`qeUNzh(@H;`1L}|3m-94Z^VdYR&h#iF@vu{yzr}L zbd=)v9Qen~;D0Ea+gI1VaT81yXJlruwNIGA4iJ-$nb251T7Rit^ukDHoU+s`eBKQG zfPufOADp8DBE>6aJKh_i285)YX6q+`Yzo~Be|p<&y$#6b(3R+f56pt?K(>VbfEs*g zws{4})(}5w@v+(Z4ItY?r=eT-ntAU4*%2BEYhRmr9{|}E+JOSUH}n4qWOt~j0DEj^ z>(7AHhipbetMwN^_Jv9j^^>jqeLxOopT?Gkto8?h8D=*B{;x30%Kr~gznT3vqS;pK zAl$0J%&zA!wNVadW^dw9bgHk z?%-mVt(sG|i`A|-(8*@@6$~0(tv01VvCH-nxxFlD%#^w5M&R;X1e)EH^*vK%kcw8e35cHB~pe%F>9-OauV&PB&s`{!W z3)c!fE;(SYS@vbn$~=)H|Gw3lb@O+|W$bKto_#L9)dVET4%eWqIQ*PW#awvL0$n;X zWE}S{y6TFI2_mWgTbbh?f`L2oxqMEtH_jJrBcD561$W6}?_P*|k2bE52N?O6qC&0P zX0U`88}W>GW5BY4rs#dzn3q2X-BQ$DSU-{_?=Z*k>mco|zx9Vnetsf>AD?J*EZ8K; z#c0hBRyh1%MQI%4v?Q#&ZgBD0mpDc(tR%u=jkDtz{FX-2WvR$|Z^Tdq@jD#J{0_$* zO>y}RkHBv9!Lvz~zFbxX+;Wnf&(3#wNJq3Zd3ME16$z z5o^&4JdMARmlSluz&~ZC@1!~(ibno7aMcdQ@e_IUqOGz&#PgYgpET_&z$nEH+pLPKr_2zxTDH}yC{8)jW;$hyoy=?;^q?~_W{X7Hzwg6_y&;QDH~=M*v~jS zP@#kmK_3Qza-4}dCwb*QgC<(?*#>;*#kc@}WUe*!jVFgv9lw77RvIlKl#qtYsjxE+ zr&r=;t=9o1zUmBysFXMr5@)f*;Hb=CpssW8*s&mN_oT-VhPGO$jk>e6EBRQ^+haawe)$ zuK+V010uS{DP94VImU6}YNnABX#zUDrLj@kt>|1ps6OWByOB=Rm7XJP)q)MjS9}r#iq7JQ)wv!Lo zM#@=AicX$bs}L3^_KL@NC`!3}yC>!C?t$D-vA$T>MgNKjsS72Pv#hEo3 z%M77h3+!^7X|w0`^eEQlWk7mqBn+gtMkx76htr zCe9k^3FzrXXBW*YlqPENY>=n=QC)zT^!kfy<3< zLT$3l6dg0TQc2O1h;cLJDb*{zFF-%E;*w@9!>0a^^P*w%Qj{cNQ~3Nw>@1uTHifbp z*!egmYzjq(O@(-2Qz2g1T+6U|E0k`;DPdD6+kibv3d5#Q{tavoDGZxy88&;NrX@Hf zYzk!{F#eUTgiWD@feptg!7uSdZ=lWl;EHR_8AFvrj)%Y)oQd^H;E=GHt{B#1qPbCP z&Vp7IHFw2nM#5$*t;z4&tTo@$n&(1m2{pIJX-2|kvDVZ#I&7}BhcybDrz$~nhZHdh zTnU?(!TcJWG7Ys*0)=E&+zi%@tihJJ8brh9BwdB~#qwXZ<%giQSzFdZ4u!<>3t(-d zW(w9wArd;Ys>mZhrzYy>q3|sT8>lNuEiXEqvfT*lOT2? z3+xrG;zhzo;xzSmu zO>5qy#0Ew+pNMK!HLsbXW5xvxn|cyS*gRhKiWfHdp14NBCe}1OqG59z7O4_8g+CF3 z<8eyZ6v_f%=irpEDHI(x72<_Wg?M3e4a4SoD6PRMVN)oZf!#q0!=_L^0rnOt44Z2h zHrpg4%Hx!&WQz(6b@oV~C*u-<4hk33Awt3@7<&c9RFbHR2y%LC>8={%6 z7}iCi`Ht2c53MoO+!d!84Vzk%AAnzDrk$Y5oCU2aYHp9yjD}6ES*&hculB~8{xA}= z+B{Y9%^ReMt5^hAo9Dv(5}aPxR6+?9l38&XSZi=5Zc(h*R(lhClHyo*isgTupe)}E zwHtAYWi8}TNGv}D)@GcEo8m0TgiUSv0kIrLtdlyw0JUw}a+MNtC?uBO1M6*C-VkRw zCTwcU`_zpNgKHkug?s@EdvSVUQx_61F9jZe*taau9_;mgqfV05rsmlCMu*KcpX&k} zVBu$+Dr_oK*59P<+@_GWy8&!};Pk?#5^^XcRcQlOKF-8a#X7Vq*@|Q78yyDMJgf^T zfraiky|AeZiIJ=|+a`UZD!X_3* zJfdOqKiE`|uqpiE=+VJAC2R`iEMOCGO4t;N4x0+`!lpvJuvy2jc^;JbA%6**Lb(yx zm839i3Wfjg&(owZY}PSsx`-pmJo%C?lx$#`q%dp>r5&&WoL<<()1QZ#i6?lS`4+Z5 z#6NmKpbO5#dLX*WEU*FjnfO8x{!EzDexnR?Ph^CRzW-(b&?l0701>h zDW0TJ*B0A+(qCV~!sj?u*i;JEY0~!pr?__kkE%NN#`nzZJxPEBVgdy5k|-dcB;>+X zKtd8EfDj?vw4QO2Ody(@$%Knyjd;x|v}x7ePJ?N+o+<~67nINAIUmKM*g_kv6^o@! zKdrTRlvpp+oO9~`_j}h`GkYc%^Za@Gbe`p;~LayQ|AY! z%?Zd1Lr$9|NnyY=lsD0geLJyFW%qm-`>OqraZ z-GlcilGo}Bl{U3jRNCatjC&+)PE*}`#-q-j?@eE;)27ttL!&u3By9?08LmojNZJ$# zwlr{℞>qL$)*TVWzAHUKI|>lmgj}t8Wm(ym$}u;?Hr#|2HOiQ6R75>NOma%O1-2z1xH`ye4JXB@iNSGZbf#e0*%1qWZ z-meMg4-MxWkX>px8zhHF!g&#@7LfC$ah#*Obk`fsrjQC^e(tGQqs8ZAX;=*1a``O)+eZVN+~$wxak~h0S=&(;&p# zF9h0uysgt{e~40sqm+qoYiz>xx1E-3e2lmJl8w0}YBuX$si@(-!MhnXR=yH48a34$ zbks(Bx(e5JFfW8#w2P4VxmT0sHnM{QS&hHzKcVmMj)@@ij7Ou+|8)*jKs4+ zgm5+?kP(0k!y&$ZN(<=mAg=HBj9RDtV;m4h<4E{+f$Bk@sQE-wdPfN5QbTzes3w#0 z-Z;ug)bMu({CG{lM9tmJVB(6J#TwBwR+>1*CKxsRHyoGakfZcYwn=2k`xK zzNOK|3XUubo{my37??8I_!#e?CmVA~)I6hmrJ{zn+V5i2n71lNqvm^G(orMz{O3>q zfzZ)Cj~g3NsW!IM&?7sNr+2m*J485y%`| z&B7s3Gxbtseh)qOF3;j?w0|rH0{`QA!W$aF_y^4;lrwaNcdSsh8p;izT0_bsag>p$ zS!gIt!9>knkAjISYVOvEo{OXj-?iGe`GV0+I3#Kel1(IWH9o?73ne%ZCqXo7b{P?v ztncz%XE=WYWM4I$4U$77;rv5XeV?57#Bq*BO}F7}3MLBf`h{ua8E|+SheVA*b4mj*ut+Q&E& zejL}JbS0xe+kjCs6YRe@YSw6qQiUyJjWOhAt5Kl+N6oi1+8t5Kr=ygQ4NRGQN~7^d zUdhI$YOK+{Qc=TSgYA%Y4U+&q(e0q5kd7Lu_nw2_E@>w4`_?*ZXYI1=8~2qw(vP(pc*uJHbsP@W&ulz#(N zFDc)MqrBBno^L462<19M$(QOT<48CXN4Xu8vV@v!C{1AmYWUgF3MQ@qU8@m2UN5_K zf=zHTI05W4aY%p~B%4U$)w58QPYDjhNg!b)OQ`FN2+6{^ph9zA3bMt9vq5r*B%Jxq zhz;cYqd3mgiVFQI!#P7Zf7Nhq1X-=&Y>*rx3FkXdbsITdubfG(dM zpPNSR2k09(B=ilMV+sae8r+Sm@8L-B%~xF9uAy%}>KdOxNj42muhjbb5jZ?TzM|Dp zn!tOp^!=X=)_!0-fkW(NkQ^e3C`VBBQydAi2NY$j;cN=yj41zY8u<-49LFJjH)xJ2 z7<_5)Euj5@4Ni?~@K$oo_)O;qroH^C*t9p;Z#K@oTnV*U(J=YV)F4b5>IB+<^1D`} zwMHqo8OrU}zYapVTcbS}rF=e0`G&an*v#kt9gWQ z7hNDX&iWo+5;4Qy>R%^`C?=Z3^V)xOy3fB)@x#RF6DI;EK0<&aKuC z`34a9Kgbg{6)OaHYzXByG^O`fLRoGo-via3NVz_alAa}$9ftCELitrg$$!$?OUfm2 zluQ8Xr*4MwN4j9r=Izgdi7RcsuIoL2mL^g+>R?U9v@scngrPyQi6l`m0acke5@yFq z5KWsWjR+qL=Nk>@Ss=?doDGsgB;mXiRg1}aavW!gH%T3D8_u5#=fj5cbs*bdI2$B~ zNW!@hRkh@t5yv^2HXC(~*A(EQ^0|HHCasv;!QnO>k~$2UV+sae8sszPZEWz4xCWzB zG*ja<1(P;!-)I_q037baq0(l%k#LxgZuk>}^#fq+#v%4HNDh%il>MlB0!PAu0Y&+i z;cN;f4c?wtqx;U+3;h&_^xdF2reN@;!7iZvf(6GW0W|F71HN}GIcp;gkR&Zg0{xurp;O{wQUB6dJ5GYlRDvY8lSTyoi>p@84-DrCAmi&Ag|k6&h$Ni(2FHAIo*c*7l{O9M zkZ}GV!+9yl78}lQYb1wA!udK>Z6N22IL@xLscXEAx?s{^Yh9gIOg%X8hwdtEYBVPv zUmE0t$D7&U9dQkclGHDRb&b!Un6%lt+cdZX99nVcw5bWajnenO8mzAY<108++Kh;0 z`u+n{?Z%OCU_ep6WjLFHNrSC5^}6p*fx{CxRN6F+#N$if{{v`z%T~f;aSiIUsq+KV z=J&yV$Z1p4J*{XYZE6tG=9>Z?AZ=>252BQx8OrT=@^!%EcMhN9;b*eo$cFGd<{I-=op^j92pO`a-2mtre9v`7qdRk~Wdg_=%>?$HO{pO8v{w=wTd^HU;trT)l}y z(xyO6+SC^+ZR!h^Hg99v#H&KAUJy#!6i6l@V{k~?6i7L)iV0!byp3s-?}yn%2-BuO zzKg4G6T-A9kRRgeAsi}gqU-#4?)RYDb8n*##wUUBIF5u(;L1q2rAUQ-5&P!3X7)L@z9A{VB)HU8lT`+0$wuen4 z*Mh?a94c*UG$$Tk8Vmugk`3Mw*PttH>KdOxF=_L*Uz-N`2H-jzI&EqK@9Wa{oMzqk z?ZDWIL#0h47Li1huc7KII1&yFD9X1CXHx*Wd~WMBjdTLE8;44prjdAjY49jrp?xws;TH5fw#Blv?=w^ zj8iYpmb595UjT9hhont`m^%XcLS@QZnJGU6-k)$trW8olxwvVJL-OLS%!?~lJ63P}$>8%&aBZhJts9H#w z7)Qw`P%WnM;Ok7jI7maY+q={wVAh~QO*x!poV#6TWL=snh5LN#|3I3|- z-Lk8wJ7z?!)GYyfchvR&n~h&V`r(h9*9yFXb>o$ADA-P_!u8SPd4U~sF|sIrJ{zN0QYQFAA* zb`Zj-5y;nYwF`&%{?t4rpr;Gx?Vg`*)&B84AbcA~!W$aF?Ri2uLsxj;6w1FD${&Mj z4=MS+2!0GDJxiiyp`kPd6E)i}*%lKucWXq?J0RWexgE6u@#PKtct6C~cF&uJ^SdB>+i*5W4v~cOf1~OQIq!+%%)Y6p={B5A z!9>CK>XpSiud}(kD(9&@voQ`X7I~&Xh=klcPK7SePzc^|h&=g-+ z*o>MdH3+_cK%o6c4d3^{&(EWjA4e(wGB9Pb@iD&9A=#KqqUKZGD-|_-^}{WUnu7(Z zsc6)ceOX71)L#URT!2HOMj&%>Re(dHMj$3?^o5F=TNpLh0dF-9i5h|I!qx4BFlugL z)I5i)1B5VY1j5%&zkox0|FIcLKu;d>=`Eh#TeN??3WQ(aNLa5kk@5ZQz!%E>n$kO8 zC<{;_hW;a{{y@qlag>p$IcO+N!9>k1*MW&^tnq6Oo+Z-6vuuJlxBd$DALEdyF-SI% zM1tYxqjes$<0Jq*gy+M($-2h7S~#a-!X%t80NJ@XgtI|%h$NhIQ8f)m!liMXHd*dIMzIU>rkR* zwATGg3Y$@rXUwtL`aq!lN6k8o=79qvI!PIhQcf0Vzm&eoXfCK+^*#x5|8|!V%p=M|r&56gC26q6hl?~=-w3x1BJgwb}QF99Hzj&0U|HT$6%P z+;_lHFWF;myS6!O`JQtUaL3EKVm503-C@VFh3H|>`Mmu*7q#=e9J` zBxZZAOiT5gldv%3W?_;P;SGu??_nA&oU(@1r>G`}kFFX-4d1s>+Ck z*UqtW^b#x@`9p~@1u;rOn`3hTAx?&2U{iyt1688AaWqT;B*yF>{}zq=PcBwSuL*krhw7rg?@BpPQAeJ4q&)$H<)(Acx^y^eIEgNHtXyN~32+*vdU2bHX+}_XCTj%ICry`*o(E2sn66S+S;@-4 zla*>{CQ;vc!)npxDS$%tanPwAPpPQp(k!SZ2P`jBj)u7a3p+gHsO@aJTxOP!&F7?g zCZ?nf_gy&tLOS6nIOlY9C{ejKF>@q0DG<(CG=uDUw~1B66)6yFSZf#2u#mkl8H@#?tPybu|02yP5+Ri9 z;?bh636j)Yeu2m9DCoHiXCywTVUnb-;VQyOdWobs8i?oym5DU|6&w{Lk;aPTRT9kFRZYxWyP2M>%X?wc6D=PkTy%o=gQV?3=?2Rl;2qO~FOc zP{hqICfpL84AFJ!n7`?qC`2iDiCf>1lv~<2?v6#8m6Z)&$MO?kEXQMmo$b1gTlB@ zd{9T9yn`?rE|`eMr25~Xw+`O)`Xtl7$MfGQ$vk;@B>=v%1M0(p-yK<)9a|6J_%V*> zar_a-NFZ_t#p}7yJ95loKs@rbjIe9)<-49=wfM5bgngNpceC^WOPwq|fiLF(zWhI7 z>1X&#Ak6nVz7qe)FIFUeim#*uFG}2)@HqKalK1+H&?Y`({T|2XUuJt9$M<`W$4T*z zTk1G|U#b*skK^&(@#UpUojLwbftloAmgbD|cc5^mGa7)A?Sw^(8&q+<<7@!Q1|eCF z(kN&2e>fK}b;hl8a_?{^tarvNbw=)R^6+Z(FgT;D@}E{L7u85Y8mw zK211A2+{fTP?)yfnN;oMt#{5_?_{rc=BUCBXTehEq78&xw9d(1zHXT_d95>dsZ+26 zZ7y>rf%2lI&g7+pU38~YutdNY0X+BXPWlEX3zbWpx!}3MnY+#ze~mM_)G1geT`Q3G zH#nE$oGnadELB=sCJF;>`g(F0zf|hmoy(UxGun+J*>6-rw9D5M5m=Bzv4ExK`g8oA z#B8+mQ5v;YEp4WO$T^<4GNS+bFhAgSjr3E1};2 z+Qj3Ec+3|PkBJad;gBrbpZFV;s6RqdmpLPEm#b7?iOnVH$( z@{x;6x^PKXT+%fc>f;NzT<-rwb75~MEOo}L=lA*R87Y_Ub`~NKcQa&+LNv;H#!w%W z4I=p2p+G@}{w#P0+f?2$f89KkH_%a>(Hosi<)O?5>>Z)b-o&M0XQ6*1%ISAH3zsWeD$#L3n3SXwBQ}Aenz0=hRH{;TI8<+m~`1KcjB`|>}F!?8P7)avK zkjSASkwe2U4hTui_71bXBf|iPh9t@Ry=35H8ypo9I6e$#DUt1t7{QA1{F=hA+59TT z*NCfFT92;;zOK~Qz^^Y8CZoqaEZxs9$AbiE9y0aa>GAkI?cw$QzhETvzioMKpMM9x zy?9{9YbUhx%O93+ZyrI(1SR{|<2%)V1m9zJ^UD+YdL5%uI_toFXkYWHcYy+0JI-KV=hNK$2P3+HSo=vD@9c z`-3zUXE#vz-}(Dl?GHn;nn@CZ-N$OC_LY9D_V6H9J8)K3Gp!1j!K|hbVYR=ytah)q z+FyrawR^SI25BnJYM}7@hW#C*?f8)F_FXNwVE3_`seP#*yFEUL-5x(HyO~yn%V2g> zh_KrSF1vk0+wFs)*zFs-`-3zUXE#vzeJy`SyZyf*+3jmuaKY|lH&gp+KX!X)5WD@K zv$C6MRk#dhH-!khede;;J=$)c4aIKv={(gOv?^Q%vzkJL)y}xA)~2m?W++x`(^ea#sW_{FLRl@WR&9xySh<*G+w8u} zHoSJhYo~D8mLe;;6u(zMqX`=AUyAQ@WhIxHNX$w9#xJg`TwjTqdSx}q_d9LXNn$Ia z=~dk%uAnCA6@Zy)33eZ=4z2bV{n-3pZ>3}tpW|0#xi`_bUz>X(jKwOo+?yC#?oBkp zPSnCqq_7k9a?gk(Tm~_>-#1iDjR?p1#Os|HxA22KzYwAphhNdoF^FJbRxgXg2!&cs zD-yrwh=RYo-3=aiMLVP}nl`!hD?QOGQ;6%Y;jHT)3>JacHZKkvsg zAM4*UpFAtiG~x)CK|OP*m_CIF&-}~Tc&3^C4&G*H)W2sweO8`n#1Srodgf3ueF_nt z`SIC!=1#4}K?E~iqCFE7$}<&7#4~@UJ#!FF+B1jHMbl=yXQFYed8+?$zA3u~7z_s= z&v$FBsy&AIUD~15zR-_vKH0x-K6X~VX~YpOgZk!BF?|XVzIp0weA8sGK?E~?qJ0w- z$~P5B#5Z5lzBvdd?VCgBqG>bUH_^D?x8)z`o4*}W-h4p&reOEUn?tKT+K+EO+P`l; zbymJ<#1Sro`sPqEeF_o2`O(?<<}R(pK?E~?qJ0w-$~P5B#5aGgeRB{_+Bb*LMbl=y zZ=!L3{XZ^izBVM!?9e(D>^`13wA!Ec99r$6emwK3{yp>2v+_(Mj&K>& zGlz=lQ;6`)Kc9_feoJd{5W$R>XwL+N@=Qe%@yuUq&m4r4_RJx4(X<)wnP}Yan^^5Q z%RIIZzh1m&7=GZGo~CvVK4~Fvs_!eqq#@rYEn$7V9>0Rzkp3SIe(Hq%$#K3tTi-@a zmhaaIteG#r!uXf1_<;w;UVk;Je16~Y1kVGgNb|kaf(rZqieTR}!#w`PvH0a089BZO zx9$dbr0);Hs6`lk%`nPVjNVG{eAAhZ4KQD}Q+Tc8yUAbREZ}9eQ+5R}eZ#Ar^9k^8 z^bMz$(|rH81;1WP!_QvQoDrpt=if7(5!1jN);{FLZ~X8Z5B}^>_SDcwn(xho9ZrJ( zGyIw>-ATL5DSV#a3I0Tit$w!xy}i-GJy8#LG(Cyy@dF>6{pp}j@cX_w>^b>88E7_0 zFYeR5&_A<5Yv#8lg8y!U$0=iDRZdx?F<*K%fA$q-%jv%6^^uD--?jKrDC8x3-|%Qz zevTCgRD~*9Hd=veR)=TSG}nfjn?oV%$`xxei!Qx1cUER@Zgzh5^vr2>;g#o91twJ#*U3g3M_f&ELwr%xOHTo5R7%8>clkHH1Tz;fAJZ&EckodZ1Nr zX$m%O#<{Gt2;afxZS|F#P}R`VJgudEOHF;%v~aKjQVhmJF|Vu*Hg7Ub)HKwCqO#g` zEnUiQuBi`2O4U{{9IRKDp{biz1Agq`ZYN@QPsR{+_ zb7xmJ)Nc+og#)!sR|mokINelIR<(M1Krw=_h7pTOv>CxDe^n;j&2@TBgsF>Lesx{2 z8iH0ev_Qdly9-Hm29@4qK20GDyt6c>aFUknmVhdxxS&PE?8?RzS0Zyv2j~-&Bl88RUojj zz9mq(b*t(hX$b9Kki1zDL0k_6s_!|$#>U!h zRJPKKQgpvs7`*WTG!h6jZ$T4uV1!jTSX0|99i36zurXIVnUtq1!6NF&ud3NxB3g0V zF|V?ruCW2`2Nw%RC2p<^)>hO)A-Hid%WP!kLltgWKM ztq#u+2MpCf{|${wq=;4E5tS89+H+|T07z4y{2#Vi2EMZp455v1ivT8N%Gx0h_m+C6Q4O=RuPfE4bP%ZT={RoxmD@h4Jcbm~-Bak!dC|hd6 zn_|2rsy&#Zx{-OVxu$xXQejnJMyi3A$S;l zRhiJJ6|oG`QBe0Ad8s;7rh1#-2y?08?3(84n);e>s2YJ4Zm6rUDw;#g`yxraTD05D zkWS;G9;g-D*d#TRJ3ZPFp~P z$O=r(*es(G95=i%SXUQR#*=KOM42JwYKxjt@*~@~Ah)r>Djij`bRbsK?^G^Qe3gGy zSieyHm3*aEjyUI%PsM;YvV`O???P%}G%~xTk(-CxLnz)IXi=K+WR1Rjn6niBZI7UQ*(pPZ!?v-RloEF<^&k_b&lxU z8%Ppu;3m|&6Z8yIrGqb;qfJy|Kv(1X)fVK-5ekRsf-rhc9p?iT=~0JDxp<-G1r4K;n*-~-LM~Nmk zNrizOV_>SLzv;x_18Lugl*}vr(bh+9#SpLN9slLDe z8B$ajstoHi-IT91r-Tlfk*J_DR8y;PrO06Jzbk#_e*I0e0x-sn^$lC<1A3ksYO2=B zqJTx6WPMEK!`BJl3Gp>eAI^ZC{p6aEn z9!F+KyLv7xWfM4*N4YD;o#0l%mqTsOmG}5 zmHN6xY-b`%552%+S1?WA3g2Tuh|p?jpv1xCOD(17(0Yl;;fGVHs07tYD7{+cMgL*l z*Jl02H9{lTYOD=bhBh@|#n9AjF>gfssFs5wL_|C#K;)7O<_cvS#(agUmZIv{46YLL zpt)!#grTTkn_`xZN=zBTn9SBx-WU)?p?8C?ML0#Giqt?5QKXt=DDy`qwINF-N$M;b znt2%Kl)CA49J*u1MU`Y)7+&sWRxFR)==$5enm03JPAH5;&7xnV=1N5C3*lnYC5sH4 zdTd;X?jo}R)m4E(aWyoaS!!diqEY!2^x8m2rCR1hq{eKFiP~yu#F9(uW~#-!Lev*f zVBdwmU>gfzHz8D6%iWR5^;m;8hMT4+6>-UcI7P7PyezV-sg6>FOhmAntmEKbUC)Ue za#4OB3a$W_sdm5i(RMNG9oGO_K$TQmGr52eZZ3MPT4I(ld~4Q2Gu4dOs9UDL+?{HGAqN=0WZfI1{SXOi_@!3= z1zgDM9>MZSClM4HL?{H zGkp{;k)cFZ5hhgQvVk-qJ0u}%McIbHniZu*D~n64+!WD=^KM^oyjUSGQKUF@P0#la-ra zwrx>Mb#Y@0IMB~}29HU~F{0wK6surAQdGd4v+)#OvQtrYuN*zHuOs~W0WFe`;{ z!De8pjYW|))QEj8_5-R3Hf@w9%gUFmDk&@uT(zdWWPMF6qlqm|&|;thy|4o4@Qs{a+f-9?OGUUTScz?uiojNE zwsF4_yD8WLvjS+LxTI)R$zs@0ai*=XUt*PQxUytLU{y)^npG z$Ed+YO7N>z7MCtAEh%2Sa{2O=>q=K#37nQD7_YXauHI@6g&}$!CEF4T-dJ0Mv|3#a zsL0wJ*eH&JdJCSCm@;s1TbS>@VF2)pbn`?2b5l0J#k6vg&997@?)2 zxw5IIG0ZMCg{mvXAp)DQ(T+qaZlnCOuBA3ygRNBQ#_A<2SCwO1IjoEvW2aRs(aG|_ zin54f6_%BXo8S(@jSz@>SiW+_mBlO9EQ0=BZ9v_1P(q_>q{xL-V)oCq2T?w0Tbx-+ z;DfFqJG&LVqOhC|$o_}!IMgEAg*D4z+rX-oYgQBo)|82eTcDbNgczk=+-|7KFkZv2zl|{<}W$>_)Re^P@ zO3QHqZ`ca^?Hj|J=;O+VrISTkg|S^(ynN-#RdhmE_linNm($Hak34`u8^(nk5*@Ow z>Xw@Of#Nr6Zwq_RwE^vb=tMM8F$*#AF$*yYBxo7`#vXM+gyz;j#C7Ug-sg;8&cEwR$VRB8Qj>+ZXlUxtuU&w8D14Y7eQK% zY063!4TjI+U~{;vC0rM5zESuEYE*(!BCuVi?B%89SRN4s?$&D6lCe$`Gw={(!&RHaL+7NkCTF$!I z^VQ|67<4SIQ7N;U_sTF`F@hA+$XGx%hr_`eF;Iz1V;XM;RS8fC0uQgl^rfbLBYl$7 z1L^UK#%+ZyTZ=Iz2oz!OK?x9v0U<_~!HlL7jnYj_UROiCg*9wTbEqnhxhOgjk(^Ws znJn2eh7CBJKnfLb0jv~FK5z-J7&%Q8fZSA7(gXhU3LfuH-c=X zG8)m=t}HE%cq-E9YRt#PP+Y_X>RV)@L0^$vs;pAo)KJH;hS8b+#Q;UiOQU0Yaf9Mf zQH^}-nk%BAA~Kho=DB%g+g76+t3u6~JxJG(r`4!~NLFKtw2J0yDy3t%jU23+fkh?) z1F;t|?o}nLu2g-^okgx{?r2;FL5JI>HIkwv+&B?pVcn|2GWMcQMk-DcnQB+H)Q2(l zt0bxOh_r+OSw&WE0Ya2NRWL0m!a^jRnhMOi6sZnlt?U3MA0cZCr?xk#$rbLUhpgN@ zF&1*_veFgB5^8#Or(14Ni})?U#(JgjO01S#5vk+Xc<)xgN)kX6- zG-!A$(|}$Y*^Iq4HSo(Fi^$AEHLNFwdR~LkuW-$BnHplD5G2EhU#<>?OQDs;%%G;D zQAefy)Zz+JCiiwQC5ld6sb4+HM1wvzw`|+mV3V;8GnSh4z&`RL6cyRb3+SC%6v2&} z)Ud`Z&LLxl33jJgr|yJd27)!5%5rstHTYH&vsh$R4^bL zwCn^`N})yYh(W~TmLZvnoxmxY?Ko895B5>hKotS7ah>ogE-Wu$ro?g;hL~9ZO=3zb zE+p&Jx<)CNZM!lQhA%Mvati`02DBy#9ILEQt)vKPw~1@A0Fxaq;f*pCVDe;!Vd|tU zL(QS4%^{@Gm=#J?nauu}_~r5|k6-z)O;NBB=_(Z9c=qDJ@#2rbac<*_2*9 z7h%=1dP}fTIdDvKg~f$s<$8vNi34_FFkxYEMmrd8;G$3BA%=8up;<|B6j`h$58~}B zS1z{#o8^a7W-NA(6^pp+g$5#ndc>TC~`Fuwvz^s|uG>B@*j&&SJewmODeDO>Z}0w}xio*rwORv5X>lHlj?% zQxPN(r^wmVP#4OMLtoszN!HmtLBao123>p3VJL^asmPzov4tQE0U_6*(I# zD|7H8(7?=sX|*-=EnBDI=T~e%w-?K=58{B*^uZiR;2i#X5qB7BF=TIS5M^w#DzT{A zB%#A83%e>^$le6RssMJ%P{PfLDs(_dIrYFEdK18mBTiN^1#iUGa0q!Lgyl^mNyt_4 z09+No0R?meld|fXjS=89+1rU;;=TfZHw8fChn5KVYQvS2YL*AIvYru$q1}eaQSOnS zjo;x2oHo(0oGNTUOl!n=9^4pe&OvH#+?G?>&=fMpQJ^m{5fz`qgcIj4(S~y>wT}kW z)((;x5;oRK(tXCP?5rwf)HLASQV+?hP-w(YW}Ct&sQDZc9WpE~Wx5}^!aN!SaOARa zTcsM3g#jn-QV4OUgi34-Z{m^>B`$HX4q-U-DONCdi@z%QWPNjIRwoj$}Vx(ua{R@S6wZ>Z=!NbceTa)ik zh6wj3e?J8xd_U!(6cOQ}lt)sO2#=)fK~01N1kWTxglCc;Oo0dwDm;iFcrFoIlb=h5 z2+t+&PJsx!6&^$oJSBqNI^yXOX#D9BpO28nT&;}QHv+Bf8*y+1#5y?Qr^NfI!YhB! zjRy`_gTqH7Ak9Z3ddUc_^a9o6l4f7hPm;jlCrMu&2E4BhYaiy@4o$ZY`}#0<%l5vc zmy^)$%SpS2LF!$q+TGy6#8(o*=#|9XNno@)sWV9!btZj3DTdL(#NQ->(QgtvlEA1# zRYw@vU4FbgX^s81zcazt0zouNDOh9Kf?$t&OcDM7f17;sP z`|wgGFx%(_il+a5c(q zv%hK&S63kb5^;IL9uWal0CK|qeJslF?YHe=!a$L{ZU5O$& zimr}%f8lla6bS$3ML++I2w^BwBScNt<7p*_R&R&m(Ba)3%b~~fKOS)S9}f`7K_f&s zK$+J+?g5L(J#Ty99B+Hx@rVfaJD&Fe(4uOza-jXu1C{?#p+V(>w${QcVl8{Z%wfCn zKSTKGxx${g))SPnZH@8-?NO=zhkQRw%~qabTZx`ZJ5gY1fO#z2PV{#sPbG!E_+W~V zTSV*pTrPfwSG)5q>d}w=uO+`M@s!zLz4C!8aoTg`lQ^kr$Yg)3_=#eGpD6x$2|S>y z0L5#6m=eEy7>rlUU0Zw}t99jV2p#{Lc zPIcDxZGV3G&UvWbIq&p5sO8gnApMde{gQoT!EurvUvPQ>fTtIn;nf*3qUP-V^In|i z-8{f)`VET1lJAEmVL(!5vaLDY@~5M?b8A>^y`PR@f^yB2g%9s!-4_bwanoxe+Q z2G%#{cd(DA=J(=cVYrG131P?lhuPB;^H1RfuK-poNU$EBuRC=DeN$MmAar2wf)^;E z<1W3h;K%~_gOX8nu@*`YrAt$>ATSX{Q4Uk0qV3iz+OD9nulT$u*4S6HUqNGEae&na zRJF_4SF|mJy4x1+Swv$m>Me>h_QIpAKgxO-d(qw^8oTIF5rBt^fZd<57w#-X_0Gc6 zg*0{{NMUS}!q`Q}NqW5KG_Ot?*vC_gdU4XmjsYoSFM60gJ+bH%PTJTpAZ6@Dx>G06 zH*M?~5RF~*0wtueBc&ILjub_WO^<=yqo^kWqOqwcWo%Va#=f-eQX2cx&vRmp zeQEopH1?$jSbacMyNrEl+htI9+hu#QY3%IY9JCw#*w0^fl=Vkh4`XNV&7rY#4&?xN zCD zV#L_fUY$l`=YXFv_Oz4JXzZL0%A<@u?OitBo4reMrm?d-*vC`Zy*O!O$AFZvvma(p zPh_9MNgF!`q>P=dJ9Pqm)5eYg(bzdJP(m6zQhFihNKVw))CDZd-Wy}bfM{$gN*P;~ zl(A>D&7iSod_E`E*fZK^(AYB$u=;?ib{Ts{+f1mtZRVcYH1_P?IcPWfv7euLl=Vkh z4`a{XJBP-eb7&5LhvopgKV#3_ISbW0XPuq}eSbO&q%bx~VeC1_NqT(FXA8D zKSq%$!uvQW)yIO+cn2k-T}+96u@9!coC>wPocd{cOo$vz?Mj8#x>7%4^+&2YR%`pu zIeZSaaL!9<=*N3$_ow6Zo%Ba|+ME6%PHZ8nwKM13l}0V69ZiF*g1;8{C)06tGW~;e z)O|oQ(c1UY9!=9)lcLeuV`=-@+A)%8t?f@cNQTd)A5*mG)!pg4loZbqOJ*mrAko^c zbcjq5_L5LWkysG4c2ac&TGJ)bn#ILo(lfpom0=29ZjZ`GO}^B`YOCcg4?FL<#|!cI zc=5s)xS01Hp5FI9;fq(+v!27mKkV7*g@}R=`+7Tkxa#oX&AV_hAIOx8dH(D%F2}<7KT` z?O9A`SqE5sKvhSyW`CB|b`g5ncF~>*X!n;BdMBdY=*NEkqNA)o%6g1l6ZTHz*fsIc zL;w#>1a^O8*F`%oM)l5%PhSkZe0niRF?Nv@W7ovvBt1UyG_OuiJj1IqWTeKfi(kCh zj9o11v5UpX*md!%7emyJiQs3(u8U7z%&}`?2jvk(p1k;7Hr_j7m*NZyd~-qv`*>W}{&*vUx{ZZD#*!g=4XzYSR1ppo@0Cs=I&fS@Z>YaI~^Pulf^FRt? zlN81-I8M^z1*ds+y5J12&XAEZcHWD5#@H-sW3w1BcHXObG!h|xH1?#=r^Xt4Qu`ztd(r_` zA5hgUV^3W}{&tGzs^+#C`V^7&TmByZWXexk*rUJV^V_&j! zGOBk@K0O)w{&X@(VQiAZ*i(;_^!U`%ygEJg46n|Rkuvt=7bhEIv#5>DV#L^!U!6>2 zPX#|??8zr5)7VoxD33Ds==+T_LPU&(-Tup;iQcn z15(DGqC0g0ebdH{0nyk~U!a6EcBJ&e)FV@)#-=V{Z1&z5I|f8!Q&Gy;szlq^t>?9! zM`NG&d1kD!&uc%A#y;-=s}HDZm$A=lJ0I$9JAcoGH1>tPnP@lqv7bNxDC>{19>%_K zZzheMc_3S(y;C+YFb)4V#Jd4^YK$VeIc zf)_6^#%56)o5hH+FL?C=8aosGjIl2`c>#@`*+F@fu`hU+jrU%-OL3;LFYI6+PhHrH zlQwn?NE!RWhuPB;7oNgN8#@N1jD4Z*)Cu%W8#@L>V`siV32E#|>4nTAnNed?7ce$^ zZ;TxSqOqwcWo%WVZR~>?FK57-FK2u@KE~JwGrBTh?5>QDSpAWzju=}=_m4X~4k|x9 z?xk~~pZCtae>_g#8UF}Rd&hr>6Vcd7`PgU1-E}VT?>hJBxsX-xG0hl%ay+h1j{jgh z>OLTun(3VT=(#i$1pgk3k(ti9``Owtl9`##xd+Mcx$(yoEqZnL_+3hh=ZK|dIx!$o z{jTv4nIh~Zp_=K$fYA6!)e)#(m)IA(HKmPrwc1jiNsZB3Yf3wBUbUw@#pQLpjzn^EuZ^!}(PQscGu?8w8!KRj~hD99@Kn9`2wNX1o0>f@=X zdps3nqP5?S{PReyH7Odcof`ScNbuj43NkaR9@$EUy`y$1TJ-A0QOA@Ny*MeY#ezg@ z$0#yIcpoRFwOA0e)hj99IWZXZppjed&NPpRrSt&P5G47E1q zp0U*0*w=Xa&DeK%dVlN_8GW=i<}mROkJ&kvS|dJ09@~+DQ%A<*8Pr+^$duN`{CSMg z8jBIFjrn8@wUz-gqqQ-u5Vb~$l-5*9 zw03aV%fq0Smxq0t9HX^^!@7nsLWh0C>W@@)tk(7qKRldT82%D(F}^nf_dyY%$&c`~ zH~B-H*n%rUhu<}VS{`wfw;BZ>;gNhY8CNHhKS)O12P9JwI^xk0CPG;>T6=87eztau zWF|s+j}sA^d`!_YLX&qXDR2wbL}(01MJR9GQiQ!ER1q2jVuY%WFhW%+5Akm9=Ga_M z+U>qh+(q~V>qxuR*N!6Bk9Lo@6~$v%5!&6}x4iZ{-X5^yQVO>ryZyNBfF+cD(BFk3 zmrl5mco4;1SPa>n{)hay-MA0e+!VoG*3MyQ0h=LqEAG6a1#E)YJxQ%7a$CdhPI@cJ zekZ9X2`xZDc2{zDGFpIQ?1RZ&C{iKzzT|@_?m`#s&g6%Z?MIUL;hNEFx2JZdq6I{) z-J05tB16;e8P$p+GmV(`*3{3w1D($9~|F>BGazDZ~Q?NnOp77@ehr+9~r+7*DqnLwL3HSW#VoP##p;OvlGRW z7+dYu%ytwxrrJFhwxZa9QPS?du;)U{ei%cc-F0C%id`7c>>iA8V21UV-8pgJL@>j; z%Wj|8i6YlqcI(7;6uGFfdnUA^$d!}bJ)vg;m|?|acTMO=X9cY5?j`GYfd|g+^V*FvRhH?z~-~vo!yfSX4ql2yRy4c?7}{= z-Ghx|FvH5j?kw0>0A^Tm*zEb}Nb<*eSKUXZOqo zGi-<2U9-DU?82s|-Gg0DFvC4KyK}+51z?7IZ+82FP8501&2C-Ljw0{1**)`HQRLk- zyL*1md@#dZGrMbkH;P@j4`}z`&KH>B9*^Bww66%vaBs(MFX}|`B<|_htwrr9@?MVJ zv#1rt4&0rwyBGB=0yEr#vAY&^qu7OeD|Qd=tXTG)#dj9lcNgy}w!cw)phRxX+6QrC z*0P^0ezsWd!vfe{V%cvO|G8LhsoLEo@0KtT4)Bq!PwT_a?)Z)$w&G8FJJ_$;1`cF}KR*_J zp@tv4A{M^T;4g}WUt{o#W8qs3{*|%t2Mm5`Ec{8pJywR**{I-~)X92D!!vJEfJ|KT zgKqU}_mhHuj&<)ff)?}DpP%qw0DG;G*1{DrsMd$N-BvA+sr{S4M_b)-ewcuN)oWR) zR$27tA3}02;Ov+2f5T^zz{grv9RGQMd#z!Xm1!{5c@f~}FfJ}u*V(%I1`Wq>A)gyH z{3{xc@jyP;YWNd?XX>*1bWG!$e^{TYE8o!Y&PfUo)bPJ*_`hjeZzx5&on5W@i9svKJHGcPGg}6uKKQ3^6;X1uM0H5Cu0ROK6;Qu=SJPGqQ z_V;?--x<2?X&Qb|_iLAiUjuliOFmPq(fA9OE6CqG>bwK+{`7X=0Psf#fFBqD{xaYq zzt-n%TA&XHz_($moB9hPPg<7#ROt4tRg^|C7cab&0|^e)Z)6@b4P{-Z=n# zzvjPB%afz^`3B&bx{vPDUj*L`QDt9(WoZ+}R9*l$_13E8?>4oSP2uJ+UXGAmiJz`E zg*M{ntsy*9&4(KC!*#qW0KcveY^=ralkq!y{LmPW9JOr4qYia={3;x(%En9d`oqBQ z>+5UyZ~%T!i{FOhDdFlSJQWeBYN@Nk^U-(!AaaH07w`y?8#VI7aQAPA1J^8%e*sF_ zEd7Q6^}?;?d{C-Tnv@6iLEwH(Ss!fIt8U`!27HxHJfiz8xaQ4XeQ=@;T^(N+Z7A-Y zF!6})hRmCH`ru4gF9zWYKjQ16?{JE*$<0?(T7W*)@h=LDM~HCl)4AN3m%zr;#k@Fe zu*$xCXG9;6R`21UbIgna^&@tHz~WVfSC#N}C4Ac(U6S6~+<>Qt>#O)ux#A5g3a=_H z0u*nJ4wNj>1WStXxNo5Rsv<**r^gl*E)T3+ym)mtSGk9jgT5c{l5OfRC|9rq3zqZ8KyDlvp^-*5{Rh<(4=!Yh}TE-DJ-Wf$vU?YCLPl55$m;mG}9pFjH_($^lf71+~ z<#9bq#6%bKBy6nu;$t>y*XVOf<$M$?mdy2TzX2W7^(sS?haw&k|MG`e?olt)Ce=pk z^C+_G5y7aq?#HTPY~@ON(QXD9CjABp-(ei_o4o892=vOWK_&-z$}YAlrlFW@7H!JP zZr)ah=NECt>#XIx$&~8x4*6_6SCoxMN%2^0c$<|S0adir)K*Qasj>t?UImg}wXGh^ zEIH%ZHmTwJC-~xa_eB78cv?M3L|tmcbLrWVk+MkoFOIO;FMj_+-zm@Srxv5DO(;_0!gqQ zPwtpYc|y@tRa7*EHk%qec@;8cD9scJM(9MZ8}RfSo-;M|P4yeqwVB5J|2>ZfA*M!H z!>G@Xbitf6HQb!cI@?@x-sq-3qUp_ff*& zQ5by8xlCQkRy>QQ9dq6U*xy|A7B_PE(Pu+X`AK8sCkj7Xa8N|UuguWt^SdO($8^Kc zoBrRf>lO)?W#Qi&%g3A(sWf~@kJWFaeMA2hz=(qBxcX$qp6OrikCDT`?nc2)pP8v@ z%=w_YjC`B5i8+5AHE#OuOoeLB2G1}s*XI1)IQkw}!~FvO(16c>VoY(;NF+Wg1bRS8D$^Y~tI0HjduxhnRB#mFxP%w|^LQ zL^18(Tdt7J*^W4df*b!+SC;il6jE>)G0lEqm%afXk8iHc`AyJ{bkUpr$v1{b|0mE= zMAN?6C+gPpUAq4|j3WMT^vL~8q8R#p4Y#lPSYFy z<~$~>F#h=h15sx~XP|Wh(06`AVa|+881eMHj&o6A{l+&H<|aKJPXKf>4j{7C{V ku8TsyaJQl_()0qvSA6^2H|>x9jvp#a?(4fhahKNr2i-hlCIA2c literal 0 HcmV?d00001 diff --git a/robotransforms/euclidean/.euclidean_pure.py.swp b/robotransforms/euclidean/.euclidean_pure.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..3fe544036c02da1e1e6723982a795c097dffa56a GIT binary patch literal 32768 zcmeI44U}9}eZU_Ik*`1yu$%+fN4CJs?966omb4HPi%`m9o5Wp64t81h%+9w3nUhBEil*GkUMv=H&V!}4mz;( z4FAM8u5)7~*NFuZ3nUguERa|ru|Q&h!~%&05)1qvw?M1D$a^1Ue4Qz0Xuc2Y_&(g+ zUueFqTfoLU!h~-!-#g8>eZI)tUt_-CWFFY(Z!qC0^L=~A^Vgg3=On@^{+)7etC zJel@HO#LSpWk0jZ&*lBf20t}Ek(hg13$0g2Q$Pf`ET{} zK`vid(MLxiJFImKi?U7~l4dEECYjUm^CH+8U!^&{zciJO9Qp34qdQHNM~UAzkJGU{ zD!WMho_4`1Sh<}?Wtg(RN@^um7g)HUEu2sL8Gm?axt|kJT|r8$)LSgCjnr3cy0_S{ zu8Y26lI>M~DzEC?L>42O8j;NEj24!A^a0R-rLhY^BE2D?F8D)1<`86Y`&5 z$fTw-<-ua6l+N0KQl^|MW~K=s&D=DUnvKCS=}&qp4*xmQB_fyGkq3#KBeJUw{nKfG zGV6$=deEqj#h%WTh%Nf$qq9c>rAWN17b&GuGd}vVKFMc&$?Ph>m?;vNnI1BwUClx zQp6lJLAljUagf}m>FjBLfU2CCQKb}sY5PG z4?CNBGwER>m7Yj06t_fj117~tGFL1QPD^viTfrSU~VP|`?d-F^Z=SfETU~)PLB*5 z6NPpU<1X*?7;cB1+s@%C&*-G0WYquqE!)Db) zZdNu{GpJpm^D4JkP|r(}NtqYyR3zGT$I&WNkus;;erX}otY?}b`D`v^O7%=BjGAAL z5FVC7#y#Tkuov zJXFiok*jygVg4R+CREEUAh*ydH{4UsgsN7l@}-A%btyHZ6gpOQ$CsR*J+o?7WTroW zK}Ek{WEoEOJDTXJT$HQXNR2&q1nD-kGdJlD(R*@gh8ZlAqdHXEz)(4Yn(d$xLGl#4 zw>yoVmVEt@wjz<7kF+fl)I_e`kS3I>1saN^q6Kr3b~{J}B@dFI7VIvZCu#L-Mcpk( zzu-0dw4ToRc~iSms9vq6GyX8~#oD^Hm*s9d3eyLWS55gvw z1ow)a;}w0jUJF}(b#Au4zzYMN#9O*_sWQY&I41U>7AO3zS)Xig%kmbS^($Hb%B;WH zRNPD$bVs8BW%Ue(2=iYQx6vIpuC93y>Y8DHb-Gn?NV}%XaL(3qJh{?_lv0gs9nm3r za8u=s^5UnqYzoK<|0+!k)8tTg*{|1{l~!dw&^0eZqo@=Eb=yT%m3i939G5NBgC-sS z?3wUvf0hH>O@F3V(iPX*6jUXn#TM3X*8J8c5+cxFYNIT*`IFFA5YEc}HhF=BCO9 zm7zYlRL@lw$@e9Gv0Rp|S z9o`Ky5I`9&h9lr`c*5wpU34X%!~%&05(^|2NGy<8AhAGVfy4rd1riG+7Dy~`uoe&x zgmGnwx1)eRCRM88)@cS)5|ARGU@!7`ncVwA+H8DS36Tc2AtYLd?^x-_K@-3Y(++h-+o4uNw?9zU z|1YtBy;SzZS^r;X>gFNV^Y_C|a3j1IW z1RsDZEP;F2?_US2;T-rWd;2fIH{fqzC)^AzxB@2NA~+dNf>+q*{|fAZd*M3R4lTGC zeiMe_aCkku4xXcYkHf?85bT26;A8MXSb(iihBa_L3 zg|px!SPaL)PdPL25PTeNfUQu1HLwyga0;9NOW^0!!=v!m@TYJ!RNz0QbQA;VK9rfc3BrE`T984i>}DIdkwd+y#FHx56#(L8!nbFbcm4XTotxShwpiCU;(=44Q}wWdYcG;t zp%jek0KKshECi`@(t3YloS>LHnlWNxWQFOy+AGLjlG?kFBNFl$mD-Oj~HR~`83=@G;ATFUC7s_`E(S5O^EJ7NMO4GnVb_S=8x~i$d1iL>PK8E#m;>i-7PvN z_loT5w7TbZJC&Q~^f&2%9Tgr;;jWfg6E`me<~fgKzP4ISSC;`JBt~qiRsrs0tpeOR zR|VMVR&>}&I5x*efv#v2XvMo{YgZuyRZfqC>X3)&E%H)h`h`T6>=4nE)QzY|Eb{;v z>2AGD&=4EMimXE1jE5@3=Gx6;OfV{+D;ot`@dGWiX`*CXwM{9v=}M~HlBIURJ0f?K zy&+0^lwB0HKRG%4(0)zh)-6Z-@I!Y2WQ)_Sfha8#H5WG2Fl^%3%(nB?R%ys;%mH@5@Q|yTopjHaq%ej`uw&qe-GygPLdeFKSd$79Gj7ne4o^Tug)Q}4ri*gI#dVVrw+QN)ggP|T{=wn?W4mQGioL}C(fvAbD~;7mlpe~VNQpbkx&XG zndwqP5MxQBOHFFjKi{94Ppc7A>^&u|GkS}dn3tFQd1+Cqv&lw!+tTWlVzf)AQ&;+p zMRjj=$r5GW)u3xb{ohtI&~8@E##|6=3sPfKt*z(JPjUKlC=8mLiuE9+@6@&Ak+T+_ z#;}=H!|)BB~p4hD^TI1I}of2Nd5|mzjde(jh0pA)m{uCZ;3{TG zMWDz!CS{&hF%c=Z2QU?N+Un9#ktwUF$dvjWA(3?CT%!9K^rhXZdPH7Yv$8PSrBN$; zcoJVuq`Du8tDdW4zD9>S4`y`mhAQ#pNUHmZ(lByL2XFS0p2~-5D8&vrd9Lzi(ok}o zH;UxU8?n>3x;wM;&!FH1S{)&75u_25&iC1w4;$*ljMWnC|406qtD2H*~;K^1-n-U_Qgd;qfd z|25Y9Ux1yk1FnMw*a+)j4ahlzbKxX-96!Jw_%z%OABNwB&G1ebhcQ?Qr@;^L6FdU{ z2s=Uke&AZz3L9ZPtc5jj9vlTn!t?kG?uReJr{FK)Pv9oF8fvf>*1$>_gzw=mcpCm4 zz5!o?yFh#l*TNRq0B6COa0>hqh`-^xtowJv1MqinJBUxA1nXfPTmVC`1dfNjto^?a zpMbmJ&tL~^ht04Wej8Rm8dP1GdP=?$3nUguERa|rvA{kopx>Qd6Yry01L~LB#DQuT zl=gk^RrXyc4phA#*y&>#{h#%}+jW8Q0voqMybl=nfm#G`Z9VWR=kWzV;y~qqKkK^o z;x%#`x<0rl@L+w3u3t29pn5V{D4#Bi=MJBwaihgtkA(GcplZjkTW>nVt+a0Ev6>@d zwXH*3DIK!!dXDBAyjpo;<71`tj_TqtxV-dRyj(@!B~)CFRG;s`dX-y*5S@;%w0X`4n6Sx_~FR%^d_Xyqv?|=(oCAiS@g#cE7rPXBak}G`bli4shim8qLt_QK5i5gVLnQ5S zA=RB4>a-AXqP^Tk-fAaE&EZzSY>XHQ+e@9U7j~TZk$ZP=lY2X~Np_<0#0JH7s4LqJ zwHn%9e)FRaUQDMdMI&w_J8X0e{-H5d!!Z?kb!=q?iK#Z^9D5ODlj=5@nm~-mt6(rS z^2bj|nIP9xCTQPw(viqHBmO}ciP#5bBo#4gRN6=?sZJviD6nK)SD^pJPNSQtJ7EhiyN?s>u<+V2D&_`Ztv+ogcc_dU8wY*JHR_#}TMS*sr8j)5n3bw;xwHYx?Nkt~RhW8qjVu52p19a8T5 z_ePa&Ku=VL*Y80hp*oLjmU5#`hVpH@hm%d&I#Vhn`?71+UQEbtoqK2VATh;z;l`DF zH@4i{_}wF|Co1HJK2&yf`x6N#&jEQJlZ|r8vx@Iznm1H8ac!D;Ac)`c<`XypXcQh-bT9%s$zcT*tatY?;E1v2pay?wDAr zSD9T*7_ZxQ&C0W!nhIhTHbHJ~P0)VqtW=R{vog_xQO62`*O9E8EX>+-kFoQO`dDLh z%F&Y?O6M>mo$emW-zPfMh^Ed((a=((J-WvMo1xnZI>a@C4*6ee1359GY@n>>w1vQAxzX`iR{x0BFxE|gEGY~)-E{5fB0;s&2d?sIs1riG+7Dz0R zSRk=LVu8d0i3R?DT0mB8`V;K|uo%Qu6L(vyC1tYz5w}qzZX>$@P4++Z=_J|Wk-dl5 zM%q4&BzqL?{j_~-5~+yF!6k@B Q_RfvoI= 1e-3 ) : - rho = np.abs(np.tanh( vave / vdiff )) + rho=1-1e-3 + #rho = 1-1e-8 + #if ( np.abs(vdiff) >= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz @@ -56,7 +57,8 @@ def dead_reckon_apply(x_hat, P_hat, step): SM = 3 P_z = np.zeros((SM+2,SM+2)) P_z[:SM,:SM] = P_hat[:SM,:SM] - e = dead_reckon_step_errors( step[1], step[2], step[7], step[8] ) + # dl, dr, vave, vdiff + e = dead_reckon_step_errors( step[1], step[2]) #, step[7], step[8] ) P_z[0+SM][0+SM] = e[0] # var_dl P_z[0+SM][1+SM] = e[1] # cov_dldr P_z[1+SM][0+SM] = e[1] # cov_dldr @@ -86,17 +88,20 @@ def dead_reckon_apply(x_hat, P_hat, step): # print(w.T) raise e - + # x_hat y_hat a b c d lrQ = t.lrq2lrQ([z[0], z[1], 0, 0 ,0, z[2]]) + # Computing sigma points for i in range(L): # The first SS are gotten via composition dlrQ = t.lrq2lrQ([dz[i][0], dz[i][1], 0, 0 ,0, dz[i][2]]) lrQ1 = t.compose_lrQ(lrQ, dlrQ) + # x y d Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[6]]) - lrQ2 = t.compose_lrQ(lrQ, t.invert_lrQ(dlrQ)) + dlrQ = t.lrq2lrQ([-dz[i][0], -dz[i][1], 0, 0 ,0, -dz[i][2]]) + lrQ2 = t.compose_lrQ(lrQ, dlrQ) Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[6]]) - # The last 2 are gotten via addition + # The last 2 (dl, dr) are gotten via addition Z[1 + i][SS:] = z[SS:] + dz[i][SM:] Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] print("Z") @@ -106,14 +111,19 @@ def dead_reckon_apply(x_hat, P_hat, step): # Transform to new vectors def T(_z): + # b c d quat = t.redquat2quat([0 ,0, _z[2]]) - dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1], vave=step[7], vdiff=step[8] ) - nquat = t.compose_quat(quat,step[3:7]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) + # Taking current quat and applying step quat rotation to it + next_quat = t.compose_quat(quat,step[3:7]) # Only return offset, this is marginalizing out all the quat dependances # return _z[:3] + dx - return np.hstack([_z[:2] + dx[:2], nquat[3]]) + return np.hstack([_z[:2] + dx[:2], next_quat[3]]) Y = np.array([ T(_z) for _z in Z ]) + #plt.plot(Z[:,0],Z[:,1],"go") + #plt.plot(Y[:,0],Y[:,1],"bx") + #plt.show() print("Y") for row in Y: print(",".join("{:12.8f}".format(v) for v in row)) @@ -124,7 +134,10 @@ def T(_z): W0 = LAMBDA / L_PLUS_LAMBDA W = 1 / ( 2 * L_PLUS_LAMBDA ) + # Grab x and y in every sigma point Y_pos = Y[:,:2] + + # Take a weighted average of the position components y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] # Iteratively calculate the quaternion mean @@ -168,7 +181,7 @@ def dead_reckon(x_hat, P_hat, steps): return x_hat, P_hat ## ====================== -## test +## TEST ## ====================== D = 0.464 @@ -177,12 +190,12 @@ def dead_reckon(x_hat, P_hat, steps): to2 = ( dl - dr ) / ( 2 * D ) x_hat = np.array([0,0,0]) -P_hat = np.diag([1e-1,1e-1,1e-1]) +P_hat = np.diag([1e-1,1e-1,0.05]) step = np.array([ 43994.76, # ts dl, dr, # dl, dr np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d - 0.215, 0.143, # vave, vdiff + #0.215, 0.143, # vave, vdiff ]) steps = 3*[step] diff --git a/test3.py~ b/test3.py~ new file mode 100644 index 0000000..d49e785 --- /dev/null +++ b/test3.py~ @@ -0,0 +1,241 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean.euclidean_pure as t + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dq): #, vave, vdiff): + return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3]]) #, vave, vdiff ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( quat, dl, dr): #, vave, vdiff ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho=1-1e-3 + #rho = 1-1e-8 + #if ( np.abs(vdiff) >= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +def dead_reckon_apply(x_hat, P_hat, step): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 3 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + # dl, dr, vave, vdiff + e = dead_reckon_step_errors( step[1], step[2]) #, step[7], step[8] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + # x_hat y_hat a b c d + lrQ = t.lrq2lrQ([z[0], z[1], 0, 0 ,0, z[2]]) + # Computing sigma points + for i in range(L): + # The first SS are gotten via composition + dlrQ = t.lrq2lrQ([dz[i][0], dz[i][1], 0, 0 ,0, dz[i][2]]) + lrQ1 = t.compose_lrQ(lrQ, dlrQ) + # x y d + Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[6]]) + dlrQ = t.lrq2lrQ([-dz[i][0], -dz[i][1], 0, 0 ,0, -dz[i][2]]) + lrQ2 = t.compose_lrQ(lrQ, dlrQ) + Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[6]]) + + # The last 2 (dl, dr) are gotten via addition + Z[1 + i][SS:] = z[SS:] + dz[i][SM:] + Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + # Transform to new vectors + def T(_z): + # b c d + quat = t.redquat2quat([0 ,0, _z[2]]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) + # Taking current quat and applying step quat rotation to it + next_quat = t.compose_quat(quat,step[3:7]) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], next_quat[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + #plt.plot(Z[:,0],Z[:,1],"go") + #plt.plot(Y[:,0],Y[:,1],"bx") + #plt.show() + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + # Grab x and y in every sigma point + Y_pos = Y[:,:2] + + # Take a weighted average of the position components + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] + + # Iteratively calculate the quaternion mean + Y_quat = np.array([t.redquat2quat([0,0,d]) for d in Y[:,2]]) + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rquats = np.array([t.quat2redquat(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rquats[0]*W0 + np.sum(e_rquats[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, t.redquat2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rquats[:,2:]]) + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + x_tilde = T(z) # transform the mean + P_tilde = cov + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps): + for step in steps: + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + return x_hat, P_hat + +## ====================== +## TEST +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +x_hat = np.array([0,0,0]) +P_hat = np.diag([1e-1,1e-1,0.05]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + #0.215, 0.143, # vave, vdiff +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test5.py b/test5.py index dc65ab9..f29fb32 100644 --- a/test5.py +++ b/test5.py @@ -34,7 +34,7 @@ def dead_reckon_step( yaw, dl, dr ): -sy*dx + cy*dy ]) - return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + #return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) def dead_reckon_step_errors( dl, dr, dl_scale=0.005): ddl = (dl_scale * np.abs(dl)) @@ -108,6 +108,9 @@ def T(_z): return np.hstack([_z[:2] + dx[:2], _z[2] + step[3]]) Y = np.array([ T(_z) for _z in Z ]) + plt.plot(Z[:,0],Z[:,1],"go") + plt.plot(Y[:,0],Y[:,1],"bx") + plt.show() print("Y") for row in Y: print(",".join("{:12.8f}".format(v) for v in row)) diff --git a/test5.py~ b/test5.py~ new file mode 100644 index 0000000..d6ac52f --- /dev/null +++ b/test5.py~ @@ -0,0 +1,202 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean as t + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dyaw): + return np.array([ timestamp, dl, dr, Dyaw ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( yaw, dl, dr ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + sy, cy = np.sin(yaw), np.cos(yaw) + + return np.array([ + cy*dx + sy*dy, + -sy*dx + cy*dy + ]) + + #return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho = 1-1e-3 + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +def dead_reckon_apply(x_hat, P_hat, step): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 3 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + e = dead_reckon_step_errors( step[1], step[2] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + + for i in range(L): + Z[1 + i] = z + dz[i] + Z[1 + i + L] = z - dz[i] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + # Transform to new vectors + def T(_z): + dx = dead_reckon_step( yaw=_z[2], dl=z[SS+0], dr=z[SS+1] ) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], _z[2] + step[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + #plt.plot(Z[:,0],Z[:,1],"go") + #plt.plot(Y[:,0],Y[:,1],"bx") + #plt.show() + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + y_bar = (Y[0]*W0 + np.sum(Y[1:]*W,axis=0)) + dY = Y - y_bar + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + x_tilde = T(z) # transform the mean + P_tilde = cov + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps): + for step in steps: + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + return x_hat, P_hat + +## ====================== +## test +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) +yaw = to2*2 + +x_hat = np.array([0,0,0]) +P_hat = np.diag([1e-1,1e-1,0.2]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + yaw +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test6.py~ b/test6.py~ new file mode 100644 index 0000000..4142002 --- /dev/null +++ b/test6.py~ @@ -0,0 +1,179 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean.euclidean_pure as t +import robotransforms.utils.utils as rt_utils + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dq): #, vave, vdiff): + return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3]]) #, vave, vdiff ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( quat, dl, dr): #, vave, vdiff ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho=1-1e-3 + #rho = 1-1e-8 + #if ( np.abs(vdiff) >= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +def jacobian_quat_position(quat, dl, dr): + """ + Compute the Jacobian of the position component with respect to the quaternion + for a given wheel odometry measurement (dl, dr). + + Parameters: + quat (numpy array): Quaternion representing the rotation. + dl (float): Left wheel displacement. + dr (float): Right wheel displacement. + + Returns: + numpy array: The 3x3 Jacobian matrix. + """ + + qw, qx, qy, qz = quat + + J = np.array([ + [2 * qw * dr - 2 * qy * dl, 2 * qx * dr + 2 * qz * dl, -2 * qz * dr + 2 * qx * dl, -2 * qy * dr - 2 * qw * dl], + [2 * qy * dr + 2 * qw * dl, -2 * qx * dr + 2 * qz * dl, 2 * qw * dr + 2 * qy * dl, 2 * qz * dr + 2 * qx * dl], + [-2 * qx * dl - 2 * qz * dr, -2 * qy * dl + 2 * qw * dr, 0, 0] + ]) + + return J + + +def dead_reckon_apply(x_hat, P_hat, step): + + # Generate sigma points + Z = sigma_points(x_hat, P_hat, alpha, beta, kappa) + SS = len(x_hat) + + # Transform to new vectors + def T(_z): + # Apply transformation for each sigma point + d_wheels = np.array([_z[SS+0], _z[SS+1]]) + quat = t.redquat2quat([0, 0, _z[2]]) + _new_pos = t.transform_quat_position(quat, d_wheels) + return np.hstack([_z[:SS] + _new_pos, _z[SS+2:]]) + + Y = np.array([T(_z) for _z in Z]) + + # Calculate the Jacobian of the transformation + def dT_dq(_z): + quat = t.redquat2quat([0, 0, _z[2]]) + return jacobian_quat_position(quat, _z[SS+0], _z[SS+1]) + + J_quat = np.array([dT_dq(_z) for _z in Z]) + + y_pos_bar = W0 * Y[0][:SS] + W * Y[1:2 * SS].sum(axis=0) + Y_pos = Y[:, :SS] + Z_pos = Z[:, :SS] + e_quats = Z[:, 2:3] - y_pos_bar[2] + + e_rquats = t.redquats2rquats(e_quats) + dY = np.hstack([Y_pos - y_pos_bar, e_rquats[:, 2:]]) + dY_quat = np.hstack([Y_pos - y_pos_bar, e_rquats]) + + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) + cov_quat = W0 * np.array([dY_quat[0]]).T @ J_quat[0] @ np.array([dY_quat[0]]) + + for k in range(1, len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) + cov_quat += W * np.array([dY_quat[k]]).T @ J_quat[k] @ np.array([dY_quat[k]]) + + # Add the quaternion-related covariance to the position-related covariance + cov[:2, :2] += cov_quat[:2, :2] + + x_tilde = T(x_hat) + P_tilde = cov + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps): + for step in steps: + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + return x_hat, P_hat + +## ====================== +## test +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +x_hat = np.array([0,0,0]) +P_hat = np.diag([1e-1,1e-1,0.05]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + #0.215, 0.143, # vave, vdiff +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/utils_wrapper.cpython-310-x86_64-linux-gnu.so b/utils_wrapper.cpython-310-x86_64-linux-gnu.so new file mode 100755 index 0000000000000000000000000000000000000000..92e05a1f572ddc577f630f4b39018e281e132c14 GIT binary patch literal 68928 zcmeFad3;pW`9FT|Idkt!lAD>yN+w|$AYj-+!e-bsfdnRi5RfGx8W4ztEeMICq9O=2 zVpv+OxYoK`ZMD`~w0eO@nz*S%+X zmh+tFJm)#fJQ*&pm@r0|rr~|0ahj1R8AhoF?2w7tQlrF30i>tVL*e>7;uEALj$7%a zM%XQro5idyw@*iAxOiUb!AYmuD{|pRyVSAWdM|BFN6_ApE`0A9?NaHM_v_T76R0NL zeoePu(|PG$trjm0xNMY+l=EIPI6)d!wT9uP?df)Fy7pbsplKg$(<(AYww#OGo+F;<}6bR%dK zb#*KLjWR!X;bHxjELAk#*Y#KH`mnC|_)OFFbF@%B(0_jD%E@O94HzHYyzw6LtY1z8 z$46>>qo(G(rS;2dRyNFC(NI%k)KpGAqh|hs6${R*TiLK+#ndxKFR5R)VCvj+mn?8$ zCx+C_TQ#?)wr<(nC3P1AaaQrbc?;{8ELgetB5+=?ylQ@3ow4%#6%7DQ9NgGYw`66B zhfq;hHUG>aw0r`{{C1$?A?Gb%j@fwHLTRsiUB(@Z*k4Mg^O!y=hiJr za4a4)cFJ@@8_=n`c_4DzY}4$IkyPWvsk*3a#d$SVb62cfFtu?xHBog@%|z(s%!U<> z^BMrJST(O^`rIXr3o2Hus9(W~6)S4aT+jf7x@G4n{PG2Jmn^BD2Uz8@x`rC1gqjOi z%w4{G0SPLXF0aQ3xXBsy^Bd7j)kTxeU9@0cL(SL)4P^}tD>S#Ni$>2~z7hyEQ!iRh zEUyT(Dr!YBba~W_Ua??q!-4_8qKs1-mo?NaZ6oEF`V~v(sy;yEDv0a##}y^sAy89> zx^o*FH2spgbC(vbtS=m5AUDs=jh#?AYIMzj!U2VY4KF_k_GYSoLZ@!&$8QNg|Kr*b zdTvL-r!luKiC(|Tvv;fnV>BFK4fiQH{aI#RU8(_`*&5$l_r3MDO3$BtdR_PG!@7P= z6}h_W22-!RyIp;kVnVS`XjdPd?ACj!$G@M(FVJwW{x&^tOWM^B(fFn9>WAz4SiAb$ zxNzZ9-LBr_GpAks1kGn*yZSkuT|TSY)q8v%n&iT{mTH%!Dz>+(SNl8{&DhbZ-mmMJ z>~2+$0giw6wyM`#Nd?>2sy-OUhW=aChg#JiY*kOY@IGI*s@Gdi1v=iUUb|jZpQFc@ zvTKu4_0d-K-kyYjf>!n3-ih@^t?H>e?^DvM-m?k9N?X+@d&o#*t?E-+)mOEu#{`If zs$12k#cK^?POJLX>)gUt_1;?2itMNCPa6111OJCLa4gjMzhmn@3&b{BkDU&8vVKQ{ zXxSTE_jF*F>Q&3&1E@aQ(&O()LR}2vFC^sXp$}VHTDGV%9skioug1%Cj7JYW6))2v z9zFE?c$tpy=%HW7%UmFi9@-i&(;*%`bVa;OXM6O}`SCIxhI1 zA~YX*Uq{k5te9zDl%&B*njH5&U&i>({^8ZSO#O&>Qnv5g}qLac-L z{kx^*;Cv|eS?g@znP-DG-ahFMT?n9-hvl*vwV@-gl{a5zmQ62jUSXC^t7tk}Hnptj zjcMhf2R~{0`pj6YoN3|q`8>-F`~P`K0FP8_bw`dx&y$(O%whl$!AXR=hD z?<-sP4>Pp>WeBI_kInPt$C`b+fMV2!3U^*Srm?)d>1g@TuP^U#s0s$Eq9O!uZyP`tQ5&quS8aXMngj^s@*E zkA^1is0|gobTpKP{5iYPNNCe%kYpp}GCvD-DK%pA_CnxTbLQ)iNE{8#d#HOtJ;%gxpKJ}QHqxv~UmE2nh*nQ8j8d}GJ_ie_K_*k-49d9Nc%o-^h> zUpa4A8M-m9*?Cd-n2HIYjU7irvv;GN0J&Uw2;-zkn|9Y0hPqq{0Wp&EzHH9)ySj9a zfhH+7@3n-Ov$dEz8sDlg|79LIyje+We%4yxL*pPH)wP`yzm>*f7?{App+5k+(fSQ` zpd5D&;iJsQLd*7}{%W1y7lXP2hyDO5YZLM*ducizYkIq4{f^7#Ry0?e#m`q1zgE%o zj_QAT(`zbi_9a6Hv2EzN?^$%&_gvY~y_X-NVk(C2Z73)=pK96-yVT?GobPS+zHI1I zjh|PT?;PIl>7)3y@}_4GO^3+tJkae|HvLnJa86u=@}>`JxBRI6vQXH8(q>ZcjuPS{ zPl)bH2$yeLIfj1O_(i$-!QtO;aod0E`_}DG!*nZ~UN)_)>4&nZl}%s8n%+7S^CCPy zw$az4fP>gnv9IZP=)vb=+c0#`uxIOALYw+vIATpN7Vn77+vD}`DCF}!O$F_W(IBCK z&tlD^Lb0X~V@*3_J&Z3gSiPQ#tvm2#Z0JjHE?0cUd!X35Yx0kC|BTAU!&e+=K|a>& zjoA9vLhCtqDw{rm=B-z7S}AWjGNI|{!Ce@~^*cgW`T(tHo@SOeeNn-Yd$%I=;G2o@ zEo=I+yy@+-b-T<7O$W-Gc31S;UEXU?0v?+OMTSLe-Od0-cU~!Lb})#~9}QL0G<`1u zI_h|{Llaij%3^&l4t=)q=?e2ux%owf`HzaBhZ}#Xj5D@z+P?X*KAB2wjTgt77wkXF zo#1Eh`hQkKtZ8o#R}oLs`P#8{6MVlL>JHDe&RO=6B1^N@Vwt%W^#u-g;TD@N>n_k)U3cSi*jQiASO+Uc=Fq>aJ6AotY z`p+-x5}WsC@s8Rppz}QkbK42+r1_q8$8=}o!RC%b%A3cVO|$dAFI)GW8QQcC;{fE; zfoP<;p`TIKbg=Ak)L~B2uVKi_n|6TlDV}}qrbelDw6F&)K;6}&jzj08jzhVBD{CGF zk9E-eqI~G<4OUsx&cjcDdQo#lORVX;Gn&3E{wCHu`?)|_(?1k{$f{CsGa>41qdC(? z-g%A%=UF-(<%G}?HpR}oUO9AU>)97lfdC+s^O$Sj1hag1= zjB4%}fU(8qy;})K+N$q=gWB2enJ;K1n9zY)K6Gy*-0su#+7z#>*P${R+NX`TY;1rW z5U$KT(mci-+K~T!LmC|6SBDnDO|Jhuw0R%Kzm=D4RZs&eDh{Ag^WfU29Giw)h~cus8is6b;iCT27?T!hx&#AZ+xTEA5_I4xWW zg@z9v!+fC_y!ftM*Eb*Q<3mJPx70xPI%Fqo>=7JHpfBG%43(`x9X3jXXX3n$t{=d) zQ*2|&!C~LDv?vA*aH1e?7*SFD5!ap^I0o0BhSqN(>AI&2CN%BG24GiW1i-H+_#OV8 z#~)LC_tz~ghadOm(WeKuvwVl1M}Xgp@}YAu_^`JLO`jgz#`0*l41R~e@6cJQSgO0W zz79p8Lb8L4h&>zSgUgXq>k$?Nj{ny4Hk7AmdD9!oGMB@J9)}4VZ)LxUh-Qszl@Em99NC)+_U>tK2vtKiWLiz#8#dY-n0&{Tm$M z;bkzh7my+t?UBc-3)NPetVK+Seb6@a)dX19-0t$Vu2HM_F2cWt4)ECh$cuO{rN8fC?* z@sAT=UX`kd8PWLL!+X*G4&2uqxE-HT{ZK$C!m~u69^VTn%e2AAmLnRj`oBJg z5>ZnL8m>UC?K`6FyDK1U;gcgk>wv-*6756j@cRcpMB>`>RGhM}hE#OLfrCllsn)yi zsAR03&4USqXF9kEBuZ;Az0j3vk->)G%FA8rsV)T8&6l(ZlO;(`D zFdCLA)?Bq)!Xt6fVPc4mV2B!*wrtski;{K6Q&ICiYC;>H1)G*FTTsi1@;yrHj^mK5 zR`PXE2cG;I7cmh1UbKr!dNLASb~ziZI9p97Q!kb8fmTon4`-jG4WpFTfn;3p0Iq=BC_ z@RJ69(!fs|_(=mlY2YUf{G@^Z0~#21P0@i(7gg|r9iK1xy)Qn2(rN1R%;`Av@N>Ca zZy0k|oEI&QE}XkETDR;1M0?JU&PP1qvXyo9%T_Ajfd2#>_@97-P6n*2n>1;XVm|m} zD9aj`F2AU7Uj2#%g*8hXmo(JPU9n>BMKz6xY+Pv6luemZHnXOzspRsguel8SO(+jkZCiuErq1in>)%@MU`|7c8yo zx4eF3T|?ak3!?KEAY!(zVF5Ac)n5?(-{KNK(I=00JPb5iuYyL2Wf)6UBx!VB{nF)i zOBT$J&OL8#-LjPp(XvsM(F+!=;J8JLR`pmFMObIFVIk!7YU^vGN~`2gjQ@dO)&D0VOaD>Vy=ufE?c~;{=#L^1W#fsqkD}zvRi`4Zz3Efbr#f zxDZ16(EBYd+mY@-x)*8D-*6p*bk2t@Eet)_k90oLIR{!=Rv|6@sHNpzq*b4^w0wqi zIZ_4_EAAyt56thzYSNeEq0G3NiGNr>8_z-1KNPPujQPm3pQRtPw5Ztf zF~RU=F)o<1Nsb9dn|&3*f@`euV9^G9Y_MdVe`2soT$~&%867Mt3l@wDMn?s6Mg_y8 zf`Kt9vXcqOm>)sP7_UfK7@Hp0-_qj6wzKX_JPobta3N#xtL6QuQ?c-TF=w-9w4GXr|LMvM>UY>?%_QaKA<%_&zMAD>bLFu#Q!f${x|#%&f8f;rd7 zvS4(BuRK^K_kbW;?kQ_j$_UWVCU(OX_MDjJoM82s;G8MJ>N3#Z)`osu${^6whN@vh z>Te5_d@)zPsQ3-UJ41u;r+}H9`)ZI<>pCcLG-%TNSQ+*hM%}=hI7~bDc zaWBe`2mkutE%hvasoO)mk^8}yl>F$#h%rVSAMbBlYBj#MF+miY`e-z4p53xWGXlC} z-agIy+ad&usZWt+fho!+L?hjh9_r+anka!tI~R3-8!%6ayB zB3SD>@9*!tI$m1vt8Ky$c8vEfry%hiiLl_?uz>EfrJO)4$5dTd8Ga69x zK9sW-PdF zHQ_%!Lan5E^(zheL=TKOiIdT=R;vPR->7BmPJrrH(#pDJ#&6AkK`o@L(s{0=Czu_hKag8kpz5g{z_AHAwcy#dBLjXhCDDA zgH5qY;uJ36gNGnC5huqfky;#(0myJgE9c=qmFaI0$0bd1U4>LX(!) zUuaxqKBsAa7N;dA7kZ_6KWa&PSDe;u_vhgGy4eSa#D3DFH6#Ih%pagIBEIdB8UDQx zUfw5r0Zx*C#z|brUGhN)LYfrVqT4&a;Jo@;CPP!C=|PB+&V~F_W@#Os9;cD~iHd+Z zO4~F5l{{8^9I zkOXuV{6Q50{zicEdT#1akYO@PaafB|A4 z1SG|10^HI0HQ9-HB_b7BjgxVI5X5_!wBXe6zTCk$l=xnXl^4;sv z8VZnWZP4;P<&hb3F|tM0EO2FOe~nWpKwoPC0Bq=3f}#xBQP!WK6jC_ofEJB_)2wF! zAVm)XTpe5wCR43XbQ`B7C1Ztv%X?)@6`Hlnbm(j4~O#(}sbT;5V4fo2)Zo`RwJlZMeXs0KM88th<^8 zwJI`A`v%&+-Fg95Oxl5jGNYv@^j2#XteA~YZb$nxsHXZK)wB(5Xf*?(RQdl1ZPQy` zPZVYnFGCV#g8#Q#zQ^0Np@k&MqZYShlx<&|hFk^@TgL#Ukl(anU`Q?pFIdO%=6V^z z1&J1ofM+cqdPqP40i-wN2ms!vdDd8&pdjF| zb*=_nlc0DJW?|Z!HQ=rU1pz-;w`jnV35wsN@eDhlb?|nAf`E`Mw1s_{pm-a&J?+)n zxRQeLo)gf`{uu!5M>hi8o*x6N65FqPK0HA|z#uzakI~cw#aZa!ID0ApJWMT3P!KT2 zo}&R95)?0?gR|}Bun1E8DnUU&wSB1uY)??|47JRD4I*&#UrkUDu*g0D0LA}Dg5oxG zaE;vzm5?G3(mmG$Pv~lUDc&UONhmW~2fZQkwf1s7nabPI61v4M!X8|;6jQape_W483fjS@XD)}BcZ4Wk=1w$pXIN2$ z{kzZ!D{Q5b!e<=V1WJ^9n}v~ zmMG=HN|f>xCCYeY5@kFei83CB#3-J8#3&wf#3-I=#AqI1#AvQUVlH#yz%(aW5?@ zxn~xY+#8EZ?t#TP?sdgD?rFt1?p?)1?oq`=?nT8UZal>#?lMIcx0Ira`$sXEn?*61 zJ3}#r+dwgedp>a{_jck;?%~8#ZrH?B?#{$CZpFkj?z_ZvZnDI5?x@5JZlA;q?v+F} z_e7$admk~A+Z!>HI~XyGI~6gDI}&jgcOK#_?l8nz+(d}8xK9vgaVsEZbIBL8xwMP3 zxsHpoxoC@XxI&9_xEzZbuDzm$3$2*LRaMO45-R3$y%ck~IEr(*5{h%V?1_0?l~}-aNi5(ZBx4C*!x?8b?zEv!tBNa>OFvU_jMzM?zP%NXP6ZQ0JqMk0SD=&o2-s#sPj{)T; zP}+^xBhF^EuR4Z{Sd}rd#z6lm;tBlWd3G2^y6SGcx}s!qVwtQ@yj+x-SA(Q7j&dSA ze-M+^EKm9rhC%p>ICeXR{>L$pW=YaIh)Kko;)sP1x>d{F6=J`nSJAd=v2C-M$Ru$7 zjgGbdVNCPpsaV;3%Zyc>Ndzsa@5Fr7#;RTvrvMe*@c334s|K-REDB|;K**l4>U37s zqBsXn+O_)YGO`Sq)8rlIw17F)O(r9m8Zf6InH(^ykxW5TRA&3%={MI zEVTmgCs_yJ$)91EXQ`Ti7xif`HfE=?sWSnuz>{(pdc;q6H!-?HLVJ-hCxciFM7tV~ zk#bz46>GF{F53JKM7tj-_Yo~rj@N2}>WsyT!;`3f1W$*VfPn83MZmzV77`e#yMfKm zC2m5>^A%1Wa5C_u?$;P+co>U}6?trSCZK2H!N;Ltw*QG$^X5E!iwSj?cOiNcP%ps) zWtR7*=6Fl{BrB-Q^1-b73dK)YRc(}yV#P?T9{usyQ;hLpvRjM7Dm*E>`K<;%eci;E z4HJRzV^p_!v&f~$NLdah{48=4<8BviqC(pZlpT0dJ*?Rp3!0jwwD1L>2g%6jQG-6@ zVlfKi$vH!_Erdw>!4gI(F2#Fp%AJMrxgRhmi_3sKO%EQCQ}LV>`9l0Y@=}fbA-)wd zdUAS^>=d?6*$s!Yy8W-#nm4CoHw0Ce!qD3SPn@W|nj#m)lXk6_1ZUN?KA( zd~ODovTBOaPtD&Z6xQJhQ320^8vQ9${h`0T9Z$+W{lzxj5kGejYmw1k3Ht;v z9>rs%Zr5mfaELNMq3~;^4~SxgYs?B1-n8ifsb?3y~mpTwG9p>%_)S!DPf);xt0zYb7)_toH^ zdk-u#HHW(3vGE8VqXRpX`x-2~v+`8Ev04@2=}m!p;s*%$F?;aUsmq^H*XIqqxX=y2 zV?<_Xy}Ymb-uETcNm_2dnwnME_Ne8-DCF*kkMY5HLw(h`3v;}52r9ZRR&K~J+J8yP z4OyTM_5i+DI}8J2$lb+<-0eSpZ^GTkMX+mYk0R=_I*7XsyEwpIv%Cqrc6*?|7D$GC zl!YNl+ejg6x}b2XDug9}jKnTcg&a8)4D6w*5S5it6o#onfqVq|w}-1jk=#trJwg>q zByXE)t5k&sIRyr1k4tF)w^gzWwm|k7>61}dBc0ADObk_{uvQLZqmu$P;I>ZA zBJ0VadK9jb)5&0F>KdSJk%KADSsg9{WSe{qi@rTOvJQpYM7tGcvA0-saGU z+|wU^#)+rDkb5!=xnIYll4r(lfus@gLCD7IAo&@3nKUvTO^2s{Lw zq|>eaVB0O6R4$9q?GbUBir`X8;L?myg@6$#22Rpgi(fB*W}+;_Bwrq>yc10v_(Dh9zUn%%CDIpkvNN!H)q0&t$BUHLMSd z-;?s7O7BhCqtg3Qj;Qqh6dNiP$q%ITQR$c27b>~G&fciX-()|m(&O3uJvNd2U3L$6 z1(E#U*&nO&zp^b={yw`DX(q!fQdD@w(-_vTVIw9p8lb`}HUf`}q{)m1sPKw+fOrZ4 z%xHiLuXqvVQUaLK02N;G8p<;XU`7K}cm>U11p&$)T&Yxe1#N000m`^C=ht0eB>(i4YA^^dx{8Ljl|n4N{yQr$}drhU1245OZdn#D%ya8l+hnr|~gF z!`WftuSIZ44$!7Jkqdgllnm1#)qM#nMq@bNnUaATqiPbZ*i(jhH5w} zRD(3f<1{Wng=(;!H0%Xj9r$<%aEeUHU=7j~6U2=9B32y3h4(cj!!<}c*(23(24py+ zP04@_lARx?uLZf`Q}EMG$&d}wZ;jI{cvd20gVewAs0{^hLpDgZ%Of*<+=w}Krex3t zX+DV4xS$25WY`9&zDrPXC+4g+B?C7|6@hiS{S0HFH+%}d%9IS6twUWX1)ApRDQT7&kOlHnUfzTYD?(iy(txZxWldL~Zf zLfr5T()=w!!|)Bq4c{QmcL^E=ali(oPa4Az(Jxyf|xOU3gj~-LpX?B znV@2jhLdMX25}I%&ZE+#3f{q#4C5ealSissWweIVT}TFU&=T(S=nbC&br$?T6BOt# z1Sv1;f+9lZYmoY?)9nUBGn`>UGMwWk_{^^p3>9dIkPPS`C=8i2Lj@Wjl!|OcRnp9Rx98L3d7ps)S@%2SNPiOEXlUn2-$YAc$W~YlaNdaFz?n&<=vGPcT%V z#X>T;gP?~Aa=WZR^Mqu02SG0r2I7z#8s!BBy&6O!|URP_mlyv}s~AS881&}NUJ z=BnTi3ONgdMfigrS1qf8-!CKsJ_z6AvDN}JXv29~Nbbo9KhloBf9_}_$N@CV_W z+wo@rhhs_={z3SI?f5JB4?;2kgz!D>_$&B#LNWw|@FVT`-$AdJCshy#;UR1~Tg$KD z9i$2aA-q4~t>jnm45ruW!d+!HcB|1|fWNJN^pZPpWVb z!XIqMpHUyqPM>5z2-W_A$KUWN(33vNkPu4ru}5n782RD6;gg(u%6f6C(gUVIdwr5& zA*9M9$TfaOe>k7`Bm+Z8H6%f$KnHx1p&>+`oS@>_$2snk3=SdHk_43kedUu34&0o)J~l6~iq89s)H zI7OCZkO*lqaTL>yDNtWaGE9V2>Z?v>3?HLGoKco!pa`kPC8!kWG)pp6gvbjBa;X>* z;!L&VC%UaQ2`UAuvLwSrhiWQ3&edZbz>iI5Re z|GN#f)=na1gbcdkP^M@TFPIhArA?M(&&uq zDNs%1a}rdHA8~rxlA$G}x+p=VK;3M~;1W_@o1o%lpi^Q?hL@1)!33284YDNzOi1-Y zf{Jk@&Ny2##AGQ%{y0IUKx1slAQOW4NAkK~j3seq+mc}>1mzLLMh%|=Rojw*CIk&h zQ1OdxXPGS-YC`162`U9zWJ?B{P{Jh%s@tfIHMV5938}8}sC0u0zS@=yI3ei+9;ud< zAtlbWkX28`m)g-Q_!e6-=!Ep2#p&G+F|5S7+m_`RUe-7`HMh2H1;5>v3_KxyU&5Ku z?K7&xdEAx^JyE@GL$A+23h7Z>GWdkF7qnrbkr-p*ykbj+pODj5kCWk3pcib(02I>m zrct-gI1^{TEg6DBs^=0^3iO^W8H7Tr0|_dInK(yn$!j)J30(cSy;i2+Q}8cr$v_m6 zb|ah__u|19qFwp?lA$Q19~Gysg;5wT-0({Vqmb;}IK2z!<)@SFmkdWC{iPng;ZvY= zzhpoPNw;~VhL3S4PJv(Ydk#|lAwi`;`F_cu6jHqsrz&JnN(ezI9gbk{nKVl{6yXcP z`7-Qdc#rYT!OkG5Mx-+(0x!W_gtSFiAj1*mFnJ|r@=DU^P>98nbF0&K;VLODQ(egM`YdsKXBL9qeO(P@8)JFnlQdff=~Q^brW#N$qr+5;VA2&L zxDANBb<=JBS1PK{ks)3Y@e)oo?v7N4U9j(@+okF>FXj}9YR^bpg8Sz5<*E?CU7M+1 z?41j@Q&AamV`F+U-+|wQCf(&StMivHi?$}MS(OyyOd>a5!{)koF6*gWd_0+Cuz z3}pI<)Z^3J_KJ6n3c*P01iMIYQXS~2YC&(R9J^!Knc$Tc z#10~Tl4@v79ErLz#xd$C2T@P%_2ljp_u6uwF8@8ny{`Ny#l5EdIK{oD{4~YAzC4(s zt}E63-hx%uMLMVmMR00AswEe1)M886N!9VA$9mtY1~v*Y)f}@ zElgxic6giZTmtoErI?xb!C(SUV??sgjV!_uCs2q%%U&Ge7af7e;Zm|2GS{I#8)8Q$aDbLFy zGS%Vnm?_V~A~MZUL1##L$`z664v(}+poal*bVfIoILYgDDRhA~Mh6se&nw5F#?) z;dy~64+kQ$z~M=NDYyM1QtK?y=`|`n&v`(nFR65)^O;V$;TDlPhZ}3AlU2IN;T~B; z7CGDoi^yV!dtRp8;EKo+hr3y(+`5X$Qioeqrre5($TEjpPNv*iib%b~eI!$E8UxQ$ z8KXKLi{cxd19(jsiP~*u?q32ob;tK$yJ17QJ1jFF-b2oU0pvcF#$88_ya!%9cW0Qs zI4ai@ZD(f|3glGSZSJ$-Jw0$fmPasXxz8!I68SBb!`$6zhXE;-Povwp&!=_liJ)+K z3Mg}5$cpyGnOS~H1}_Dt0D>R^Y=d(5X7>POj@(Dct2w<w~6ax40g z`&RHA(5#Z9DBIgGS|r?_1uPs5nyzLOpX+7@{S7M|R{rjJ2ko4lP2-p?Ea zZnsIshvn|i7=~WoD-Xh6a}TI)KO|%1_DOmZy0Bdqvz=Uc^YN=Jnb@Y+bsuD zRbQ%Z@0H&%?>7m$5&Iu^RzuhJhuVZVHjg>NI5pwWY}h1`xu)}!#H%x34li@bxv z@lJc8#D7ITKpx+(TnU=*L;cWZ!0c3nA^RbH2bhHcLFfLR{t^l~W~X&s`CkR7;W2}I zIX;FN+y_{J85}`vn`S6@3WmrG9>TUWSD2|E0a{`POF3lH4E}+`WCknP6`!ek88d?g zl+rSl099u2Dnf0ySZxL$qe}g5agG`63L$a>ZgHU*?9A~`a*NB&U^ClIHkGBUGJ^*R zO*PZY(9JbwurHw@7kZT$Tu5lx%&afK(3wV;i_mab)P;A^Odmo)ELOcWq<~Juk_-X@ zhJ65~z<1cLi=~n#-E%iy-Ezdra2m8g!&XKv8iE8E@^zv%Dpp}5kO3TVfqVy`!26u< z+p{Aeu{-0H!ZF}u@@3eh@2SRRId+8NvFy>PwqtlHOj@JDbkPI(6!Y=yg+yBFA<>i) zNE)+-4gWdxb7Edk%vv;ew})v2?ty9$ocl20eXGj z`XO}!GXjsoq{Q>#cM0217(J1eH7yF*3t8V1_B~!oN%RwL3)_?!DIAFxvpBGUd~RP~ z3Kamw?uVCB1AR$?K(jsy7bac~QDK1+QoWKzBMQ`UA>5O-h#cz4VKZc>|Il;~Qqg;} zt|ojl;Z!ZXh}(ivbghz$(WT;5m+KE~;WamZE_M5Q7Hur>XG~o2hATxUdi^)u{93B^ zt*kHE%GX{i^b96vP@*X#u!8cwos|oi-32ct&%ijQvZFITp&ri`*_;g}7R3{nh&58}$kP$9+D?_Q^RwVyH#WbiwiJVBc->3?u@*OsMfxAG+RO;tK1*wvK$zYXY zT`en!c9AN~k!Nr;E>?ww@)inui7G6YJvlV1RbiDpgDSgJaa$vUaI3kOsnNJfp2~JE zSCB1|VX?VaD4K2ZAr{uE!fotutSx&uOtqS|)X0~&UDjbxz64I;+U&^)Qwn-I^cj|yf zH>*5W@_}HzRrLTXd4CMaFBAkT`FZHVwW^R~8iD&L_I2_O7(%zI-0Q<{VI;cs!2lnp zslWY$47*)%iy47^w2C|A&tZJsa&qqq-va17%C>?M+^uCh z!hOy?TDD(NRrh9aZNUorE3&&!7J??wlV*8;&Lzm(Yw${;&$s~@cakWF$08gqB<>c? z{cX4mqU}eObhy>{ozkWu?`C@sx~i3Ta0DMxg|K{t2KD=3JxFqlz-V^tVRJ`3si2%dF=x|=oH2R3JoPm+aD^O@ThCLJr1!;iWYsiqn z%mp1&!rTzbIbhh)Q9DwjBYuC{=$PvCgJTGET**Sv8Hz%<eG zH|(py#y*Ay0}be0UWU7*QR=+j9oe*fgstYmb_+W74Ug)FR(Tfa)K9wGq}L!%r^3)! z0K(ElpE~sq(m&?NDKP#{MX4O2s4m{LPgI2>*#mQ@(PF3N5p);lO2u8cp{)%w*N5*+QEMwB+T(!;1Kc8Lrw1FGpQESUkqJj8Oj8@-+c{+ZBr5C zIg7gX3p8%}`S(u3|1L%g`q%`F?)OXf(WN=`DCB&CG~qgh_&Y-w)BinWG5rF{5&n-*FZ~N1>_pzJ=< zl)J&sIftw#m|gP0s`o!2Ty%;Vn2AEN1IU?X?$41olDDHHQ_Z~VQ3xcbp)lP{xfz8p z0vDjR?vu<=EsA;P<7M(?*d6e8-XO5b%wC5=3hT*EBd`_w0=%M}J`W(%br>?(N7h9_ zb(NX*80yqqeHj_|s~0uXoCndv?oDR!uSB5z9V0?~D!OL`=Qa#e_l;)A7y!w7;pMWR zjke0EB6(=4wdh^9IqS5LwG~G9w8D|3{kH(3D~t+TthVSK=jJ^kl}ARc7~R&G4t0h~XUqt0{pmdfDv8ypjA{ zxTH7D&VNPW-sC8u+@SYj{2!-v*uR((M%`S&f*pXa;A^f}9`3n?w zC)dJR9Wrx|p|Cgk02mxGbC092FL@6d{Km}t0fqg^{7UP4v$KFf987ky;SEJ+KMG$a zAAtnPBF{nLc<@H{G%R|gp@iGDe{cY^MP4?F0WYubRegQPz8#(Wh>#NED%9PmE)GJKZmNf=rRsa+_F7IXdlsS5{h%o;7wU5 z_7z>GqKI3zPEiyG2-V5urV)J;UE-r0Wu{@%GuZT;Ha(_}v zGX-Rlmxxe33Q6+b$>=LSHm6gR8}BPouM{bb;W0?|LS}=)jB3o`*T5!U&ExhtN#0ha zsExF5U_;US)MoDmpu0;OcgQ1*v{$3psCLa{3m>5R0Um^}G~ z3eO& zI`T1L>P7a3O)X9<0lR2wx;ad9b9*{{bqB*Z#YvwL#ekWARqYf3lOOfpY9KXl{&ocH zx6gR|p{WLmF($l`bua3xnJpd(Ab*M_hNrj^g(b+$XJIM|*CEq{XXJ$_EYdv8IUw9= z-3Nh^)}sCyAn=!TQv=;p^Tti+hK0Z5UX9{ucLC!fkJ8JycyN1G;6t$K^AwPh9>wb| z@L^=7+v05=9h`;nij_B9w|D>;AF#!ob}e4O7Afln4KTe-nr`w1%YUxN<``J~lWeX# z0h{cxUgPM^6(B*6lH_wmnost*8cdtL+XbV;mN_*^eiTQ#RwL2qcWI;xh-4NS*_FE0 z-vM}70YSSTK93*EoNPJx`q?zHy)OI%f+S<$R2$nho{{}TD>j85xCpL8voTLIvfpZj zbB2fWkj62xkF^3X@xW{1;2^d_{7`_69{7mY$<$u0z)CisC!1l+R6k7tTAKYUiWXY* z`~t9LGXBr!oQYZh8hPq`U0`#HUjV+;{S4qdT+2D-{am&BFK7TXZ@zpKrsy|tNo)HM zp#=l`FFZZYfkRq5oK+0oPs07_E>;a^RVJ(W$3m~Ls+3iEta=y4ckuLGX52=<@CEYxOOd`4j9;_d6=uSp zyb06rxnl8SeuvkS*2L5Fl$iyD>3C9iM+rv2HaK&Va>^)5o;djt{9lazVqN7?^0#y9 zNVz?#;Bm@JQB;(NJxcx!;SOu3N4W-6t4X=99p!3JcHRVOzws!&43FCU?6f`ump(TD z#|Y2CyK|J)=vOYFC#D)c*qfH{;1==RG7Jk(6(`8=%`M!nUX)j|LKP27eaefSBfAlzeNEVS4=a&H5P0m+odQYKLi_5vM$GHeZk0kxK$C=?J@8VH1 zdq@_M6z8J=eSs%+VLQ%Lo6(ut*za-nGFb1`=jTaFO0{Mr*D5^ys2LB>@-iNQYLW3< zDR@$kMO`*tUzC3eTQYvgwMcMOOrq0lA0ro z{Lge1=HA~`?PPNRX!*h&Uzr6`tPkDOy0{I0lc4OctFY2^g8M?VW-%%8YE3y+qZKKf zX>4;vf^vqYJVBc|p8McVD5rDO6@ZR7hZ}u<_Q9HrDE-c6@KIYq{DuWLQtC$4`)>yR zf(m}joBw;P_RB;2(RH2!P4lnBlwTe?l2sR=$T)WT(_thPpalue*oPs)SsDC4fT*rW6^p6k8LIuBf0 zx!&m-)7*_V8j_x38+5%lga0->Y9f0`J|d}U^&mj}GwalQ+li2Hy=Qweybhwqq`V5v zc_+x8^f-G+7LgR^HvxK;od490^QFLWozHxa^9QK8AgR&g{11?QoV|?a zNhc?L?6oovEau`-z4!1eFXIuY7MB8ze-fHHtX+$0B(wMDK{R~mdh_8%TD#u6TDx92 z-6^iqt%lQ8t~X|MH#@rIr@EwcgN*ax2d?)VReNFwI$EQhpP-!UQLZ+&Y048g(C!;F z+WiU2I}?fNB&e`7IPb9wmK^+G+mTqx3S6SA7Os)4`>cyZgkG zZUf+jNe{6Ny1SX+KMjwXJRXvdNXnF#0JM-I#M+5K;oWKZxhKO`)bvkE9;Z294zf!; z&K{CQB*ppX0Bs`Yl6IUEj&zNNm^Xu{L( zL%g@;hx2YTc(tB)_q3jOF}3BXGP-}QDQ^WAHu(7WrZ`g0(2yK6Xnwt18e3_O}3DHEr7}hm; zc*@YO4keX^=IId`9M)A1w}y6=%Yu~|BO)dM_@gQr7}nJUW=ds-=za4oEutubNL`|1&fq^i-o59cBO5A(9XsrN-LDjali(c(H zw;re7oy_8lDdzT3DbqSsr_4;5q59OvGKxL3>dT>xs_K5q>@;_{%R=My$cV_YAWhC_ zWx@(W8E|SVak!QC#btr^5;kagHfYDK#a{r@jvxuBagR5e)Jin0I~>67up~?a@=wXq z8o`$(N)ZY|Kdpuz=BOodDR93OO3a#YYh83TJ!PcDWmZ~s%__ZhWuhY)Co-u_g-Z)+ zJAblteOIU5^v+HgYlnC{N@BP19M6Iy%0A*2j7gl^rVnCf*FX7Y@X9DJ%cSiivPPM* z>IoIr$yH&lYcVBINar{Q+DUan4_z`a;Zjmu>mswLXMSCk`GH%v4AVnc79>h{_Jo;y zX4aWG%=b`68kgGjUOnBpb4u&!LhFJ}XJ9Cq>E$y|>*`PG>Z{C12+>Yuh7<@5ejE&EfR@NSCJrqAPVG~qcC7n-Viqk&EwROznTf5;2%1o?;-JGEf zO*P~i8UpL!a>7`<5|;c)%|LBS)0jer4~=>WR@~9F02sLb=hY@6uowFtY&Kr zHUC|Vv)elLbJXOFyW5&JKK>3H+YAIB^1x=A=D*-gk(ey0iY{0L@kfn#=HR&qPcxo- z@H~R&13bd)B0{OSOEOILBC$xpOQ!L~Ut9C>)>RDRs{$`;0$w(AvKlY51~0!=Xe0^m z_h38Nre)dVGp#~9WaTcl3M(vYy;V5WN|qUc-9BM;mi^cIOe-v>zhzl+@#7!aG6hAD zWsI||wN{e7&PqqAqdme(!j-rPq+1=Cj<8bKS!ADD+fZnkGTpR#%Vp!3D~v|hTFJIN zzt&1xgf^t?4Jk6L&bB!YZFP~;ZneVWt;|YrAFtYC+8M0CSO!K~5vE|>ndxx1I8rq) z?SHzpV0gBicQn(=ecnn9d~BTp^xP3v_Q-KopEN5M?{R$hQ}0xCqN{18DfV0W&aj57 zHqu;fBdxA14zqHYjC3m%VxZ8K$_~3IrXqVBN|iYc(1mGdTTUeo+URo>U2Cki@aq;~ zaheH%*sVMh6=_!9c~<%ZR^A9JeXT2p{WGhl;-$Mi+%1l@da<@pDOpzQ#%CZh4YlBi zL`=2vn2fW!%yfBSAP7c_3T?PcJW>;1p@|hrAPT7>Rwvu6uC_+mFct5YpEDBzkD|a^ zJ%Ov^0vGC5)Hn@?p($nMGtmOy`o9zSxBq*AZ}sH8)xwV!CkgL2!Lw{LP-|t>SYdRj z;|;pqK%>=33#o<@7O09dT$Q+^Hx4Y%)^;bxWYCHqu#(oUwW4<5*HBHyNGogjIIC0b zNZs@2tU;Qo8k`Y0vY^YAZtZxt#aegZ8mw-FjnkAf-CC$tiB;`V4s%PVxxf(~iBhXQ z-Nn&kUFps?^DW35v8<1=kwS_qluEcCkdBB=r zuh+wxk95LgR{l(DLZ$cq74zY)AReEQm0@)>?FOyK@m99(aXQm2T8#_ZsF9FrE62{V z^4P%kHr1pbI0w7QWky3Jd3$5q1|qcm`{KZ5JY zwV_YBYRgApE0ZvhZF!-&R^iEH(<)Xu)AbWutg$SPa7z#9R;})=9B&O}GR~df<8-?V z+9=$$6hTW7_Bg&DKo>jMw?1yAVfgIlt$Y|+k)2@;9ARaVoxR%{tWwh&!*q)`o~oor zcLa{0fK~D}!Wz$HymbnbTdk2y#(7lAOW9Yr_^xvhGn9y}g;Mhv3W8>m8jy@oib}QD zV%#0Gu-2-ukLi)GfFe7L95JG>8Y|L5oRqjs<#4??(K3ZK-d(1y0mhwp-owM?$-?a# zmn$w^bMSEa;?h-!dbM;FtRYYJdY*L?@se}#^7WG-Uxb`}K3}Ww@~`2Gzu+I>I+w(C zF2Hpzz;!NJeY?07Q0q3nh-`7$OJXkYd%XOQ+q+*1p`pTe!hpYe5{ylAWo*0lz~R?zPwGNg#dwOmu9{GKVydF(`d&WO_C*|m&u0E0!pvSqxkRa z%%jMgC&{=iJq8A#BF&;4l&^4S0HE$I)D>YVwh7P*d6D zfZol9x)C!FwXasP{av)tt{T$Km%2lG-~_NO8usA{U_aNeJqp%#xbL|%KHPIhsNv2? z4EGM&$A28|Ce8XU|0Cwr8uQ8jj2V_2A(1JQI7ArQuY~yjI=dF&xT^DfclYi?Z-Hr; z%rK0gq|+&}WLcIBozk$DR<>$A)~l5tV0yXQy({f_U%q=+mS`w~77XDL69ObKAP)>l za7kkVgbv`w5E2N)#7PK`1c*C8AOwO5ff`ew-~XR;?%rKXq0@`eIrp6Z|IhzA|M|~- z?WwhXK&dA>F8=h90oF%Gml&6PItP?$g7$~PwFC!OFX@m1_?Ob-f4{U~pvm4R8F}W5 zzGZCW-!V$a_qd>Rlce;@(v;*ZdsRZdyfma5^BF<=6R$`Y3z04%YQDf#PRncYJ7}8o0b3@2!*fBdvhzuY*gkUlv66fbBqMFp8zhw^?}m-|-YUi6=$qMlm}! zS0fuw1P*PX$f>NNg+=`N7t)ZoF4Fh3?7L-=zGr0LmE2c54}M>r2j^#a9<(}?Ms8s) zE?HX7(jt#Z+82K+Gp-oPNy?#G-L=+i?LHD5-;m;9H`UC&2+F&Vw zzE=bEL_HAX^OC$(a(3I&oGGu8p1g3O^yJ-);(GGS(m!urnv&GpzsoUiS{hP~`HW&$ z`t89BvCN&A2?p2u^Z@+$1!Q@F6PA%rhXT82sPS(ChZ=;F@1Akw`Q~6CwB>|-!Bcp} z`E20dW?w0ins#dXtl2aAmiMjdSU#oxjjilhPXA}hj+xrFykr+0E9DgJe%766vn zVVk8Hl<}c{{58vSh14{k9+hcmL}Otz49tc+HkF4|5IeENFrq-IDhTwNRSKe> z(bB~V6asE@IlEZFllhr+HV+d{6)Hw*c2-cMHVaZ1h#N9W$E~rtifE@w-bI z4KKkOkRxvzr6QOrYvq)go6HroOs-h8nN%+`YGpyISQ6N0q>80E5+7owCT&M^rp!Ek zCz<7-k(Ky1Xi80xqJ>sh%Q37RBb-^VW*sx*ST^wsP4wUwHiS;7R&5i6sBKEi*rYrm zbJcaJub_F%ppp7qqEa>F(Nept1u;VRs%&}6woKxKEGU@~(q|w&IP0CBE5U(l#mGPm zkCu02o#`4?SLK6NG9~iTayB!k<;ef}PmL?N+JI}AlH-(>%}F)FT{2c&Dh0n50A{j< znFOd!tz;hS<&dTjtjm+`6;(cjroAmvA08N~EmnFaE_87we(A=<^mNVE2X}TpBWha{wzETxU>C4Ns8m&k8ne-V2S=$O0m;n`9h+7HS z$Frb7^NM`logGvo(MNkL4rXijs#*qP*?4+Z4SD#O7V17h_Q<331+w|Y$!!l zlZf5Ol5W(437YZD1&WL{ishk88u`7D7=E|CQp}Jak_yFWm}D}p)}LpzESR5U++MB< z2vM)0X%SP|GQ2ZyirBP@W}c-D8}Z?Zabq|-vSuJED6va}l2IvaD-?GW3}KH|_++|t zFs=&vJ+sko}im03tE0~%QYAwz_J@aaw?L<-oOiIbW# zaWQHy)0EP39lC&h)CxwbriGtY1@A!83CJ=MnX$xN?d7_+T?~eaXwH&|G?`M{jMVft zBclj+ub`;r6nB`I_k=5*`wZnpv22>%8vKb>R&%U8;ycA$c0D;D*WCe&M2sxNfLNi0 zSVf z0}{IH5rqz>=`Q$C3yrFAY(i-91OWy-(-i=rkLCim_K8GAC`z7?IEuw%Vq7)I5lG<8kED!MxCtC ziYvDim?Nd2rqXQbCmeFUb;$`OQj!y@A~sX%$K-mTb7Wdl+n8g*YHkk7K$w|u1b3FA zE(hUuISA2|gHRQrfbu;NJbGEziZjytBHDncJS#ar^wtr?+3Q_~MQ7C^R9Jymh^`*g zBwJ$YjK;SZ6Qe`@V*@d*yEi^JTFFmZ_K4+77t>{pde>}8#<xW9w9Id;kEdj z7;FGpJ_1=edjX}{#?Y9NLaa&6Aki%u*zQcHiusahBSg?Z+?uw`Tntddm8p^?}?Y&aQZ(Gt<2@fZ(UHfJouf=SK1 zQKmANqpvx~=Z5knY(WfBj1a*B((B1{xt6~9h8XOG7 z`V+B1SVXAZ$P{3e;-uh%%!+-P7T>ZqHfkhd$%(`$V-1Zmmgy98Ijw9_0*!cvg_0df z2s<)1Ff=$68yFlL9v<5?G`bcr6&vH^D)|DC9Eh7IZg*Jbwj5GK>AR4r6OtGgS zY5*Kl7mWooZ!!I$(Ihlcr2S@Rl9;EG0n0+;TAs`ZJ60yk zDLY$YIc+PGVuv!OvBQPz>~_Mx^Oc;FE#>BT)bVv=i6r)iPKKPV*3^lyH521WV>IqM zW;8y8B+)76ksQG=*uifDU+^xd)8GJa(B`~^MpD`E*y!4Uv57S>pJ#knD-V5@1OxpZ zAmWwz;EBOC;6Y5pQLha~qe(uUAe{jM0Tz2zp$+JYEdY0PiWS%q?vR9Y7>Tio(E(#3 z&YbUn;tZa^#OK(We~9%bNx$?Rr%V=DwVIGlPpV)+W-R1i9+A8ZU~2+agvvRSC%Q;r zEo5yp!LVO+sV6oKkM*xN;_%g2!q}7;N}|9ZFe$#fH|0!gEC%s2XNXzBg7-_U*2*?G zJT{i7lea%MG)ztke1x5nL+L&E;rTdY<|;BE3D2O-A-mZOUvWX4&l%EvA#61+QqZF~ zOF@rj5{C&2H_BxAC22c5Yq*|BYC{jy6T?M^0$qbpA#Xfo76!=$;l?HfK{gYG z2QaLFqV^QSKmc+TEuX_oFsI5S5h9sXP_IxwIVd*gX#+xQd0fpXfKGC*WQ~bQrHBri zWhY*7@@9D(6F0IVR0=N0J!s_^9!e(R#_%rF!F4DhXeBS581sYz;hJdw`c2WqfJSp4 zQ;?=V@usjeIb+1iG%+4a3?N8l3y6NUm<^-JE%Dem7>&)QWU!9eHf9W{Ah@P%gzKf; zhk~?lpF#=VQbYg|bT*Qm1sORj*onkYm4a!{u{gCZpNREOB*up}#>gK@3+rOh_&5cN z$vMa3-8jvFf;EMW@C>35E((dzoGVXfGb}eoV^ry_kO46pa|deyQIuL6980j$JoBmE ze+t$PW)bnQn^x_W^rr{n30oR#Ehh@IjKk{+Q{IW`E)y6Vnj_m${!$S3tFHMbQnv0s zlM9zvGx;9VvbTSxP(=h zVKs~=6Es6dOLNi6>;RGqV-V4Tfk{gfB1C6si;2ua(HtOez{aHPIOaBFM?4X5JqKRT zNdV7q@Q8VlM?@yQU`$G9Sa#27{n#Ul;oK?1$Ou=dVj+b=$)D6ZB2p6#o7hU(O0UFn zfF&-E?GeDM85Bpk6qwTt2U8B#qIC@Hi1}(1b7>V>kY)bz zH>}V+wLMbAAK}M%_uZ+))LyUw~M(V<%A=HaC3=>?eP&_Jz#}zq> zLxxc@)4dwUOw3W&#v`%BS|MxqYN9G~U*$QNoTXwp%K?p4vndgc6Z3gq?kKmVxSXgI z9Ap$SqR!!RR-O_+3NAcOpG*KKo92e@RhYGOn?j8v=upVYP9hH!l;q47Aq`6f_7B<) zO3=59{4SS8lHR?NO@=tUerR-nC!NeUB?m=uMQDdvDhRcwaErh*H|3O8VPp`=&L&)c z#`>ExIqFd)hl`Z8?PXY4qliJ5HCPau(djH^GNDfyaTB3DSt(&J0Rtkucv2Lxk{Qu8 zLq`ADNIaSxqBJmHT>+q0MO&B&_&mrAt`~`vf_JTM&LReun-Q5gVf~Cw40Dc(9gj%_ zT^}8{oFV9DkfJVj>~y!O+UGhi8CUEUF#%a(Bwy8BnzSv~scJmv?vBrGG;L)miew_K zg0=W|l$i7sG9abc<-xUVu`tpKK+8?9iUWLMkkXu*jh4v1tCJqO^~MrfM2NWw%AaYw zht2z}Lw7kW)}q+ljK(%6>*#Wv>R%V@Ur*#XO`z>LWo4M5xK3JSWbyQLY_ujffP`wR zBc>*<`Y+GN(v$+#usx@|vpP2)Sv601wFUB^RoAR14~tPN=hF6bcJp=n!{-YHVF z;+ayz{$NyW_HaLo_TggX85C&;PlK_sVa=G~d#h^k_AV@IXpax=xLJVf?(RMSD#aAR zT7k`jD-t3%gJe@Nj{gx8))$#Kl@%(!m-eHBb7U zHeqwQL4kq*&U2S9PPthZc^5J%TF0wAZRD-k1bGCr1{J1p8&o7`xDJmC9*TYC9it40 zr4QRux^vE1Vo7Xq5KnM>qEOTfc%|4kNZ$mY10zFjfq{O$%?LoII7wk{43$hUf#5lz-Ry_UKq*Bsxq98%F{f9v8^? ziePsy&o_B>4HufoGPL~3&3G*#HyXS8qZ!o?4%iR6ri*#23rie!xLpIqRD~`zmb<31 zP8YT}g)(g{%F9c0fGB8oak5x#?cz&1U1Yn?RH?LRuhvy5+g;g0DpyHcU8&Pg@9OUE z!V@Cp#X1&i>k>EPy<}>^@Pvrbw`zGVTd2$~#}f-n4{{77^MRDbz!kU7X)T2v)HJ&{ zr6I&4kBy$PljCdzm)&ffmT;%p!aTOHODPd1ArgVpPe=Zg$xflpS`j^z+Y;2G+LIT= zSb<(4yM)SnI&qhj+jH4T)z+29m4oFatfc0YRqjH-EX{SLiniq{nwzS4Q>j$fG19{j z(k`E(P*PJDP4GISRXOZRNe3~+MI8hW#7k^%AT{(0WpRaO4qvVn&Do+TAsH&zD5g;( zcofU|+L+tFTxMu!s1zW48kG_rovzr4)8z#I?f2=QFc6luMT~8 z>piW$3H_eddt3F}eG?0^1MS~w^(FQ1Q1=Gao%D2no7%rk-3isb!PC8m+V@cRX4Rc= zyLUA{)QCYJYWz~GZ=?RD*6V7<#v}W?8n0-==vOq&Q%`b1pKraK*tuMQN%8`JI-)wGUmS zzte(I;+jrxKxjaIijkjc{7oaEf7AGKW1!?CO@YpBO`uCd@tb^TdZFoEYSQ0ry1O}I zYZdLJp3g1lcQ@bH+$hif(zl@B*Zf3tGoPP63^uG>oz<@(nuGzY%#M0;9~4QC^6=9tqD$qu{j_dP5Y4{?+iS z;noU#>f}hrX_1b<>IUqq;iHk(3t>!88yTn`?r_5g4fSxOgE}}K2t(}+?!&iC^nJlQ z@gkspXJ}7|Z7=xPORXlihHeksaa^Zz9iTlGguR|3fGrBG8k4wtgXo@6-H1sfpMEcJ zNfSqc3nAY*f)O}v@RAUmyh z=pS+GNBU(!#qDLmYl6pctG`5~U((;uncFvj=W;8U*0mHyP2KH-AK&eJ(8mnx5Bl&L zz_|W$;H`jYcq?#+?i-hKRtv&T>Z$Mg5WT1yr!n9}YYpfXHn6%L3O0PAqA{t9wo>Yo~rA(rIh>bMk_I z9k7mbw7O;t2v%$rpU>2G%6F_idbq#+H|?07w;q4T@hBcV{t*L%f9cq7#h`&a7 z8wK7*ArZq7#kW9M^9A(h+n#Up$I=Q*`}t!Q;feRe!GaH9~!@^^;aKe$u*=)UvY;gh+Gx z?alW#`)ArUzpP%^jx|}d(r;C{hyF&>z0Hv4mF5qq_<$C;YvcM8Ezh^$^k~afls34Q zU^Ib}1j^gZP{`Yik_5`LEjWD^nE19NP+}FIn8Oph(6`9dSutr*K zezF;gxT^IQ=tDF;*^EqLD-tKDNO*z%ar335)i+v>qM*D$t7~Ffm$qC*x_!Ro4HU@X z09D(>P*=4`H9i4t3aHv9sBB;BFNnjSxAu$H=Qu%NBCP$5P&=EMhpKG?5jG9+p=zW( zeO|wUBHXjX2Q0ONYL8>EEaB?~CrLdtDs7HV6Y>8+dFX#Jg5t%C54?_^+uE@TK za)b{ifcv60OT4HxjKN z+p(sJYzVkVmB>eFoEsy%X&f>pY_@10a9)hOOG5*qT6;Hggi{K34b~iFBV7?3Y+Ks| zB0C!v$RZ#jYk-0@6n7ftDco0g8Te7sq~6|xo*wRTU4l_6m-?XEOMSQbA;6vfr>S_~ z|4snKJAwBCwJHDozQ+mraUZ}o0_+7^f?go7xc*+?L!43Mc-!|sK0k~IHo1x*A`blk zdH{N-|9(G;_x)D@QP}fR|1KJNU*G^n7RKAaRA=wdXo6ZN6+Q#X-0yhM7TKzQr3tO;QUFX;Th;_+ua;12;9=tER#D(HJ7`y-l8Q$Rl$IfN>?zP>+l z5LNPTeLiwIs^r(~)xtgX!{PY|yRD|rH|%WC_rm8i>}|m6?$*7n8b?>`=60h>QB~jD zx*t`Frut#*u|#~-549X_(R2!e`u>)Ks2;-FqR(S3LCV|q)i(Wxwp-ft+u9y)=M`E% zi1k_1A8C86jhACI9&Sf+-u6M8PAjW^xc!Lo85rT1gYBoi^GSUNedo}xwQ9SMtL>o= zbW!`ky7p6Kdpo|G=RH>A#HW2$+by$CwR-h)`w7}}BVK6yS^!Roe!PwjeYDW0Ez=Ix z!C#MdeG&d|U7~%Dq_19B$6$Q?0Dp;3_0tvVlEc#qUViFOeW3V#*?#`XjIOB<%6|p| z`tVD9>Ra{GqFejCY*#;cF)!OmAB*wd&+x}{^Hr>*EwkfNNIbd()cFMapGr{UXnb@XpTyI;fS6Y8ArTWCKX z_T7cAD${X+D6~h=-XZJW;w7}#k>Kw4BpvnXp3g};HlbV${zSCbxfIh`xdeP{iS~&l z+A~YE+h}Kb>8n&YUIgEC(C>~=yZWAt(!)Jy?_h}9KaWWG`XB3f7VV44`}z{?A1~3~ zf{R3p(K#9I#OFM|B1MNZo3>^N_zg?6rfRdgUgb8<8FpXOh_99pv5MD^hUwOMl*giHNdeh?%*zJHpwvCt1}qtTI}ezfBCRU@`eBCH$0 zlSxK$q+g-pKK7dEurW3`I37zH`~VFIl6oN1k}nqwB}Z_}O_>hl$Z$z|(-OCC&At&jW%2Kt6AzBstbb z-WNg?lxuVM)f_zXiL2}MdJi5wH^9%(vCj#sJIL|WSISmO>%`*&IOWOJ zX&3n+>rQK0#*yhXsHrnSLj)9oq3RgQ%x6Iiq=_=Pq_-_PC-EM7C*8E6*Cjgn?j2Cf z0`8KjQ@*>dx+W)WYex0p4x**%P@1YzGkmmqUc}v7JTRg9?ZT8euMNll-!n?raPLT^ zciOjP+*f5s9buL4spd{py!ekxd{v&N0A)#=9`6yw$@`ytQj}=gVOddSQUWWy`tj-0 zhxqWN%l|s8S9GZIKO{Zc(o#yH@aapObkIdmLQ&&uxERQXEGb{{9z?@?(2b-|Jp5 zUR#HMNOq`F!6`E8T$MM~;bT+Chbs3fL|H04Ro;$vFaK&Es7m_bVDF*uRNI}Xc=6S~ zM3pTHP?q)j`;Np{_SaTOKv{Ol`Jl+ukAHt1zS_^I(ou-AtRMe}b@<RH_IZaS{y{Ph4w`>- zsBx7ZX63wn%)@ zTK)TERMgL}HgQeispgZGz&~9Ev;)%$Qk3=hf4v0$5xM|^k+B%|5c74Nb*GG57a|z3og5nnzOT>6Y4}TPi86;;zwo7X*LN9E g{yF1gQ3=)storfEJasB!#IyVY^1?cVx>N0c0n(eIG5`Po literal 0 HcmV?d00001 From 7a5f1154d13279733061c25293ca6822034f8680 Mon Sep 17 00:00:00 2001 From: Thomas Noel Date: Tue, 2 May 2023 16:12:25 -0700 Subject: [PATCH 3/3] Fixed quaternion weirdness --- .test10.py.swp | Bin 0 -> 36864 bytes .test3.py.swp | Bin 20480 -> 0 bytes .test3.py.un~ | Bin 72606 -> 0 bytes .test5.py.un~ | Bin 7643 -> 0 bytes .test6.py.un~ | Bin 20100 -> 0 bytes .test5.py.swp => .test7.py.swp | Bin 20480 -> 16384 bytes .../euclidean/.euclidean_pure.py.swp | Bin 32768 -> 4096 bytes test10.py | 374 ++++++++++++++++++ test3.py~ => test6.py | 157 ++++++-- test6.py~ | 179 --------- test5.py~ => test7.py | 33 +- test8.py | 347 ++++++++++++++++ test9.py | 355 +++++++++++++++++ 13 files changed, 1234 insertions(+), 211 deletions(-) create mode 100644 .test10.py.swp delete mode 100644 .test3.py.swp delete mode 100644 .test3.py.un~ delete mode 100644 .test5.py.un~ delete mode 100644 .test6.py.un~ rename .test5.py.swp => .test7.py.swp (50%) create mode 100644 test10.py rename test3.py~ => test6.py (56%) delete mode 100644 test6.py~ rename test5.py~ => test7.py (83%) create mode 100644 test8.py create mode 100644 test9.py diff --git a/.test10.py.swp b/.test10.py.swp new file mode 100644 index 0000000000000000000000000000000000000000..18db4e40eb980b17ededb1ac08f6b2abe74a7bba GIT binary patch literal 36864 zcmeI533Mb!d4Ssob{1@~aY!I0q0j_tq#ccBMtdrj@!GpSVy$;q+QYkpJg+s=lG;0( zneA>#BN=0Jg>Zztn6LqZc_G}`KmaEMNPvJL0TUp>G4M<x~KAc&Na^Ku06?#=IZlq zC^wFO7=J@o?VcRkI#S53>G?UvSjI}toadeCI9~^u|Bw6sKYxPbd>1|quL2LsunEq9yC3g3UxF9H zH82O;;TdomNO&KHYvBNlz!TuBXE@G1@Gf`-+z8h~6%NB5xEzMzhmUid*T7Bihwvg; zfdlXqI2lfYpFGxaJ_>Jy=RpOoge|Zc`ru4B1MXbsIG=~-z_VZ!*27caM+{PY0zM8e z0|ifm$H4~}Sa<`>!=-Qu48f`JMFuB63~vV?O0XHuhMzGo@>BSC_!fKyUIRy<0h2HY zr@(y-g4_YGhZ5|AAvhg=$NR&Y;fM;QeqjycU+A z3X?Df{ctv%1?PgJI97_2lk4+SYD|TZ*C-aI+OD~lYd&@zotzZMW@*liilf#Qhgu`M z;sy0EohG!xz<>^9a*{h6^l3_6wBT1OYN4ULX5`f>UWNGF$Wx16IjRRHEhI+;UbGO@ zObi*dTO!gS_%kZ4Qz&U2Q#s|p~@hjh>w&?yTVg(C}YB-h=M7l>Ex z6!W7~1g}qXQ~DV>F9eOW{PsL0PHm~m6;WSVuX#FOilY(uwJ6

8`!%vKl_)RU#5CKC0Dn zwH|sl&zaV%RjT@jW7h!+TeR7v(dvy!Qn&6H4;?Ado*qaOME(Wy=)=+k69ln|3hUgL zMIDZyW=7CGnjO14QnZL8)`JUp-@D3AZiuAi*AzlZ?cKF~*XSC`T8~iIB|kLE--`d( za@8^No^`5#@nx#Fk>i!>1C^)*uFG=`EwF_u-mLWF7dxfqqNov$4i7IaEoE!vX+K-5 z&Sz`>Tz0m;INX>o54%C+m#bblynE-xn?^>q7V?{i8@ARNkX9m?hM8@6U~ zoO4oEb(9~fiT!FOsLyv*ctusIR0n}NEbk3%;r*Da%QXZUZU%BlM32@$^Q_2*K2CF5%z~Ff7yyI;gnKEwde+=N;RX(^+kRqaP4A$r_E*A zx~eIYN}l9PF;_Q5<4%WZv@3FJb7`Jl^r#~iEB?%kvLB)px|G%mh);cIK%rA)Y(xzx zqgg2vTz*KhtCNSrn7$m*my+Kxm9A7vVcD&ER-*~964+=&T&w%2;-mNLBj2u)7X%be zT8RX-U~TAQxoj@CabQ%XBtPU{vV)hN+g)WAW%UQGB>Iz%vVLvR3nFtRP6HWLtTZ!~ zZ7QbTN4=Cw1=@y=&A;;MbF*FIO3VOrM$A{!B*h)k5FB{aob zwVenFtV>#CMH1Z{7;frpi;74UMS(U4)cK+u8wku+-FecQZVonwHw~clawh)`=L@;G z`q_utH|k4Xph7S3y-;E1s=|4ybJf)8)>3Ga8fUz;dwkzyX?)wxi?(kgX(PP}v-N}G z1>!Ao=NobEGHUygVs1+RF zTJ4ZK7w_7><2XLFNE_8C8_w02(ndyd8TqqwQK{-K)0)6pds7^4(+i9KRMu_!VYm-SsH-+G3o3Lr}+SWC}HH1qZOb( z2=Y=byGy*HRxQoNoHSOK{7N)OeUR6co9VaZ#ldO^B>Wx3fuK->L6c%kaI zhg4@1S*iLvDv9=OsWb2)KUUxrkhy)lQW3>5zN8okKz_0_RX3v9Pm$~BXZ+cWzQKL1 zB@5GyYCWPFml7S*f02b0?3n(WQ9Kg*E8bXo#1wc&aU#B{T5W{dCm~9+R%$BGuXbw; zHBIXg5ki+bb>|hubsHY65&jO=#aPj>_O& zlSwiez3Xe*NtUJz$I2L_nIsy&uzhZag%->Rkqj3t3^3rgo@m7j805O)XY#omzIFe9Kl9>`XC7Vp|NXY`zDOVccK8^)1g?Nf;7M>N^ZW0E*FzIz z?*9<%hKt}_I0J5DzJD2H{{QLl-^}U%7`_2thg;zmcqRNPTn`t)2KZe#8}1@qpMo2} z1xe>;N$(BteRwat1rEZca0zUL)8QZ1VP^nGLFW5s;hAtU+|Qi;$Kd&J7$#s8Qt&ed zK|Ty0f_K7AumBNU1qUDt>)?~j@xL4X5{|;lA%YNMTY!C>i#@<5cq%w>5A*&11n-7F z0~gMRt&oO(I1io-kA-#cBkTa)56^=t><6(C*a+vr{ml8_3wOco@M5?Q#5UjvoDUmd z0Dcp`%6$J9;R|pVd<@&@)xY1=h)6J9sb5n@{_U_xr9L%@?v;X0GeY5+9>w>BRy4wk+yF<@yq%hmsHm62(EA8;sfj`*!nQ z#$nq@-Uk=1HYp%v`;fffj>seqOwQ#vp+HF@LCRwt30~@&7Cm4qlFoQeD2_!NgMDbx zhPRlJ0cTUUh~0w6D1KVYD$dwkD3edvb;Qn+PKq>kH4<^OtC)0HdkaGCFvwWN6a$^` zy9#!-`G{UO)we#3f;7YYWJiS6F@vx%Co=`;8BrH?7N#81DOWm;OfWh!Gbb)1gGD)= za%=^j%4G}rjWTne-!PJqyr@*?RFfkvNGYBo)1&(g@DJe@Pmt-yQcUBFDmOEoDQ7DB zsd)ZRLLg9csqbtU*}8Q@cJn3^pS>T2I+3K2pzY_v(YY~B72lo3%D@}SXY?NuP9Agy zyPnBqa+$oI4{Xf}=osWrGqap=NuG232|GP2%53FkN6&t8w#Cl3ZP>JdI`(*zNPBlo z?mdnVN0PCYJ&@ef8Cq49j%(ZF$g^56jJ=P%`5q(XUcgj`HZqc0sAs-*b>-|e6lyZz zRIM;!yW5L;QA9SiE<)-$lR%vFen0AIa zp-sVrNj(_ro31W+SVy?k#+=K{(MA)2JS($=SS7WTW@SaD6Zy--GA%5A;-iRmWOEyF zcVZ{`E#ipINc*PSeQ2#4t#H~8km4>yR9%zTGUt?0B|MqRTF#`9imeFk1 zt%k^t%!g{4T=OBnuBhgtLL?)e;%@%J7iYL#y7DA$A*D&Q|kr*_)==j(6~g zd9X_rD+h~*DYWcfbzz5sT36~su^SA0O0yBvD+^^~6)4f9I>S4F#Xwstju&Q}!iV-W zlkKagNc8QnZd~XY>wKolv}fg@SZqm*Cbk2)-el%h&APa*6;bC$UP3;h5B;i*iHdzg zY)F-Z_Vb_WYPgs$#Y2oO)!BHF_#8=ks&Wv8IEanKa%mcq5oMgUD}@fz9` z{1tB*<&^?V#zHE=!l+2fJZ6&Sb6bpSYzsxAIU-M$u!|wG9{U)%)2{urNA0OxXTmo0 z>;$=q)mXI|qdU(wm?U@|9Z!+sPWw);9j?dSbe!ni)F5i0E8}oszU7SZ+2DbU*g=ft zIs-RZHNo32zEpy-p;$z#qc^FN)r?vmFqP=CD5d%4bX4@dT8|-=Bk5n7^D%2m(^@)T z?c8>iHn25$xAX;w{dmdB`V4Iqfcw5LC`w$phNLDqqld*Ot9W5}zR>r&#ta zXZ?7}>YH(;UN$G@5p&)pnxZRTs7%FljcLY6=B1l)P?TjVBR?Zk(kWIPG*T|7a$!n- z(W@>i%)8197%X^V&DLQ6q2`&5*AM7FEkz{ewAM{B(N(6#vAaa2zpfw0WX?UzY(8en zVibdc97aolJBy|5jE)$^^RxFqGuFb2TP=qiFRn02JWQd81?Gf5CwpX+B zE`~|iMCktiyXZT9mj0#m|F`iY$3N50{{*}lUH})tPw3PCE4&L{3?5Wq9sCdd`+tKE zz?)$YWZ*mW;ia$tcKCe|yZ+PQe){oug4p&y7p{N}px{3G?w^A9!C%0Q@Fy@1C&QQ5 zu`U5V2rq;ezyzENkAYL+TlC{U2RFkkjKMm%jXwKPs6qz5NniXMAh!G0!xiv7WFhi+ z5quxSX8%_BDss9LJ`cCSo8UUw1>dDV{Z@z|1*gG>=sW)%yb}HZB6td%31`4h*`wfY z_#nI*UIncK6;uc0b!nNxb(@G8Ev2>?Q`Tr~Satc(3e~bF>$*jyI<9Z;zc2sxT+?`Jf7DyPoua~nCIkWYbd=hcf^^d7T;!f`8b*?6E9fd)8n+!+twy1Qg9)rzY9Nn~ zn8zKtAxBE>s!A9Wl|5ro zDFL>UL{@w2YTeqEo@Q}mbhE9JOd_ZuB!==r5b*lzsz|@!+R#(($Wz9duaYq-!aUz^ zH;yVYl+w}1F3A(dWOB?jvn$mxy#_=?RSC>FLzb~I;h0X?W^QU5RCBpy%9?6QGLLDC zBT(HISJD{gqDSoVO#5){=`?L4rEG5)iz}@JMq8*U<9$PA@j=a7va3dHefaRzSTcJ; zdQ3Z5(rxwlkkw;xI#kS~iF{Vo_!LWPSh6vu*Vu4^x$6oxbmB`6zB<}ydUD_7?j0BJ z-LYL=wC_?!-_mz0)nHH8i!r1h*E-EDQSdXNpm}RVMlZ zEv zWU`cCwl2n_YSDM;KS?WBw~Mso^e|4lyESebsTe5ZaUs%mWV;E}RbliYe_E1K3OXoG zy3|Y$jqvV@Tt)voYqgF_?HC0y!)(hk%&B-wjZ(zbTdTND)iGF93{k5Kwq`eWj8T_D zJMO{PrlvwG9m%S8sH}9=K9!YLKaJjytW)#mr@cyryob`3oV#+?SGwzcM--DRt$py*oyET&3mX7Z39D zy^&%XP_wkBL$wgb)wNpkqdC%JV=t^^26h=wf zLH1o-j|cR{an(Wn_R~g?UbE~qBDF*RScBz`rGAurXMZR)C)CVBt*k?nm36$QAuSoL<8{-1>d3?x z1G+1W*>p9n9TDRpZ1Br`PK+SpkDzXmn)PXM554^X(iMqxPfaZ%hWk>x4Cz4(6Q~Jr zg-(5A*)E^Z5t&%*Qrp7d`1*Wia%XG7?V;6fx7Xv!l$`k1QFMs5qmS4tQN1#Z!EsrV zD0S(vC7@qvdHeNpUh_&Lt73lr8hvH!n=zU?G^Vd?+J`|JHL{r&I3m*919BW#BP)wr)i4EskE&ZZ7rwg5d!&~4@@JDbRJR7D#)&X1yr^2oD z^KXGy!>iz>Fb9Kh4m=Sa3!kT-|5qUU0WN@y1IQkLm%#}94*WLUOTYe`@W(I@Vl!|) z41)Cezd%3!F1Q);kb|ef9rW9816c!b6&!#I;7Rap`siXO@IhFC23!Vxa1Z_RufV6_ z4tNh-5Bp#*Y=Sf4UTg;b5#9mMhixGC{!f5!Tl;}G@;eP;=f4Mb!x)?kzXf97{~hcI zJ`S&go1qRh*bQko10DzWQC4@uM?v-gJPJ2}lwlbrVIw5RFG~XQa;>>ZqSJlX41ccf z`*`>41U%mfI}&NbO}1NX8UGa?Y1=LSinl-%#k8N2N8JvOv9+MF)YO}Bw)bUxC|f*s z2iOj4z`WEV>$X{vwa)z2@A25Z>*7#r+e6uZb4aXq;vGeqP190wBqMV4Dvo%z^H?2| zpC`UGs4b9WLrAm5r-)S>9<8A=7&FK!ln&`98$z0$Aj{^bl57ZRcB72ZXdae9$%c?rcI}#5hOUwgA(^?}e&iRvA*7x*m!)fVN66N7&z6vOFF*MT#rrsR zZVIU%lfG`pn$E6m{HRaq2Df*GTqV2**cY-j!5_yj{(CouT-8(W&XB8m>fIXh7*Bi* zPIzy~4Eu4jS0wh`vu3kMHcTv!^&jrXbW8urCW$it|L4;0r7tY~{~_CD`U3s^m%>Y6 z63zqZ`+pbyTKe|zQYgb_*aT05Q{Z#->2H9Ia31_R{0;s0c)kD2IKK||K|kD1-(BYQ z$Khx6*S`Ws;gv8CSA*F8-%lFvg>S;YzgJ-txy9U0Lau99Apb~=tfd|3UA)G2W@hEu8mU@ssbV2s fs#wqq(O9HbU_q^3wpJ*1FIAL#2z#xihR**1?NDh& literal 0 HcmV?d00001 diff --git a/.test3.py.swp b/.test3.py.swp deleted file mode 100644 index 920e49bf9d8def43c97d83eb5e74e9753e258057..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 20480 zcmeI3TZ|;vS%52cY;wUD*?vo$J)V|v_e@Vuch9bOcjU2m?Oo+I;~npez1eLhO-)zL zOnG~{daJ5udIr{xKo&#-M2sN80R;j=WKkSNaiU1P#0~@q2&@Pm!c92lAr{0K0Z#!f z-+#`juAZLRP1aagMpf%?y6T)$=klN1|NnKoQhn@$^Xf>Y?r`1eIQ|_U_Das<&VjGq z?j-Bsh8s)7)i0B7@*@k2lSilP)hi}`!X%tJ5w?08ekX~i)`DaziQG=S8b%xOWOths zovFl+lj%x#`-&Om5xE3%30#{5ddceKk(-?9dQDHz!q{Ev_S+u4wmkCGxdd_vlW*;W+n@7qRx-)^6m?C;$p@z>ku9s7G>B;G#e zKe+^Q3FH#UC6G%Xmq0FoTmrcSatY)T$R&_VAeX?KAOY8NoG-lFanAfGh4cMCwf`^Q z;yC{Te-595Pr^m$K?4rJAK&aa-+<@fOYpn!GjI|rFbQ|Vt2a5$i|{P`66}BnEqEA? z0-q)w2QE{OOYn2B3R17rFc0s8JK>+GZy&Z`4n7Q%a09&ZF30&Ud>y_DpMj4<49oE2 zFbQLD9sJ`v9p@R?gasIf8{r1H^bW`Q4R`_`hm-Jj`2LTOKeXTjZ~)!~-@6exz%$^% zJRF6~H#pAA@FM&H{61WQ&p{ttn1b)&WcefbS$G6)ft%qaoGV|3r(hF2D8ZfZUifdE zH?P9;;6fcvO%5ma%8`Cp~mrH}>USG|U zkLxufzjZ$BG$l<@XFsdoQC@p?r?I#=QC%)8FEaNv?l;{{e^%#sSf0FKb=5o`Syoy8 zgW5#CC--&vQ*2aKxms4uoko4xR>t#J)l#v!Q<~9rE2yRP0E$XN)$zB~rr%1!h=VWE z)NT}Xl44elc^)f|RUQw6PI2rfXKMAzk=2W16*&9BS__lJ@2JhdRj%g+Nf35Si-&SHHJMpll$vz96*r39?P8-HJyLH-H|ZPcBYksk zDq_h&LU<_~9Rw7CF;@vXn|_ouCB);8712<+%Z>fYtfghv8n(<@W3HI*C2e-54 z7w7EI+f$1j-M}5)xs`_Sm%glhbtdeULKUiBYW^WrI`~8;RP1H&K!*o(^ zto$rvZ)aB)t@W_&$LF_;D$7TeDoga|!>5)`mYHvMwT{&sPhp}?msK39Enn#~bF${D zAaO(vauwA3{f-~G3GqyI&u41OtWMW6mh_OteZ%bpt6|%79ktyby_;Nc5vQTu8LV-Sw*5SG&LA%#H?Cq?x=A!*Ibx;bg?;i zeEz``$8~Y%7~lwDhb^PKZ5P#ZMk+gg6voA3eSB`BR%REd+f`wX=*9Vox_*DCiE*&D z;i@ica1xKSOsz)YhVnbDb{NZcwpS8cL9(tJ8YhU$OfBl%s7)-+FPpy<>$7Pf)lD~Q zdXX+aOH-AUI!#T|FqxWOdnlETAIj-!sj|F~jxDdP%kwE=bkA)1QN-@Vu#rtx7Ak#H zPj6(C)FFfIQEEN2I9~>-@35)YYPunhduotvF)$1z1 z&j#Z8p0wVL0#OeX!)-9Ybb7s|)B4%8npvnG3$_(D)GqsdQ$@4W*=dtjEgKpvyjQE0 z?pr(fhgMIc0O=CSMi#p4U{w`uUDWI>E5Fo>6wUL;C1dv)JC|; zC=$(LxVPMHx4m5)F3I!^Iq4#;F4j<<*B%FU+nPUlq^zR#P@W+|74jmvv5`tf$kM43 zr__uLU{(N`g&dd-n6Z9bRx55ykI)Tk-T0nZ)jqJJ%PJ_MQ-xc%I zvY~3()RH%q)CgH~Nlj)I+jdh=cxJi2h@Y)ZQhPHX26MrqRa#iKUbEFowR)&DqY9!u(jw6sNiq_>s~?hz?l7aq4wMwFM#`U3 zSv934P^Z>Nr@#b?ct`FgmtrH5N$%a$wJM` zv#QMqj>wtFRu;?4A|=`)N@1i*YKo^i=}uU6*u2LWt{fs%r$i+r<-RgBI=IM2L?|MY z0Wc7nVzi#1Kr-7UEt(>g?w6+eS{5>YYOL9C2g%Hi@fvk4_Q(5E_m&vQawq?$ zYW1oSL_s~uQ0|6XKH7vI1%9lRrg%flkiM?BmO@|V&aQohs!fkp%&Mu1Nx{r;H@a!- z%Id@gtz+>cD*L@35=H0+Gbf4lV#sb_lS*p77DBz`&|y_BPeTL? za0>2$+u=6&Hn#mU@M{o25pIK5u;;%Ge+JLPm*D5&BHRUH>%RaWho68Zh`s+IxC1U@ z!@mH}!SBE);4%0RIPem7{4c^UzymM|Ww;e?fmg8SzXiVn7vZO11l?k00pg#OvV}DzRD1BtWKavF}_ZZo4tVW>i*vxv5#3DSNdsBWqm0QJaxPZme(ZnZE2= zvQ!&me(qRyZx{6*dmXp3RrN}&ixXr*9(qaciA_KxhEUvfTYj-xu8;HF4a&7@mDGAS z5Ut%L5^ISK&6qmf68V(L$`P}%Uq+4UsGXo&?60G`bk}29-d*t&tp;lq+!D>Wx1!}x ztJO*lfka6IxntSW;xhK3Dc0JG*W#QRa?EJOc*e1rEFi8l?`z6eD|{#{_9YR!mPwi! zii5tcDbsyDN!H}H8J)5HJ6z5+m9c5{F#A$!|L$x1YFVWXTaQI`!WJmnU}+y+nuZ#Q zI671`d#iWTmqY6EK8kX@t5^5iN=L)g*hHK}#bBaFTSnY2hpIBV7-W>&&=p;FsH8mU z3Zm~iqEt%A^ms#VmmNEv3)M=!b_j=1rFL+-EDh0y+CWQkB*ab`(e8}*sH`RlOLaT_ zS^;HaM!Dsca;t1i@Kkk`9LUr>I`VLE`smSvmBaU%@+5@#B-WLrj%018u%laJg1o?8 zD>l%+YGwTgMfebn&@J5cQWeLj)?}})P-=ajOb$C*JLm3*)dvsWdyxI^YD&)1$;G9s zq;RA~RzcMDv*SXCOWbfEbsrim%`4hg`ep5uqW`qBO1gALYjQ&w>^s^R9#ZU}N(qK8 z#=}BW-MQQ+|GDwHc;wJ0rE0gn*vyR&!EF+UG1H1 zoJUo~O>}H;D8oZ+@+e?&?M9*3YZ>2+h~vD-f+F!h*2-QK z?$0Ww)TFZO^M-F%Yr~8~{l;oe+gw)LCF4KdmQi?Co7i?`m8$c_V^-B1x!qb1 z+CDaGfC)K&{3F^6V_J5{xZ z6^Z##NBp(fS}+)I6k60nkSgx#HWRqJ&qPIASwvVKXO-8U-yabNT1xcaZe09vF7D7yjUA}C3aiuMi30V zS!Mjfq}!E3SKLOCX4r*{4`EJ6i#Jl1u(P_ubkG~W^6XxC2J6m{IDGkEB=&?OJA+n$&BdKThfqgcqIZa!#eIixg-#r=g`uyt^ppxOlXd zj_S@Ppr@GjYB=(iT!r*qd12bTpzZ&Qd@p`Q>_F`Q^nCxT*!SOrPs20d!hd4N{|Edj z{0UrwpN3WN;TRl(_ri_v8utC)fY|<*;4|-?TiEx{f_&>=f%{<=zJp!=*YFki zEL?>9U>d%UP5){57@UCz;cocncak6cIy?mz;4r)g-U0uP&Hgfc2fhMN!8$ww2jK6q z)4vQ)!g2U7Z1KN>r{NROfGLn~`LDr0z;DAR;a6b`*5NqZ0bj)K-hdgn zPZBUQTIRGp)p5muG$Q>Syzz#e14&mK7UfX|fIV%$vmkuIaL>z^xmGWV*mTSx6Zznx z)q05$>&pa3A>Zg^TjX@c(AUn_d!A(A<$VK>l!$EgXOdLN+3yOO z{>(6XWa9t!2+9vS4lY1aF4wmCNe7cW zae(Blbl!!p9;lhUM9=R`X*8eBuIVt0G=7iBjEiGi98AhpDxG{(>8Da1m|R;DjGd7v-z-JDx} z-oTNt{P0a=yaFPOfoC=Q2;fL~e)#4GAHET%6Q^bPN!-qQQJ>Mkd7?*}vW~if2vWPJ bNU38=>VEA3o93K|S*r`?ERQ~|bHw={9){St diff --git a/.test3.py.un~ b/.test3.py.un~ deleted file mode 100644 index a91d82ff33ae246125e91303416ca3a0b8b87ccf..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 72606 zcmeI5X_Q>Wb%2E|Y=JOHAolHPMnI2dVHOFAfdPa@1_=Q|5@4wrw_4LJsbMrNb+-l~ zj19(HoH+5C%{F*T>|p0d9G^Iev5&y9V<#uOH?WE06Yue!_{9DZJNK)4_4@Wq}- zagrZ(&)j+SwtDsMSNB%c+xo7`fyeKh9IbwH!NRM)_^Y?=S^L;?Pdst&KTJM+?|;4d zl6@!Nyzng}$5xO3eeZ=odH;e13w|QHwB9HmtVbi!(5gJiF>(oV4I)=SluA5ItG+ z8=|0CSvhd9T5CkL>Yi$&R-CNwt=10I`^tyMCn}|KaWX2_qsE#?3`(|VeHs!Y#u>C)zp ze8=!yV0p5`<)YsZ1x-gJQrR2jqRE4O#Xa@hRH?FeZ&!5PNHkFH9g4c5VcDvet&rOO zs)XuzQ<*f1llybgRB@^tT^X5OqpmI!13F|ke3k>@(@UGX5A;gb>tcVWJ`gLMa0cwl zG}I4_kVSmzhxPXt*!tnHeN&EVT2Zjg0JThF4fKrJj{=@^SPlI8<<{XwzB^~$bQBT12$!uG|9vPWarC7+hJQ~uq|r!xo^nE zU|WXIb=pwd5-Z`fSkws&SBeI1&LUZ+KHQdTcVhN0W{&{tHVyHlTu_!}V1i(0sGs`bR)sQJOmxLaIISi+BPPT+?TvWO4AZ_UMTwdKeE zS!8y!pgdER9?YQaV_Arp#9!lXs-sS8H~(AHUh1Y_O1)hv(y>D8opPvEbzq& z8N`S04-DTIwQoJI1D!u#1DZ>;5~Woa38>4}X#o6XqCG4Nkg-Ar@qm2nM+Wj@3z_?# z1<`MbE)-pFu*tvDMC}f_=HBR=s2v)VbS_^yny-xI`^Ti^HK_qf^~+z>BmeE9!LhL} z$;4(2)!m|G%|K|e%i3Jmb!+LHxxo;1;cVt(p`K7U#>k;=V1z8t$KMgcUM~ z2d1Zgt}$VH;_$acTdx?oH2`$*fW^}eP5`-A)HJFAo-<3zsRz7Iz0trs)dtD39B7}Y zgBSO3=_&2lUyde<^+q%p73JxKebq*zJQ+<@iczstsx&Iq$@rQB2+vmq25(iA%Spi> zF+vvcLHd|My2K*I^oK;hBRaF=;?@G(`6R$DU_KUL)K3ss2Rbb30Gbx#oF5HC_i2Jro&VW_E$k~--F^_2$di>+5q$)S#j zI;d;hc(7J(9Ij3Bc-Q`Vqd0zFE?+pBA08Zwx}(w&5h@M_UhSP;Nrg$&{W?hF0K7td$~_aAaleDPG` zY-e=y#%&uZhVe@9yjGNLT8Er&4cMJ$0yJVi7W|p2!L{4~7$am655Qk~lL5Tc!o&2h z7o7=@HLnxZ@PM^K)JY_Xw~3ChAb2NM$RHl@zP!P}TV~;5`rj7)fheBWdR5%5{l2Vm z-WN%-gZWs1`F2tB*iZoI%#w2I18}DScxHQm7r1Wh!CGaqkt-K!j7I8mqr~-90mfmR z0P}Z5d2layAV$a{J^&vv0OPg~)Bm364@GBspj(T7Iu8WcO6FtXkiRP$JkVJr%hU(p z>kPoNtOq(o4&d@>9$2eYYtHw`{4!NKFoG`lo-#`6qz}3eP4_*_kKlV3x1#GP!>*$z zGE>J8W|y-^EbycO3=Ew`vP^v#epoZ4kAnFT7J|{d~s|S`G^Ra-8?FN|-n6N?y@xe4=Fr95Ny;BbM zn5Y{#n9HZ7o%X$0cj0trK`x5-KEVINo}xS;o4DU_&){(L@+mC4RO#W&0gPJ)w#qVT zl0IyA>5%H!x*p9ULaMn?|fuT$5YdS=MsIp9&qz_Sh$veJg zgEKuY>WG@xNaoe~Y4&|U*{4bkX3&P{tBjI5>4Wxd##zs`&N?0K5YFm>)?Q_mZf%n+ zBnMQXxisUP7QSDGvnM?+!Nk0mzBjgzi#2Env%FZHLraqMIrwk%XnTv9m zAAz#zN7>t49qz(HUwwb^U|C)0vkTm{J_ueXx>gi{?vtY2l@5N35weH}(P!=V4OUp9 zAD5$jLeyRBTd}pU-#kz$qtsHRxG$HNZ=?xi6gxmG1s4xv2l|eEkeK>yG#NUoo z9ETE)aJxa36{dlsGDxPR56AyB96M8S985UEZM`b%4U!HVl|eEkeK`Koa9o*+a8+L>ZA|F*BgrQ z)!W5#s8dDVsAFxZyf+#x7faj9BN*Iu7r zW%1%!OGKUXZs$^8^Oe2$-gea1f6dooMi1rrRE$h`lTRi?GEpA}ijuGm>6_KbQ45xf zcCaiozE~lH_>g~}aqMnO-hGb8ksrjd<%cs$g_?=m1>U&LMcjyK25k*CiP(VLq>2vY zNR%f516YiZMSQ@1)PU`=V7d6ZLezo1u^rfgc?P$hOPXUv7TksUcyXdU(%;wLza{|< z*v;x(fSwdDc(Afenq*>0*%{X{w?$;iCt*ywwD~Ka(;Y8%;4w}>FBE;=e|E#wsM&sY zgZglbs1xc+a#o>!IJ2ajCYF@_XR9B7W9mn*4Foi-D@A#_@FdaZbBAsXK-~kuz}mum zEP&*`K)Ai`ERtmk2j|fEtV?U>{%-@X&%(P_HsW%=gSXM#gOw)^r#I0_BsX8kpf6?; z^u|nLtxL!Ut=)Y)*xoAY1nzv5;|3N4N5u*m#Dn!$?QeBlX<66gU=2~nx&UjWbfgV% z+b0`w9kY?6`R&`g&4(LnHccI%IUh;*n@@DwSyc<5ew#W^YQ)o`rf!B>pe&On=~D~r zoBi>1l&9nXl{n%4EDu{Jm2K(8E!&XHU;~Pbp># z%dMhL;0)W7SrEJwD`XHKw)X2|v6mi`gK4%`5vOx$;R5pxReV4P$5jT&l=OkS`+0L* zSZ-70hjVaTWsposAGW2r*k*HFU~X3@0BGP+tPqtkLKg9XyU)Pww>{`%ajJZ=PGYyDc_fyL;vp_$ge>9#_iGP!mWa`Ts-%hr#^80zAeoXr=r-$)&+)yki4Ig{ zRXi{TuTuuel=MNj#h@GU^}1%j1l3+uJTP)!2+s>`9Y)9^9_W7l?*`rV7Twu$v~xvW zz+AyVLN41%#N=^_s8@cQGU|%1l(|7^_(qevYH-`9iVD-fQ5hst(ubqHgL=cfIj(Nu z2)F&JtS}86l|eEkJvjbif$_)n^X53v!Vzv2RaTfD6{T4XaTOzE5f6_4^RVvCVEUJf z{!sKJ(dOeQZVeIFJ&ppbdzp^~kZgAf^WnA^R>&Ye@E&ak??-ab_VB>!-~sDC=3@cm zgQ90LAK+ny4B`XtopZr6KeK&sqS1G7qT0yq%n$d-BO_)Kj|1T~p-Ko#_?e$E3;dL2 z(jxXc$o_qohvy@Owh@dxae8VNn-6hZ#{I@z*wbI{NOd z%5xwc4-O9u_O09dP)DD9M&*F~^wpI8pvn~AQ>j(&?{W|D0d!K-39xa{0N7b1%hU(( z9~;0o+AgZ=z&OAc8n`;ZItLx=i9;;Js;ZFCgy1DC3n3OOWDp;MPa1+7EI~~Fkm!#^ zTl+U|4QyTi23QA~j|GtIy@>e$4=ZF4A9&9hcpEJ|MirPJ0iO9yr1FtUBj@5JfDW-b z7T^K)LgoW7tdK!Gfc^3!-5^enmzT~FFFTHOIEqlKsd7RTid^Ro6fr^;@u7Ih37`ly zUN&$7Q7S~B=q!?D>O(Oy6kpQXcbVDpX)kpxAFvLq@&WQ=qKjA-0x4F=AOth>q>4;w z&`yu@y2~vu-Lmjy2Hs5;-k-^eKNofIUewtcHRMYRaVHZx_lxp!2?9B2840wUB~nfk zOUnK_4J{)=>+L#VwxhM9NeenhM5pZDhTM~q4wpP*gJha~LhVg@VLXquO|u@EC<5f5HVT7FjCJplnPOOPcc zQL`k51|%9bCjexd3s?|BB38&CJnQF#bQ>pI(sEPCLHmhp%+PH;BLSo|QM*IjtdR0 zDYxU?J3r8_m+DRj=zzYO1;L@QLI&{xZGXN|#ateQaSpw~3v|qUZkLAaL+V_(?8Bk1 zWLY4M6*7nq>6TyZz{z-2#*sE}xk6i_H4jTQ6By0^wVa4Swe(Q zZfL;r6{_@bhV2zB3v97M2JvBQKMS_W_ME1(%{ecgoox$F@NvV@31~sQhy?*BR>&ZU zB_$6mYpg2Mb6mP~%aYHS)_1eT$qwMaRq2u$nk^3iH1AJ!?2!wuvd!si#5VQ))%$Z@ z=J)Dc1a>apn$IqIkU;WbB7wYPUp2XKOCcW-bwXL_--nT{vq+YyPj#@r6L71o4o}L_ z2nh~jGO}G450c>XD$$2U5!eM@#uO*up9ingPB-p*+i`fgD-rN{RFw>NftNB!rlb$A zI}NX`$KmDt3qG$_Wr7_?IhkdldBh4C#D~`b!z&)MOmEg!(5`hR?c?n28r)u^N(xiD zK7pe$O6sH!$4SkR9q4Mfc5NC*o{*c?&xzYRxV=`D6Q*PoI4Yy0PWo`H8jjm-{KSP^ zca@8RXC(e;`=T*5D7{XV3WCY8LKIb&Ns~-0DLdl}i{ebwAma=hMR!P|N8k>bgQdm4nh1YQ8k* z*3j8?PiFz^H<*tFkhq+Ajwrx$W=T2K@aX8Y=@Bg*nhV~=^kW%THY$yYa;{@jqg*RC zD%Hv8!H1G-r7(M=Dj__R{#RhAER!bb!|+jcu6b6z3m|a?Kjya7J!yS zhnWu$u|fvX5EIvs{M69otPdH8cUy?#va&4dE)0wU5t;dviF*2=-A(CunR?I!w7(_l z1nfxx18QfMl+(nLvj1$TKV?wA^#8{w6#Q>eCrj19^TXpP$|$LmKGos#raJ6u@A)V2 zaTLhDS)B>gKPwt;YAU0oPI{1DzQmBuThf0mhx(kTi}6eO^@F-RhcdJ(PjW22Y6zyc zsA7Q-Y>QbI;x$&tAU@cZ8f^Ep$99Ip)=CXZZ&l@jU~o2NkW5J*YTbs~SbJ)TvkkOj z(~d?7K^U-QVx@NW!8T&B6^?^#bt^VTw@!Gr;9=3HL@yN$F%lzW5f5xjerB+3vDl8u z(ViA{O`G>uboHBhysg5!E}sxJ652XviImgClCnQ(Zh9eD*`(!-qW2h%@ul=9WyL2& zc^`#q2^a6U{rF!M-zjO-%LuZMUQ=*!a#Hz9YhDLl*>cPa|Kz2#HD;q_+oh)~8OSdm#6R5|_jrv!t9}<}4}GD^yyuwGm>_vc>eLiaNHIA-IY9ugqmPk4EVR}qQeMgStLC$>tzH=Hn^N9RyvUV$*iLm9_Fh<&+s_Gx-H+s1YxY?^!)Ol`g@AIVq2qU)~iTcbV;R;b(Wf)(m~7_2^K^SeXxAkHJ? zXFl_%^6J<)Rh&3nuE&Sx(1Z?z&CL%Ysm*;3Jry5XH!tLMF8LtttT#@T$K8Q--98cL zjc>eE6d}Kh?4kMfm-z7J$E-_*@#>Vd6rQz{%|+P5IHD=8+aunPYij|7vG)EOex>zu1Va#BrWeSuKvUvIpWI|Eks|CD|I6gq8oMHZVV%HNVoBPfnWC z`kG|)b(L9CmUw)jV=$W$Vd<}g@deh%Dn9*{Pn-VAP_qx}+0)c*A?2jWqlFIlL$F3x z@gZk#Sgy9@++fa)5lpja0=#?@HZuLa`-fwv)4dZ4N|%OCWk82DvWgEn`x(kL7TxV~ zMEc+koq61=6KMW-uZl`rT%f_u3fib2P$;C4E2fErT;10ucn08SYtb;KS-XsSH$r^H>(bHCD(VJ{91exhlXtvsHln*a@owAiqYP zB-Mcn;%BlfQ~|7zL42w}Nmqe)%faXSE&=E0xTB|mrs;YQYTkB zOUiVXX8@nQL$~Re{%ld&bQ>A;5{7r(G#2rLA>~5t(BWdEE}!Ep9xThVVyz3@b7L^o z0&fly7;CGfP3uAW70#+M)dTiznlYwlCC>s{#(GIg#sqIC_%uPB;Ju86p^JwVGKf#` zUTGL#*uFjA+S$Iu)C29uPSswEN4fTs=GR<#hy}AeEC-%sh78zkL^90Dz{BU#A zG0DO_B0 zEvGZMYD@P(k2dEJn{pxXDy+-Q)1?nWL>J6%qjErSu$_G*cfFnF^VnsddYHw$=GIX8bjWXZDZ~3L366pBkUIJh|Dv>wmHHq zA=eDn)DdhG(e#IQaomO6wnvG3^sdVnpTBwSFN8m5jjU6j@R!%!zUkrb0+4UpIC|%X zjb72uw9M0^-^~3b__bR&OYAFB2m;XX%$<7LEK`xsbBDHZ&wK*Q#=V)@5cb+E^@@5b zpti|Ef?k`YCgYi5X?n~{vTmEn9A%!F_4J6Bn4^8xZI^n*JM$VM@owg6&l2u#p+X?@ c40kgRFiW(%-DaO0U_Q~V-9gqo^6e-77ZPe>0RR91 diff --git a/.test5.py.un~ b/.test5.py.un~ deleted file mode 100644 index 2f7fce727bb9b90dc902f491db8879b629c2402f..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 7643 zcmeHL&2Jk;6nDQ;3KcD16$k`_L#uV;ScyYvv525*X{8jQwoa)M%UW%`lX%H`ceA@r z?3`$Cs3(Mg8=N?_oH+CbNEHVVT=*vtS1w!&@AqcLSsNEpLT-NY?0P=l$GqRXw=?se z*ZSgGa6bGsx3?PKS@Un-UA+DK_w}3UN1xxk{q6Nz;=_-h{@_dh*8KzBTrT$$l_P>^ zJo3|0(hN7O0yV8sIY4C(mB*-n@HQpqUOIYlKYGV<_Alrq+NWOpMAvaD`%(Loh()0? zqFwNSJNMOHhGS3ek7r5#D^yNU`GE?cI1PwnnYQCVq$MYc{I0#$c2X-XdBM7jQ&mG# zp(tu@r|5QzQ}x2B8;mYQ0Li^nKtMX6@&YO&bm4{FBzNxqH;ishp$peXRDfvLwaPCtu zeL~7Uqk=sSU^?W+VpdF*rcUed13r&XF$C-oqNAK?JhGE_&yyqs5yM`k_c8OI@H)kK z?N@k#0pSO{5Ppb04!_6`Q){7Cp&dyPujzU*ztqWNqdE|xy-bTxHn{i8SyXcHf}E8w zZ+1C=pF@@2AS{hh__8bhhsQRS!;x8D4hQ}ve9!3c1wM~vECY7X!rP!xy3Kgzzx>?> zUPsR}UYQL}Htb$T-0`uJl{)!fIe@E)quDA9!RZv>hBTFpgs?f12H_!Ex}KN2A6YSZx>%k@)hC&h|S&>Y;e) z4Dxk0`phvAXM4VOK^E=X*5F8ak;)``T)8aXcN*c6=LCF*V@F})rCu0VxXdXE*QXK} zD#UOQ4EcPX{$9b~b73oLr&6R%Ddw~c5iWDxND&Ph6b3R##fFzQ=?*E0WFr-6$itvR z#sR4#p|3*dau^Fota$4(5F1S?eG$50OQvyGw4{@?W7&c*OWRcR|SeYe9hP3v1aA>0YZM-jT~R z4K~X4lE`-&Yz)R0cx=2i_Nuqie9&MTpF0eOt9+xz*0O+%ofR=pZk_4OY`M1Oq_Nk5 zwhR)G^&DiaZ4|{?hf0^qCLL5Tb@UQFi2-xe7DOfXf>oo|4YY!4WpR@D=|Lx)Nx`)) zYJ@#kI;v|z)i!n4B=>PG7P^l|5}WE{Aw7|-z^@lc^}14QRO@kCh8kyN4A-5tShMw6 zJj^QAe4(dVnWzjlvsP?IwUTJ2ruMvy|2NH_UjOW`UGOO43r#z~Pxr+XJ7xZum8#6gSNz zbsDQyjqIvat94oxMz*oFTv5u2KX)7g7W$^fj$^Obo5BmkVsGt~F?d{@bNoiz2js&t zYR`D~E~((4=G8TCyK4rOhxOE1=mzy}_y6&8@OOO75-LH+9DBBJ+ODx~=+qggE)cSp z99*wlpQ7xtP@Ae7FJI^SbOjMlelI2MmgRK3WOfRgpMll|jWD*B0^pdAMcsk3gXuT{ z4#{?6Rd83iGE=7%(6ggfh6oU+WogG)W@-`Xg_o37o25m;m@^RVYShhoQO0G27fHL~ zg;i$Ja9Fzw8UJlVKyL*xcOzUk4&2J~E__)pl;*`-ne4Ay$!7kN6Q@zk{?D>=$CeC* zFx3a-Z4HClh+cv-@HJn>VyD!wBCY8nryh5qz!~IC3;`+2@thFAJFCC8I@El$l9p>q z0Egj05N-GR-@WGoSdT?ySaaeN L!y-=I`0dVLxvZwD diff --git a/.test6.py.un~ b/.test6.py.un~ deleted file mode 100644 index 4d7438b478dbe17239ced7e632811ef8931b9921..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 20100 zcmeHPTXP&o6;_;^?Ocp=PY9tckz{49*3ufsj))RFjuXcvC61+B6Z`e{AB(g?>v9tUk`ro z{3UN)J#$t5;cI$&dR{}kMRO8`Bxz9Z zA2B39M&0RCk41w~U4=7hB~X6o*X~Z$LbM#9(%r0pf*hNbhNso&s2WmU%~z69)EPqW zqpZph2kBB=Q?3S@?mofdKK0;ISoPIXT?MOYQ1b&4^U^>q2bDC6QFk}%O-w+i58~+- zKCR=SRxhjvag^k86B7f)eyZ?|QdSz7m;fib%hJenqW~3$SYp_3D&T1BFi^lyAh~u7 zR-$Du4!v3>P*F`Sc(rgQs`_Z5Sse!@vifnhKV5ENc6^|ipTI>p-e;NOIW^XJ$a;Br60U@2Ug^Q4Zobij$m`O5RGLU-g;v z;c1gNGOZ|Q;RORL4Gn;0eFf#91nKrE$foR9QSDB4*{C+m%2Exo?o$vVs`*4Xt0+|* zdaV_+j&;QbMW~+XnDiLVvhzOmNKgx6s*~75rR|~es!?q=15VAv(SizUm1>lP$oGTg z&`U!=t939@D`7gP(m7C}YJ&RJq&|kh5J^1W!DpJ?hE^8$j|~jxGu^yiYEVL>YQ0d2 z>T5ZQQYJxC@v4DehD114!d= zRfRQmZ1l`$CeNsurCLQ8uZHu1@>H_8V({ghL@;-yyq+f%lQ>8a>GFo&d%i;om0Ly*t+!?D`Bqp zc(mNh{M&8*OcbkxB5br{ANSgF-gVpkCDr@c5q1B)g+nvX^%l?&^3Ro%enlE(O=OzH z#YQz6_MTYws!Ks49UroUH&1j~h~CuP5JZEDCMl}L(rhd%+a5w@zx&MS8{**zud~e9 z;^ih`+uW7HB=h&!+OZb`Voo520cLNoYqCnJ`XLu0otovr&qrO2JCNiY-8GLryx76HCoT{sun%^->5^2`+W2iC>*% zc$QU`L_lL$2CF*>${a8vNZ?ArX3Dfdifk`o)h5<#g0dX74`)lmYCwTAvuMJ8d2#Hm zb_>~0NmBc+-uvyQ@EVgGdErhk@AWnsC;g~FEA~HRr_p$c97j5rF0hb+>Oz)uM zj-3EiJ>XMRIWC2M+~10m=ld2UQ9F)58~en>h?wP)BnAvZ6XUXXIM5<0&2V#*!R98{ zvWYP`XJyv!We)W$j#j8?XE{Mfn8{$O=6egzV!xh)l^HG;jyOhUS=*RpQPOBdwhmV{ zT2ihIvI;?8X-v`Cf=VM*3s&qhh8n^dH-?kB^1A5xUBUq_7g3?c{4+ZXrLd@^0(l(x zOc!~{mGsoZuE6LqTI%4hqIT=HBPV1=*_8S`x(?xEcSi7ZdU#qkAl%4|%7%@*5ZTS> zN3$0>ZhOJFy?IXY%2FH$wN$go&8cjBW%6UYqqE}(3pv*mNJv(kq9s$qHng0L(9S#= zq3|lK92_|;=H;|))u$e>RoCohH=3DA0t_pi3$ZFBSf}Gzu94w7xrmlv*s4`o!=)oX zsAJ>H?PLOovX!aNl7mP`4o*Yw{8f}^E0ft-W5&*5TT+?Nl~@rwAy#ApYpfki>7bsr zXs>tiQ-Gu~*R?w6b!=VqQ_1*TMV@M_$WtGRBFl8)Ho6+ra#OGa)Ns*my&*zL(*{Wm zsxj1%4foSSER}teI?!AVRrV3Fr%_`Vg*h0EmaUfTZ&6Q637ezXJEvCV9cPV#31HFI z+*JfsW&NGPyLJM)Q>BqSWKR+ZN7$WcCbwfN+@Pd*!+}o6-Yni8^iIyMAbK^aL3ybN z_p|L9$(GM~F-Yg64@hG_#yCLulBETcIXr^gytf)AqeK1uL|^*v=@IkQryfnY4GxzB zXeoAQm8B{-#oX~x1%tT8$*>T3T*Z#E<0(4{8d{PTS|&V}S|78NcFm`7ICeAnJYZDWG9hy;t4hRW-*DnIU;T!I!C`K+uOV;a$DU!<&=4|qF(bqy zAEZ>?XIPF5v2H7KVKo5Qp}J3+(kAFi_bXBtJ1DBIX$|PMB|b3(<(Rw?T~`>)D;kO9 zQf%qD69`0Xxom)WwbrjCB(9vAfhv)eI?Ln>yL!I%~G>`Tx3TKT2ry zYagccen-80TD@t$JssVc3yZ?Tk~jqJ^*HjEDtu`Y`$&H0Wt$*-+2K4bs6W*&I(~-T zG3YLN9e^=x>36wW7ufKw;Zp9XLM3%YW63i$b!5N)7(kS_^cm9UcN@V*(9 zcu!Q~G7awY=;#H+KOz#`-9{yPdwcPu>wF%G7ZLx2*sK6-N$}n@C9VRn1yzS-t^yG7 zs}XIWG8F7XR{^XfI=pX20siCKg#G9!k9Z!D;BL{mM%Hz9%J<;k8ydJ7)gfhq`v*i) zcNK&!4wy1mL8uVdAlg7>8MY5y1+kLo@V*HJxv)bN!xLXYx+Tb*z1UZxf+1!ZyP<0^w#FTe1p7*4FIv?*0lt! z-e<>%(tX(~^FH2PdrhS#2d@#GX|MQ(dyGE>Xnc0nj!^t?9C($v7T=a5ww)ziUYQGm zYO^oI#sg>Za5&h~mggnnLeT0)LdQ+eFs>uVTbh;O!e*Rn(tJ5wkUC^q!vD0%x(!(=I#I zXelky*KV-kcm=iOs1X_i&u2|D&!EhOCMoJXxb#rr6YAopO#QYlFm7i}PB6-hBV>H{Dhm0BBeEZR{nvBgI-4kYXFvGsz z;(#|82XxEx$%6fX5gb(MrDs3!wW)$G?lMHt4z7RDetLn9W+SnA8<@G(v~xXovV)2n zOkq1O9Q)F95l0-;Q9ljX`&t>}to9qnYCt1T_m*Wif`fBOCr^#rVeakPwsI+#QU^am!7)*qSu3>eCORpn-? zk(Z+FSTKXZaplEN@{)Shs|bIrZf%htH>#hZpXo*Fqlq(&J*KlW@-sadgC*#2KO(<@ zIJkOHWfF-$?DW>zLdGLq6kb($Og=WO3bCYl3N-H_7NZ8z;%a2Yqvniy}# zoG>un%77k>^is7l(5)>8ny?+HmX`h@3|FmPW+a&%vT&Pud&<0>@NMLJL>u^~Vz!w|twFmOm8s~@6 z+et)=bBBK1feFp0(lo+Bb82XE~IYSh4&4C*L)~%ox3M!qX};uor|)Qv!pYuiRrD*P>B0w z_PL9-l|+Yk7hgB+V*RFIeXX9#6#W&5uOZ5|N%p)pm)6_*!xE_5_-q0}q=oM;uvQ}5 zxo2+%F-Lwm?c7EKWXJsq6 z$1@9@mhne5s!3rsNXs3qweB$ZqRUAy6Q2cw^rcL7!-pdQ|J1voJB``PJEkjv;m`|j G|LA`kxJ()SiZ3vYSFjs7Y{NrnL<6dEo(lUMA7Tuj@>q@l4ss1I z!o)Th*aUSw8~pg1qhbHjBiDl=ZqL8ibt#|*-k057<-Vq8ncJ+2;O{k&9a5JqyJcMO zC|Ai`&`{R0qQ#L?rBo^die-mw+4)3d(At@aXfkCv!>NQGYp>LgT5FmuvQ_4sSSp`S zjYN%7$)MDDx~$gCTY)Or&^0}#w=*x)>s&LKjB9*nYGQ6q^~Q?-`eJ^cTMIa{O#I~_ zt}Mh-j$@4sWOiDae6;-3&k?M>3m}#{6%VL)gSv!TH-vP3n9qM^y_-B^AE) zHuL6|6ZcF$lga(h%-xy9x&NNh+sNFVNnHIuGWT?c*V;4aO?GZ>++pvkq|wP|bA@Px b_ehJkx2NDG*FEWt_bu~!yBfSJoeTc}NQGDr delta 1808 zcmZ|PdrVtZ9Ki9@mGRhMWkX?ei#wDtd5gT?m>FfT!5Bd{+5WlETd30B_O=D8l9Hg& z#LUU+vNIHX_!u8 zQKyoGaG@L3_#=@HF@rOhKr4!IA2wonBc0=ST*n-ya1vwKhbmMe6G`}#Z28fH9oUW~ zD@px|e9XYe%M{9B$4!zwi%GnK2|R(r=tLDNVMjKMOLFy__cqxmJ>C*U*OgG-vDg>i zNRjl7B7~<2@CCz4Aok5}x0~%eLAN&~&1QA7dr+0-qvf(q>DT&PibuMYfbJSCF(bRw zKv4Ji>tgL4y3BJ9X-Xi!PIkEl1_N?rP*sPd!{zr5DgCNj^#o$=97A^_4~A9e|3~_Q zNDT2MkO8KuYXK#|m)JO+imtd-g4d_$)O4xH0oSnV ziBC>*bZdm@A?a2Xe^57PDf1jdMbe??$GUk$b9;jU)g0ijJZMhy-K+Us#(=V)AkD*6 z@E(SlmkU=MDk@?XIe zUc?I+z)|EN3&~jFKRSzxn8A5?;KVVsVjDIgWpfRUC@k}5y@so}g4a=vOstZf6)a;B zMz(IHZ~}dh9PO-H+YmieyJ(3t)Hg()sn3m6G#!tuHTlDeLx?Y!b}?%=a=U&M{YL(7 z;2oUB89Was9>X5w;5O~%@ijii1V&)=cZq(Ru*!0m@GE}6Jif=JRPt)%>MRtr;~3?qmG*oJFtrmHxgT)}Zbp%bN8 z;`};?*U*N&$i)_{acmAcgvJGh(lKuj9SZh(#GH uZ2y`Zb-VBVj~OdEUyQlzGW#jaGGp#8YrP2(Ef~QlCL_mdY*B~3-0~;45OjM0 diff --git a/robotransforms/euclidean/.euclidean_pure.py.swp b/robotransforms/euclidean/.euclidean_pure.py.swp index 3fe544036c02da1e1e6723982a795c097dffa56a..cd61bdc1b20b9414567667e19e66dfceb8881367 100644 GIT binary patch delta 15 WcmZo@U}{j9Aiw3nUhBEil*GkUMv=H&V!}4mz;( z4FAM8u5)7~*NFuZ3nUguERa|ru|Q&h!~%&05)1qvw?M1D$a^1Ue4Qz0Xuc2Y_&(g+ zUueFqTfoLU!h~-!-#g8>eZI)tUt_-CWFFY(Z!qC0^L=~A^Vgg3=On@^{+)7etC zJel@HO#LSpWk0jZ&*lBf20t}Ek(hg13$0g2Q$Pf`ET{} zK`vid(MLxiJFImKi?U7~l4dEECYjUm^CH+8U!^&{zciJO9Qp34qdQHNM~UAzkJGU{ zD!WMho_4`1Sh<}?Wtg(RN@^um7g)HUEu2sL8Gm?axt|kJT|r8$)LSgCjnr3cy0_S{ zu8Y26lI>M~DzEC?L>42O8j;NEj24!A^a0R-rLhY^BE2D?F8D)1<`86Y`&5 z$fTw-<-ua6l+N0KQl^|MW~K=s&D=DUnvKCS=}&qp4*xmQB_fyGkq3#KBeJUw{nKfG zGV6$=deEqj#h%WTh%Nf$qq9c>rAWN17b&GuGd}vVKFMc&$?Ph>m?;vNnI1BwUClx zQp6lJLAljUagf}m>FjBLfU2CCQKb}sY5PG z4?CNBGwER>m7Yj06t_fj117~tGFL1QPD^viTfrSU~VP|`?d-F^Z=SfETU~)PLB*5 z6NPpU<1X*?7;cB1+s@%C&*-G0WYquqE!)Db) zZdNu{GpJpm^D4JkP|r(}NtqYyR3zGT$I&WNkus;;erX}otY?}b`D`v^O7%=BjGAAL z5FVC7#y#Tkuov zJXFiok*jygVg4R+CREEUAh*ydH{4UsgsN7l@}-A%btyHZ6gpOQ$CsR*J+o?7WTroW zK}Ek{WEoEOJDTXJT$HQXNR2&q1nD-kGdJlD(R*@gh8ZlAqdHXEz)(4Yn(d$xLGl#4 zw>yoVmVEt@wjz<7kF+fl)I_e`kS3I>1saN^q6Kr3b~{J}B@dFI7VIvZCu#L-Mcpk( zzu-0dw4ToRc~iSms9vq6GyX8~#oD^Hm*s9d3eyLWS55gvw z1ow)a;}w0jUJF}(b#Au4zzYMN#9O*_sWQY&I41U>7AO3zS)Xig%kmbS^($Hb%B;WH zRNPD$bVs8BW%Ue(2=iYQx6vIpuC93y>Y8DHb-Gn?NV}%XaL(3qJh{?_lv0gs9nm3r za8u=s^5UnqYzoK<|0+!k)8tTg*{|1{l~!dw&^0eZqo@=Eb=yT%m3i939G5NBgC-sS z?3wUvf0hH>O@F3V(iPX*6jUXn#TM3X*8J8c5+cxFYNIT*`IFFA5YEc}HhF=BCO9 zm7zYlRL@lw$@e9Gv0Rp|S z9o`Ky5I`9&h9lr`c*5wpU34X%!~%&05(^|2NGy<8AhAGVfy4rd1riG+7Dy~`uoe&x zgmGnwx1)eRCRM88)@cS)5|ARGU@!7`ncVwA+H8DS36Tc2AtYLd?^x-_K@-3Y(++h-+o4uNw?9zU z|1YtBy;SzZS^r;X>gFNV^Y_C|a3j1IW z1RsDZEP;F2?_US2;T-rWd;2fIH{fqzC)^AzxB@2NA~+dNf>+q*{|fAZd*M3R4lTGC zeiMe_aCkku4xXcYkHf?85bT26;A8MXSb(iihBa_L3 zg|px!SPaL)PdPL25PTeNfUQu1HLwyga0;9NOW^0!!=v!m@TYJ!RNz0QbQA;VK9rfc3BrE`T984i>}DIdkwd+y#FHx56#(L8!nbFbcm4XTotxShwpiCU;(=44Q}wWdYcG;t zp%jek0KKshECi`@(t3YloS>LHnlWNxWQFOy+AGLjlG?kFBNFl$mD-Oj~HR~`83=@G;ATFUC7s_`E(S5O^EJ7NMO4GnVb_S=8x~i$d1iL>PK8E#m;>i-7PvN z_loT5w7TbZJC&Q~^f&2%9Tgr;;jWfg6E`me<~fgKzP4ISSC;`JBt~qiRsrs0tpeOR zR|VMVR&>}&I5x*efv#v2XvMo{YgZuyRZfqC>X3)&E%H)h`h`T6>=4nE)QzY|Eb{;v z>2AGD&=4EMimXE1jE5@3=Gx6;OfV{+D;ot`@dGWiX`*CXwM{9v=}M~HlBIURJ0f?K zy&+0^lwB0HKRG%4(0)zh)-6Z-@I!Y2WQ)_Sfha8#H5WG2Fl^%3%(nB?R%ys;%mH@5@Q|yTopjHaq%ej`uw&qe-GygPLdeFKSd$79Gj7ne4o^Tug)Q}4ri*gI#dVVrw+QN)ggP|T{=wn?W4mQGioL}C(fvAbD~;7mlpe~VNQpbkx&XG zndwqP5MxQBOHFFjKi{94Ppc7A>^&u|GkS}dn3tFQd1+Cqv&lw!+tTWlVzf)AQ&;+p zMRjj=$r5GW)u3xb{ohtI&~8@E##|6=3sPfKt*z(JPjUKlC=8mLiuE9+@6@&Ak+T+_ z#;}=H!|)BB~p4hD^TI1I}of2Nd5|mzjde(jh0pA)m{uCZ;3{TG zMWDz!CS{&hF%c=Z2QU?N+Un9#ktwUF$dvjWA(3?CT%!9K^rhXZdPH7Yv$8PSrBN$; zcoJVuq`Du8tDdW4zD9>S4`y`mhAQ#pNUHmZ(lByL2XFS0p2~-5D8&vrd9Lzi(ok}o zH;UxU8?n>3x;wM;&!FH1S{)&75u_25&iC1w4;$*ljMWnC|406qtD2H*~;K^1-n-U_Qgd;qfd z|25Y9Ux1yk1FnMw*a+)j4ahlzbKxX-96!Jw_%z%OABNwB&G1ebhcQ?Qr@;^L6FdU{ z2s=Uke&AZz3L9ZPtc5jj9vlTn!t?kG?uReJr{FK)Pv9oF8fvf>*1$>_gzw=mcpCm4 zz5!o?yFh#l*TNRq0B6COa0>hqh`-^xtowJv1MqinJBUxA1nXfPTmVC`1dfNjto^?a zpMbmJ&tL~^ht04Wej8Rm8dP1GdP=?$3nUguERa|rvA{kopx>Qd6Yry01L~LB#DQuT zl=gk^RrXyc4phA#*y&>#{h#%}+jW8Q0voqMybl=nfm#G`Z9VWR=kWzV;y~qqKkK^o z;x%#`x<0rl@L+w3u3t29pn5V{D4#Bi=MJBwaihgtkA(GcplZjkTW>nVt+a0Ev6>@d zwXH*3DIK!!dXDBAyjpo;<71`tj_TqtxV-dRyj(@!B~)CFRG;s`dX-y*5S@;%w0X`4n6Sx_~FR%^d_Xyqv?|=(oCAiS@g#cE7rPXBak}G`bli4shim8qLt_QK5i5gVLnQ5S zA=RB4>a-AXqP^Tk-fAaE&EZzSY>XHQ+e@9U7j~TZk$ZP=lY2X~Np_<0#0JH7s4LqJ zwHn%9e)FRaUQDMdMI&w_J8X0e{-H5d!!Z?kb!=q?iK#Z^9D5ODlj=5@nm~-mt6(rS z^2bj|nIP9xCTQPw(viqHBmO}ciP#5bBo#4gRN6=?sZJviD6nK)SD^pJPNSQtJ7EhiyN?s>u<+V2D&_`Ztv+ogcc_dU8wY*JHR_#}TMS*sr8j)5n3bw;xwHYx?Nkt~RhW8qjVu52p19a8T5 z_ePa&Ku=VL*Y80hp*oLjmU5#`hVpH@hm%d&I#Vhn`?71+UQEbtoqK2VATh;z;l`DF zH@4i{_}wF|Co1HJK2&yf`x6N#&jEQJlZ|r8vx@Iznm1H8ac!D;Ac)`c<`XypXcQh-bT9%s$zcT*tatY?;E1v2pay?wDAr zSD9T*7_ZxQ&C0W!nhIhTHbHJ~P0)VqtW=R{vog_xQO62`*O9E8EX>+-kFoQO`dDLh z%F&Y?O6M>mo$emW-zPfMh^Ed((a=((J-WvMo1xnZI>a@C4*6ee1359GY@n>>w1vQAxzX`iR{x0BFxE|gEGY~)-E{5fB0;s&2d?sIs1riG+7Dz0R zSRk=LVu8d0i3R?DT0mB8`V;K|uo%Qu6L(vyC1tYz5w}qzZX>$@P4++Z=_J|Wk-dl5 zM%q4&BzqL?{j_~-5~+yF!6k@B Q_RfvoI= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +# rotvec is RV from +# https://www.ncbi.nlm.nih.gov/pmc/articles/PMC6339217/pdf/sensors-19-00149.pdfh +def quat2rotvec(quat): + if np.allclose(quat, np.array([1., 0., 0., 0.])): + return np.array([0., 0., 0.]) + + rotvec = np.zeros(3) + qvec_norm = np.linalg.norm(quat[1:]) + # TODO: Figure out what to do otherwise + print("quat:", quat) + if quat[0] >= 0: + rotvec = 2 * np.arcsin(qvec_norm) * quat[1:] / qvec_norm + else: + # Figure out what to do here... + print("GOT HERE quat2rotvec") + rotvec = 2 * np.arcsin(-qvec_norm) * -quat[1:] / qvec_norm + + return rotvec + +def rotvec2quat(rotvec): + if np.allclose(rotvec, np.zeros_like(rotvec)): + return np.array([1., 0., 0., 0.]) + + #print("rotvec:", rotvec) + rotvec_norm = np.linalg.norm(rotvec) + #print("rotvec norm:", rotvec_norm) + if rotvec_norm <= np.pi: + quat = np.zeros(4) + quat[0] = np.cos(rotvec_norm / 2) + quat[1:] = np.sin(rotvec_norm / 2) * rotvec / rotvec_norm + else: + # Figure out what to do here... + print("GOT HERE rotvec2quat") + quat = np.zeros(4) + quat[0] = np.cos(rotvec_norm / 2) + quat[1:] = np.sin(rotvec_norm / 2) * rotvec / rotvec_norm + + return quat + +def quat2rp(quat): + return 2 * quat[1:] / quat[0] + +def rp2quat(rp): + norm = np.linalg.norm(rp) + factor = 1 / np.sqrt(4 + norm**2) + return factor * np.hstack([2, rp]) + +def dead_reckon_apply(x_hat, P_hat, step, j): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 4 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + # dl, dr, vave, vdiff + e = dead_reckon_step_errors( step[1], step[2]) #, step[7], step[8] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z_euc = np.zeros((2*L+1,SM+2)) + Z[0] = z.copy() + Z_euc[0] = np.hstack([z[:2], quat2rotvec(np.array([z[2],0,0,z[3]]))[2], z[-2:]]) + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + # NOTE: dz (the cholesky decomp) gives us vectors with euclidean + # dimensions, i.e. dz[2] is e[2], where e = [e0, e1, e2] are rotation + # vector embeddings of S^3 in R^3 + print("dz") + for s in dz: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + + # x_hat y_hat z a b c d + lrQ = np.array([z[0], z[1], 0, z[2], 0 ,0, z[3]]) + print("lrQ", lrQ) + + # Computing sigma points + for i in range(L): + ## The first SS are gotten via composition + #dlrQ_pos = np.array([dz[i][0], dz[i][1], 0]) + #drv = np.array([0, 0, dz[i][2]]) + #dlrQ = np.hstack([dlrQ_pos, rp2quat(drv)]) + ##dlrQ = np.array([dz[i][0], dz[i][1], 0, np.cos(dz[i][2]), 0 ,0, dz[i][2]]) + ## TODO SUSPECTED BUG + #lrQ1 = t.compose_lrQ(lrQ, dlrQ) + ## x y a d + #Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[3], lrQ1[6]]) + + #dlrQ_pos = np.array([-dz[i][0], -dz[i][1], 0]) + #drv = np.array([0, 0, -dz[i][2]]) + #dlrQ = np.hstack([dlrQ_pos, rp2quat(drv)]) + ##dlrQ = np.array([-dz[i][0], -dz[i][1], 0, np.sqrt(1-dz[i][2]**2), 0, 0, -dz[i][2]]) + ## TODO SUSPECTED BUG + #lrQ2 = t.compose_lrQ(lrQ, dlrQ) + #Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[3], lrQ2[6]]) + + ## The last 2 (dl, dr) are gotten via addition + #Z[1 + i][SS:] = z[SS:] + dz[i][SM:] + #Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + + # z is [x,y,a,d,dl,dr], dz has [x,y,e3,dl,dr] + # + # Convert z to euclidean + Z_euc[1 + i] = Z_euc[0] + dz[i] + Z_euc[1 + i + L] = Z_euc[0] - dz[i] + + print(Z_euc.shape) + for item in Z_euc[:,2]: + print(rotvec2quat(np.array([0.,0.,item]))) + Z_quat = np.array([rotvec2quat(np.array([0.,0.,e3])) for e3 in Z_euc[:,2]]) + Z = np.hstack([Z_euc[:,:2], Z_quat[:,:1], Z_quat[:,3:], Z_euc[:,-2:]]) + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) #, np.sqrt(row[2]**2+row[3]**2)) + print() + + # Transform to new vectors + def T(_z): + # a b c d + quat = np.array([_z[2], 0 ,0, _z[3]]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) + # Taking current quat and applying step quat rotation to it + next_quat = t.compose_quat(quat, step[3:7]) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], next_quat[0], next_quat[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row))#, np.sqrt(row[2]**2+row[3]**2)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + # Grab x and y in every sigma point + Y_pos = Y[:,:2] + + # Take a weighted average of the position components + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] + + ## Iteratively calculate the quaternion mean + Y_quat = np.array([[a,0,0,d] for a,d in zip(Y[:,2],Y[:,3])]) + #print("Y_quat", Y_quat) + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rvecs = np.array([quat2rotvec(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rvecs[0]*W0 + np.sum(e_rvecs[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, rotvec2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rvecs[:,2:]]) + + #dY = Y - y_bar + + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + print("cov") + for row in cov: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + x_tilde = T(z) # transform the mean + P_tilde = cov + + for zz in Z: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="green", alpha=0.5) + for zz in Y: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="blue", alpha=0.5) + + #if j > 10: + # plt.show() + # #plot_quaternions(Y_quat, 3) + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps, j): + for i, step in enumerate(steps): + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step, j) + return x_hat, P_hat + +## ====================== +## TEST +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +# x,y,a,d +x_hat = np.array([0,0,1,0]) +P_hat = np.diag([1e-1,1e-1,0.2]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + #0.215, 0.143, # vave, vdiff +]) +steps = 3*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps, i) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test3.py~ b/test6.py similarity index 56% rename from test3.py~ rename to test6.py index d49e785..87ee492 100644 --- a/test3.py~ +++ b/test6.py @@ -2,6 +2,31 @@ import numpy as np import matplotlib.pyplot as plt import robotransforms.euclidean.euclidean_pure as t +from scipy.spatial.transform import Rotation as R + +def plot_quaternions(quaternions, nrows=1): + n_quaternions = quaternions.shape[0] + ncols = int(np.ceil(n_quaternions / nrows)) + + fig, axes = plt.subplots(nrows=nrows, ncols=ncols, figsize=(3*ncols, 3*nrows)) + axes = axes.flatten() + + for i in range(n_quaternions): + quat = quaternions[i] + r = R.from_quat(quat) + yaw = r.as_euler('zyx')[2] + + axes[i].arrow(0, 0, np.cos(yaw), np.sin(yaw), head_width=0.1, head_length=0.1, fc='k', ec='k') + axes[i].set_xlim(-1.2, 1.2) + axes[i].set_ylim(-1.2, 1.2) + axes[i].set_aspect('equal') + axes[i].set_title(f'Quaternion {i+1}') + + for i in range(n_quaternions, nrows*ncols): + axes[i].axis('off') + + plt.tight_layout() + plt.show() ## ====================== ## CODE @@ -40,14 +65,40 @@ def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.0 # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz -def dead_reckon_apply(x_hat, P_hat, step): +# rotvec is RV from +# https://www.ncbi.nlm.nih.gov/pmc/articles/PMC6339217/pdf/sensors-19-00149.pdfh +def quat2rotvec(quat): + rotvec = np.zeros(3) + qvec_norm = np.linalg.norm(quat[1:]) + # TODO: Figure out what to do otherwise + if quat[0] >= 0: + rotvec = 2 * np.arcsin(qvec_norm) * quat[1:] + else: + # Figure out what to do here... + rotvec = None + + return rotvec + +def rotvec2quat(rotvec): + rotvec_norm = np.linalg.norm(rotvec) + if rotvec_norm <= np.pi: + quat = np.zeros(4) + quat[0] = np.cos(rotvec_norm / 2) + quat[1:] = np.sin(rotvec_norm / 2) * rotvec + else: + # Figure out what to do here... + quat = None + + return quat + +def dead_reckon_apply(x_hat, P_hat, step, j): # No-op if we didn't move if (step[1] == 0 and step[2] == 0): return x_hat, P_hat # Build up extended state vector - SS = 3 + SS = 4 z = np.zeros((SS+2)) z[:SS] = x_hat[:] z[SS+0] = step[1] @@ -88,45 +139,43 @@ def dead_reckon_apply(x_hat, P_hat, step): # print(w.T) raise e - # x_hat y_hat a b c d - lrQ = t.lrq2lrQ([z[0], z[1], 0, 0 ,0, z[2]]) + # x_hat y_hat z a b c d + lrQ = np.array([z[0], z[1], 0, z[2], 0 ,0, z[3]]) + print("lrQ", lrQ) # Computing sigma points for i in range(L): # The first SS are gotten via composition - dlrQ = t.lrq2lrQ([dz[i][0], dz[i][1], 0, 0 ,0, dz[i][2]]) + dlrQ = np.array([dz[i][0], dz[i][1], 0, np.sqrt(1-dz[i][2]**2), 0 ,0, dz[i][2]]) lrQ1 = t.compose_lrQ(lrQ, dlrQ) - # x y d - Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[6]]) - dlrQ = t.lrq2lrQ([-dz[i][0], -dz[i][1], 0, 0 ,0, -dz[i][2]]) + # x y a d + Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[3], lrQ1[6]]) + dlrQ = np.array([-dz[i][0], -dz[i][1], 0, np.sqrt(1-dz[i][2]**2), 0, 0, -dz[i][2]]) lrQ2 = t.compose_lrQ(lrQ, dlrQ) - Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[6]]) + Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[3], lrQ2[6]]) # The last 2 (dl, dr) are gotten via addition Z[1 + i][SS:] = z[SS:] + dz[i][SM:] Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] print("Z") for row in Z: - print(",".join("{:12.8f}".format(v) for v in row)) + print(",".join("{:12.8f}".format(v) for v in row)) #, np.sqrt(row[2]**2+row[3]**2)) print() # Transform to new vectors def T(_z): - # b c d - quat = t.redquat2quat([0 ,0, _z[2]]) + # a b c d + quat = np.array([_z[2], 0 ,0, _z[3]]) dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) # Taking current quat and applying step quat rotation to it - next_quat = t.compose_quat(quat,step[3:7]) + next_quat = t.compose_quat(quat, step[3:7]) # Only return offset, this is marginalizing out all the quat dependances # return _z[:3] + dx - return np.hstack([_z[:2] + dx[:2], next_quat[3]]) + return np.hstack([_z[:2] + dx[:2], next_quat[0], next_quat[3]]) Y = np.array([ T(_z) for _z in Z ]) - #plt.plot(Z[:,0],Z[:,1],"go") - #plt.plot(Y[:,0],Y[:,1],"bx") - #plt.show() print("Y") for row in Y: - print(",".join("{:12.8f}".format(v) for v in row)) + print(",".join("{:12.8f}".format(v) for v in row))#, np.sqrt(row[2]**2+row[3]**2)) print() M = len(Y[0]) @@ -139,9 +188,28 @@ def T(_z): # Take a weighted average of the position components y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] - - # Iteratively calculate the quaternion mean - Y_quat = np.array([t.redquat2quat([0,0,d]) for d in Y[:,2]]) + + #Y_quat = np.array([[a,0,0,d] for a,d in zip(Y[:,2],Y[:,3])]) + #print("Y_quat shape:", Y_quat.shape) + #Y_euler = np.array([t.quat2euler(q) for q in Y_quat]) + #print("Y_euler shape:", Y_euler.shape) + #y_euler_bar = (Y_euler[0]*W0 + np.sum(Y_euler[1:]*W,axis=0)) + #print("Y_euler_bar shape:", y_euler_bar.shape) + #y_euler_diff = Y_euler-y_euler_bar + #print("Y_euler_diff shape:", y_euler_diff.shape) + + #dy_quat_bar = np.array([t.quat2redquat(t.euler2quat(q)) for q in y_euler_diff]) + #print("dy_quat_bar shape:", dy_quat_bar.shape) + #print("Y_pos - y_pos_bar shape:", (Y_pos - y_pos_bar).shape) + #print("dy_quat_bar[:,:1] shape:", dy_quat_bar[:,:1].shape) + #print("dy_quat_bar[:,2:]", dy_quat_bar[:,2:].shape) + + #dY = np.hstack([Y_pos - y_pos_bar, dy_quat_bar[:,2:]]) + #print("dY shape:", dY.shape) + + ## Iteratively calculate the quaternion mean + Y_quat = np.array([[a,0,0,d] for a,d in zip(Y[:,2],Y[:,3])]) + #print("Y_quat", Y_quat) q_bar = Y_quat[0] q_bar_inv = t.invert_quat(Y_quat[0]) EPS = 1e-12 @@ -158,7 +226,12 @@ def T(_z): print(i, error) - dY = np.hstack([Y_pos-y_pos_bar, e_rquats[:,2:]]) + dY = np.hstack([Y_pos-y_pos_bar, e_rquats[:,2:]]) + + #dY = Y - y_bar + + + # for row in dY: # print(",".join("{:12.8f}".format(v) for v in row)) # print() @@ -169,15 +242,42 @@ def T(_z): cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product for k in range(1,len(dY)): cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product - + + print("cov") + for row in cov: + print(",".join("{:12.8f}".format(v) for v in row)) + print() x_tilde = T(z) # transform the mean P_tilde = cov + for zz in Z: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="green", alpha=0.5) + for zz in Y: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="blue", alpha=0.5) + + #if j > 10: + # plt.show() + # plot_quaternions(Y_quat, 3) + return x_tilde, P_tilde -def dead_reckon(x_hat, P_hat, steps): - for step in steps: - x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) +def dead_reckon(x_hat, P_hat, steps, j): + for i, step in enumerate(steps): + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step, j) return x_hat, P_hat ## ====================== @@ -189,7 +289,8 @@ def dead_reckon(x_hat, P_hat, steps): dr = 0.07 to2 = ( dl - dr ) / ( 2 * D ) -x_hat = np.array([0,0,0]) +# x,y,a,d +x_hat = np.array([0,0,1,0]) P_hat = np.diag([1e-1,1e-1,0.05]) step = np.array([ 43994.76, # ts @@ -205,7 +306,7 @@ def dead_reckon(x_hat, P_hat, steps): for i in range(50): print("==================================== "+str(i+1)) - x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps, i) xhs.append(x_hat) phs.append(P_hat) diff --git a/test6.py~ b/test6.py~ deleted file mode 100644 index 4142002..0000000 --- a/test6.py~ +++ /dev/null @@ -1,179 +0,0 @@ - -import numpy as np -import matplotlib.pyplot as plt -import robotransforms.euclidean.euclidean_pure as t -import robotransforms.utils.utils as rt_utils - -## ====================== -## CODE -## ====================== -def DeadReckonStep(timestamp, dl, dr, Dq): #, vave, vdiff): - return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3]]) #, vave, vdiff ]) - -L_PLUS_LAMBDA = 3 - -def sinc(x): - # Use power series for small x - if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) - return np.sin(x)/x - -D = 0.5 -def dead_reckon_step( quat, dl, dr): #, vave, vdiff ): - lstar = 0.5 * ( dl + dr ) - to2 = ( dl - dr ) / ( 2 * D ) - chord = lstar * sinc(to2) - sin = np.sin(to2) - cos = np.cos(to2) - - dx = chord * sin - dy = chord * cos - - return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) - -def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.005): - ddl = (dl_scale * np.abs(dl)) - ddr = (dl_scale * np.abs(dr)) - rho=1-1e-3 - #rho = 1-1e-8 - #if ( np.abs(vdiff) >= 1e-3 ) : - # rho = np.abs(np.tanh( vave / vdiff )) - - # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] - return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz - -def jacobian_quat_position(quat, dl, dr): - """ - Compute the Jacobian of the position component with respect to the quaternion - for a given wheel odometry measurement (dl, dr). - - Parameters: - quat (numpy array): Quaternion representing the rotation. - dl (float): Left wheel displacement. - dr (float): Right wheel displacement. - - Returns: - numpy array: The 3x3 Jacobian matrix. - """ - - qw, qx, qy, qz = quat - - J = np.array([ - [2 * qw * dr - 2 * qy * dl, 2 * qx * dr + 2 * qz * dl, -2 * qz * dr + 2 * qx * dl, -2 * qy * dr - 2 * qw * dl], - [2 * qy * dr + 2 * qw * dl, -2 * qx * dr + 2 * qz * dl, 2 * qw * dr + 2 * qy * dl, 2 * qz * dr + 2 * qx * dl], - [-2 * qx * dl - 2 * qz * dr, -2 * qy * dl + 2 * qw * dr, 0, 0] - ]) - - return J - - -def dead_reckon_apply(x_hat, P_hat, step): - - # Generate sigma points - Z = sigma_points(x_hat, P_hat, alpha, beta, kappa) - SS = len(x_hat) - - # Transform to new vectors - def T(_z): - # Apply transformation for each sigma point - d_wheels = np.array([_z[SS+0], _z[SS+1]]) - quat = t.redquat2quat([0, 0, _z[2]]) - _new_pos = t.transform_quat_position(quat, d_wheels) - return np.hstack([_z[:SS] + _new_pos, _z[SS+2:]]) - - Y = np.array([T(_z) for _z in Z]) - - # Calculate the Jacobian of the transformation - def dT_dq(_z): - quat = t.redquat2quat([0, 0, _z[2]]) - return jacobian_quat_position(quat, _z[SS+0], _z[SS+1]) - - J_quat = np.array([dT_dq(_z) for _z in Z]) - - y_pos_bar = W0 * Y[0][:SS] + W * Y[1:2 * SS].sum(axis=0) - Y_pos = Y[:, :SS] - Z_pos = Z[:, :SS] - e_quats = Z[:, 2:3] - y_pos_bar[2] - - e_rquats = t.redquats2rquats(e_quats) - dY = np.hstack([Y_pos - y_pos_bar, e_rquats[:, 2:]]) - dY_quat = np.hstack([Y_pos - y_pos_bar, e_rquats]) - - cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) - cov_quat = W0 * np.array([dY_quat[0]]).T @ J_quat[0] @ np.array([dY_quat[0]]) - - for k in range(1, len(dY)): - cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) - cov_quat += W * np.array([dY_quat[k]]).T @ J_quat[k] @ np.array([dY_quat[k]]) - - # Add the quaternion-related covariance to the position-related covariance - cov[:2, :2] += cov_quat[:2, :2] - - x_tilde = T(x_hat) - P_tilde = cov - - return x_tilde, P_tilde - -def dead_reckon(x_hat, P_hat, steps): - for step in steps: - x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) - return x_hat, P_hat - -## ====================== -## test -## ====================== - -D = 0.464 -dl = 0.08 -dr = 0.07 -to2 = ( dl - dr ) / ( 2 * D ) - -x_hat = np.array([0,0,0]) -P_hat = np.diag([1e-1,1e-1,0.05]) -step = np.array([ - 43994.76, # ts - dl, dr, # dl, dr - np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d - #0.215, 0.143, # vave, vdiff -]) -steps = 3*[step] - - -xhs = [x_hat] -phs = [P_hat] - -for i in range(50): - print("==================================== "+str(i+1)) - x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) - xhs.append(x_hat) - phs.append(P_hat) - - v,w = np.linalg.eigh(P_hat) - print("v") - print(",".join("{:12.8f}".format(v) for v in v)) - print() - print("W") - for row in w: - print(",".join("{:12.8f}".format(v) for v in row)) - print() - -print("x") -print(",".join("{:12.8f}".format(v) for v in x_hat)) -print() -print("P") -for row in P_hat: - print(",".join("{:12.8f}".format(v) for v in row)) -print() - - -fig = plt.figure() -ax = fig.add_subplot(111) - -for x,p in zip(xhs, phs): - L = np.linalg.cholesky(p)[:2,:2] - xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) - plt.plot(x[:1], x[1:2], "x") - plt.plot(xy[:,0], xy[:,1]) - - -plt.show() - diff --git a/test5.py~ b/test7.py similarity index 83% rename from test5.py~ rename to test7.py index d6ac52f..793a238 100644 --- a/test5.py~ +++ b/test7.py @@ -44,7 +44,7 @@ def dead_reckon_step_errors( dl, dr, dl_scale=0.005): # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz -def dead_reckon_apply(x_hat, P_hat, step): +def dead_reckon_apply(x_hat, P_hat, step, idx): # No-op if we didn't move if (step[1] == 0 and step[2] == 0): @@ -131,14 +131,39 @@ def T(_z): for k in range(1,len(dY)): cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + print("cov") + for row in cov: + print(",".join("{:12.8f}".format(v) for v in row)) + print() x_tilde = T(z) # transform the mean P_tilde = cov + for zz in Z: + euler = [-zz[2], 0, 0] + xyz = np.array([ t.apply_euler(euler, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="green", alpha=0.5) + for zz in Y: + euler = [-zz[2], 0, 0] + xyz = np.array([ t.apply_euler(euler, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="blue", alpha=0.5) + #if idx > 10: + # plt.show() + return x_tilde, P_tilde -def dead_reckon(x_hat, P_hat, steps): +def dead_reckon(x_hat, P_hat, steps, i): for step in steps: - x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step) + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step, i) return x_hat, P_hat ## ====================== @@ -166,7 +191,7 @@ def dead_reckon(x_hat, P_hat, steps): for i in range(50): print("==================================== "+str(i+1)) - x_hat, P_hat = dead_reckon(x_hat, P_hat, steps) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps, i) xhs.append(x_hat) phs.append(P_hat) diff --git a/test8.py b/test8.py new file mode 100644 index 0000000..5d8d29b --- /dev/null +++ b/test8.py @@ -0,0 +1,347 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean.euclidean_pure as t +from scipy.spatial.transform import Rotation as R + +def plot_quaternions(quaternions, nrows=1): + n_quaternions = quaternions.shape[0] + ncols = int(np.ceil(n_quaternions / nrows)) + + fig, axes = plt.subplots(nrows=nrows, ncols=ncols, figsize=(3*ncols, 3*nrows)) + axes = axes.flatten() + + for i in range(n_quaternions): + quat = quaternions[i] + r = R.from_quat(quat) + yaw = r.as_euler('zyx')[2] + + axes[i].arrow(0, 0, np.cos(yaw), np.sin(yaw), head_width=0.1, head_length=0.1, fc='k', ec='k') + axes[i].set_xlim(-1.2, 1.2) + axes[i].set_ylim(-1.2, 1.2) + axes[i].set_aspect('equal') + axes[i].set_title(f'Quaternion {i+1}') + + for i in range(n_quaternions, nrows*ncols): + axes[i].axis('off') + + plt.tight_layout() + plt.show() + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dq): #, vave, vdiff): + return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3]]) #, vave, vdiff ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( quat, dl, dr): #, vave, vdiff ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho=1-1e-3 + #rho = 1-1e-8 + #if ( np.abs(vdiff) >= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +# rotvec is RV from +# https://www.ncbi.nlm.nih.gov/pmc/articles/PMC6339217/pdf/sensors-19-00149.pdfh +def quat2rotvec(quat): + if np.allclose(quat, np.array([1., 0., 0., 0.])): + return np.array([0., 0., 0.]) + + rotvec = np.zeros(3) + qvec_norm = np.linalg.norm(quat[1:]) + # TODO: Figure out what to do otherwise + print("quat:", quat) + if quat[0] >= 0: + rotvec = 2 * np.arcsin(qvec_norm) * quat[1:] / qvec_norm + else: + # Figure out what to do here... + print("GOT HERE quat2rotvec") + rotvec = None + + return rotvec + +def rotvec2quat(rotvec): + if np.allclose(rotvec, np.zeros_like(rotvec)): + return np.array([1., 0., 0., 0.]) + + print("rotvec:", rotvec) + rotvec_norm = np.linalg.norm(rotvec) + print("rotvec norm:", rotvec_norm) + if rotvec_norm <= np.pi: + quat = np.zeros(4) + quat[0] = np.cos(rotvec_norm / 2) + quat[1:] = np.sin(rotvec_norm / 2) * rotvec / rotvec_norm + else: + # Figure out what to do here... + print("GOT HERE rotvec2quat") + quat = None + + return quat + +def dead_reckon_apply(x_hat, P_hat, step, j): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 4 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + # dl, dr, vave, vdiff + e = dead_reckon_step_errors( step[1], step[2]) #, step[7], step[8] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + # NOTE: dz (the cholesky decomp) gives us vectors with euclidean + # dimensions, i.e. dz[2] is e[2], where e = [e0, e1, e2] are rotation + # vector embeddings of S^3 in R^3 + print("dz") + for s in dz: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + + # x_hat y_hat z a b c d + lrQ = np.array([z[0], z[1], 0, z[2], 0 ,0, z[3]]) + print("lrQ", lrQ) + # Computing sigma points + for i in range(L): + # The first SS are gotten via composition + dlrQ_pos = np.array([dz[i][0], dz[i][1], 0]) + dlrQ_rv = np.array([0, 0, dz[i][2]]) + dlrQ = np.hstack([dlrQ_pos, rotvec2quat(dlrQ_rv)]) + #dlrQ = np.array([dz[i][0], dz[i][1], 0, np.cos(dz[i][2]), 0 ,0, dz[i][2]]) + lrQ1 = t.compose_lrQ(lrQ, dlrQ) + # x y a d + Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[3], lrQ1[6]]) + + dlrQ_pos = np.array([-dz[i][0], -dz[i][1], 0]) + dlrQ_rv = np.array([0, 0, -dz[i][2]]) + dlrQ = np.hstack([dlrQ_pos, rotvec2quat(dlrQ_rv)]) + #dlrQ = np.array([-dz[i][0], -dz[i][1], 0, np.sqrt(1-dz[i][2]**2), 0, 0, -dz[i][2]]) + lrQ2 = t.compose_lrQ(lrQ, dlrQ) + Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[3], lrQ2[6]]) + + # The last 2 (dl, dr) are gotten via addition + Z[1 + i][SS:] = z[SS:] + dz[i][SM:] + Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) #, np.sqrt(row[2]**2+row[3]**2)) + print() + + # Transform to new vectors + def T(_z): + # a b c d + quat = np.array([_z[2], 0 ,0, _z[3]]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) + # Taking current quat and applying step quat rotation to it + next_quat = t.compose_quat(quat, step[3:7]) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], next_quat[0], next_quat[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row))#, np.sqrt(row[2]**2+row[3]**2)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + # Grab x and y in every sigma point + Y_pos = Y[:,:2] + + # Take a weighted average of the position components + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] + + ## Iteratively calculate the quaternion mean + Y_quat = np.array([[a,0,0,d] for a,d in zip(Y[:,2],Y[:,3])]) + #print("Y_quat", Y_quat) + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rvecs = np.array([quat2rotvec(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rvecs[0]*W0 + np.sum(e_rvecs[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, rotvec2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rvecs[:,2:]]) + + #dY = Y - y_bar + + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + print("cov") + for row in cov: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + x_tilde = T(z) # transform the mean + P_tilde = cov + + for zz in Z: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="green", alpha=0.5) + for zz in Y: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="blue", alpha=0.5) + + #if j > 10: + # plt.show() + # plot_quaternions(Y_quat, 3) + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps, j): + for i, step in enumerate(steps): + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step, j) + return x_hat, P_hat + +## ====================== +## TEST +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +# x,y,a,d +x_hat = np.array([0,0,1,0]) +P_hat = np.diag([1e-1,1e-1,0.2]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + #0.215, 0.143, # vave, vdiff +]) +steps = 1*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps, i) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() + diff --git a/test9.py b/test9.py new file mode 100644 index 0000000..6f90ef6 --- /dev/null +++ b/test9.py @@ -0,0 +1,355 @@ + +import numpy as np +import matplotlib.pyplot as plt +import robotransforms.euclidean.euclidean_pure as t +from scipy.spatial.transform import Rotation as R + +def plot_quaternions(quaternions, nrows=1): + n_quaternions = quaternions.shape[0] + ncols = int(np.ceil(n_quaternions / nrows)) + + fig, axes = plt.subplots(nrows=nrows, ncols=ncols, figsize=(3*ncols, 3*nrows)) + axes = axes.flatten() + + for i in range(n_quaternions): + quat = quaternions[i] + r = R.from_quat(quat) + yaw = r.as_euler('zyx')[2] + + axes[i].arrow(0, 0, np.cos(yaw), np.sin(yaw), head_width=0.1, head_length=0.1, fc='k', ec='k') + axes[i].set_xlim(-1.2, 1.2) + axes[i].set_ylim(-1.2, 1.2) + axes[i].set_aspect('equal') + axes[i].set_title(f'Quaternion {i+1}') + + for i in range(n_quaternions, nrows*ncols): + axes[i].axis('off') + + plt.tight_layout() + plt.show() + +## ====================== +## CODE +## ====================== +def DeadReckonStep(timestamp, dl, dr, Dq): #, vave, vdiff): + return np.array([ timestamp, dl, dr, Dq[0], Dq[1], Dq[2], Dq[3]]) #, vave, vdiff ]) + +L_PLUS_LAMBDA = 3 + +def sinc(x): + # Use power series for small x + if (np.abs(x) < 1e-4): return 1 - (x*x/6) + (x*x*x*x/120) + return np.sin(x)/x + +D = 0.5 +def dead_reckon_step( quat, dl, dr): #, vave, vdiff ): + lstar = 0.5 * ( dl + dr ) + to2 = ( dl - dr ) / ( 2 * D ) + chord = lstar * sinc(to2) + sin = np.sin(to2) + cos = np.cos(to2) + + dx = chord * sin + dy = chord * cos + + return t.apply_quat(t.invert_quat(quat), [dx,dy,0]) + +def dead_reckon_step_errors( dl, dr, dl_scale=0.005): #vave, vdiff, dl_scale=0.005): + ddl = (dl_scale * np.abs(dl)) + ddr = (dl_scale * np.abs(dr)) + rho=1-1e-3 + #rho = 1-1e-8 + #if ( np.abs(vdiff) >= 1e-3 ) : + # rho = np.abs(np.tanh( vave / vdiff )) + + # [ var_dl, cov_dldr, var_dr, var_b, var_c, var_d ] + return [ ddl*ddl + 1e-8, rho*ddl*ddr, ddr*ddr + 1e-8 ] # TODO : these are estimates, based on gps's 1Hz + +# rotvec is RV from +# https://www.ncbi.nlm.nih.gov/pmc/articles/PMC6339217/pdf/sensors-19-00149.pdfh +def quat2rotvec(quat): + if np.allclose(quat, np.array([1., 0., 0., 0.])): + return np.array([0., 0., 0.]) + + rotvec = np.zeros(3) + qvec_norm = np.linalg.norm(quat[1:]) + # TODO: Figure out what to do otherwise + print("quat:", quat) + if quat[0] >= 0: + rotvec = 2 * np.arcsin(qvec_norm) * quat[1:] / qvec_norm + else: + # Figure out what to do here... + print("GOT HERE quat2rotvec") + rotvec = None + + return rotvec + +def rotvec2quat(rotvec): + if np.allclose(rotvec, np.zeros_like(rotvec)): + return np.array([1., 0., 0., 0.]) + + print("rotvec:", rotvec) + rotvec_norm = np.linalg.norm(rotvec) + print("rotvec norm:", rotvec_norm) + if rotvec_norm <= np.pi: + quat = np.zeros(4) + quat[0] = np.cos(rotvec_norm / 2) + quat[1:] = np.sin(rotvec_norm / 2) * rotvec / rotvec_norm + else: + # Figure out what to do here... + print("GOT HERE rotvec2quat") + quat = None + + return quat + +def quat2rp(quat): + return 2 * quat[1:] / quat[0] + +def rp2quat(rp): + norm = np.linalg.norm(rp) + factor = 1 / np.sqrt(4 + norm**2) + return factor * np.hstack([2, rp]) + +def dead_reckon_apply(x_hat, P_hat, step, j): + + # No-op if we didn't move + if (step[1] == 0 and step[2] == 0): + return x_hat, P_hat + + # Build up extended state vector + SS = 4 + z = np.zeros((SS+2)) + z[:SS] = x_hat[:] + z[SS+0] = step[1] + z[SS+1] = step[2] + + # Build up extended covariance on manifold + SM = 3 + P_z = np.zeros((SM+2,SM+2)) + P_z[:SM,:SM] = P_hat[:SM,:SM] + # dl, dr, vave, vdiff + e = dead_reckon_step_errors( step[1], step[2]) #, step[7], step[8] ) + P_z[0+SM][0+SM] = e[0] # var_dl + P_z[0+SM][1+SM] = e[1] # cov_dldr + P_z[1+SM][0+SM] = e[1] # cov_dldr + P_z[1+SM][1+SM] = e[2] # var_dr + + # Generate sigma points along manifold from enclosing deviation vectors with the state + L = SM+2 + Z = np.zeros((2*L+1,SS+2)) + Z[0] = z.copy() + scaled_cov = P_z * L_PLUS_LAMBDA + # Rows of the R matrix in A=R^TR function like a square root + try: + # Generate the deviation vectors along manifold + dz = np.linalg.cholesky( scaled_cov ).T # NOTE, np returns L, not R, so we transpose it + except Exception as e: + v,w = np.linalg.eigh(scaled_cov) + print("Cov") + for s in scaled_cov: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + print("Evalues") + print(*[ "{: >9.5f}".format(_s) for _s in v]) + print("Evecs") + for s in w: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + # print(scaled_cov) + # print(v) + # print(w.T) + raise e + + # NOTE: dz (the cholesky decomp) gives us vectors with euclidean + # dimensions, i.e. dz[2] is e[2], where e = [e0, e1, e2] are rotation + # vector embeddings of S^3 in R^3 + print("dz") + for s in dz: + print(*[ "{: >9.5f}".format(_s) for _s in s]) + + # x_hat y_hat z a b c d + lrQ = np.array([z[0], z[1], 0, z[2], 0 ,0, z[3]]) + print("lrQ", lrQ) + # Computing sigma points + for i in range(L): + # The first SS are gotten via composition + dlrQ_pos = np.array([dz[i][0], dz[i][1], 0]) + dlrQ_rv = np.array([0, 0, dz[i][2]]) + dlrQ = np.hstack([dlrQ_pos, rp2quat(dlrQ_rv)]) + #dlrQ = np.array([dz[i][0], dz[i][1], 0, np.cos(dz[i][2]), 0 ,0, dz[i][2]]) + lrQ1 = t.compose_lrQ(lrQ, dlrQ) + # x y a d + Z[1 + i][:SS] = np.array([lrQ1[0], lrQ1[1], lrQ1[3], lrQ1[6]]) + + dlrQ_pos = np.array([-dz[i][0], -dz[i][1], 0]) + dlrQ_rv = np.array([0, 0, -dz[i][2]]) + dlrQ = np.hstack([dlrQ_pos, rp2quat(dlrQ_rv)]) + #dlrQ = np.array([-dz[i][0], -dz[i][1], 0, np.sqrt(1-dz[i][2]**2), 0, 0, -dz[i][2]]) + lrQ2 = t.compose_lrQ(lrQ, dlrQ) + Z[1 + i + L][:SS] = np.array([lrQ2[0], lrQ2[1], lrQ2[3], lrQ2[6]]) + + # The last 2 (dl, dr) are gotten via addition + Z[1 + i][SS:] = z[SS:] + dz[i][SM:] + Z[1 + i + L][SS:] = z[SS:] - dz[i][SM:] + print("Z") + for row in Z: + print(",".join("{:12.8f}".format(v) for v in row)) #, np.sqrt(row[2]**2+row[3]**2)) + print() + + # Transform to new vectors + def T(_z): + # a b c d + quat = np.array([_z[2], 0 ,0, _z[3]]) + dx = dead_reckon_step( quat=quat, dl=z[SS+0], dr=z[SS+1]) #, vave=step[7], vdiff=step[8] ) + # Taking current quat and applying step quat rotation to it + next_quat = t.compose_quat(quat, step[3:7]) + # Only return offset, this is marginalizing out all the quat dependances + # return _z[:3] + dx + return np.hstack([_z[:2] + dx[:2], next_quat[0], next_quat[3]]) + + Y = np.array([ T(_z) for _z in Z ]) + print("Y") + for row in Y: + print(",".join("{:12.8f}".format(v) for v in row))#, np.sqrt(row[2]**2+row[3]**2)) + print() + + M = len(Y[0]) + LAMBDA = L_PLUS_LAMBDA - L + W0 = LAMBDA / L_PLUS_LAMBDA + W = 1 / ( 2 * L_PLUS_LAMBDA ) + + # Grab x and y in every sigma point + Y_pos = Y[:,:2] + + # Take a weighted average of the position components + y_pos_bar = (Y_pos[0]*W0 + np.sum(Y_pos[1:]*W,axis=0))[:2] + + ## Iteratively calculate the quaternion mean + Y_quat = np.array([[a,0,0,d] for a,d in zip(Y[:,2],Y[:,3])]) + #print("Y_quat", Y_quat) + q_bar = Y_quat[0] + q_bar_inv = t.invert_quat(Y_quat[0]) + EPS = 1e-12 + MAX = 100 + i = 0 + error = 1 + while ( i < MAX and error > EPS ): + i += 1 + e_rvecs = np.array([quat2rp(t.compose_quat(q_bar_inv, y)) for y in Y_quat]) + e = (e_rvecs[0]*W0 + np.sum(e_rvecs[1:]*W,axis=0)) + error = np.linalg.norm(e) + q_bar = t.compose_quat(q_bar, rp2quat(e)) + q_bar_inv = t.invert_quat(q_bar) + + print(i, error) + + dY = np.hstack([Y_pos-y_pos_bar, e_rvecs[:,2:]]) + + #dY = Y - y_bar + + # for row in dY: + # print(",".join("{:12.8f}".format(v) for v in row)) + # print() + print("dY") + for row in dY: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + cov = W0 * np.array([dY[0]]).T @ np.array([dY[0]]) # exterior product + for k in range(1,len(dY)): + cov = cov + W * np.array([dY[k]]).T @ np.array([dY[k]]) # exterior product + + print("cov") + for row in cov: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + x_tilde = T(z) # transform the mean + P_tilde = cov + + for zz in Z: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="green", alpha=0.5) + for zz in Y: + quat = np.array([zz[2], 0,0, -zz[3]]) + xyz = np.array([ t.apply_quat(quat, _xyz) for _xyz in [ + [0,0.05,0], + [-0.01,0,0], + [0.01,0,0], + [0,0.05,0] + ]]) + np.array([zz[0],zz[1],0]) + plt.fill(xyz[:,0],xyz[:,1],color="blue", alpha=0.5) + + if j > 10: + plt.show() + # plot_quaternions(Y_quat, 3) + + return x_tilde, P_tilde + +def dead_reckon(x_hat, P_hat, steps, j): + for i, step in enumerate(steps): + x_hat, P_hat = dead_reckon_apply(x_hat, P_hat, step, j) + return x_hat, P_hat + +## ====================== +## TEST +## ====================== + +D = 0.464 +dl = 0.08 +dr = 0.07 +to2 = ( dl - dr ) / ( 2 * D ) + +# x,y,a,d +x_hat = np.array([0,0,1,0]) +P_hat = np.diag([1e-1,1e-1,0.2]) +step = np.array([ + 43994.76, # ts + dl, dr, # dl, dr + np.cos(to2), 0, 0, -np.sin(to2), # Dq: a,b,c,d + #0.215, 0.143, # vave, vdiff +]) +steps = 1*[step] + + +xhs = [x_hat] +phs = [P_hat] + +for i in range(50): + print("==================================== "+str(i+1)) + x_hat, P_hat = dead_reckon(x_hat, P_hat, steps, i) + xhs.append(x_hat) + phs.append(P_hat) + + v,w = np.linalg.eigh(P_hat) + print("v") + print(",".join("{:12.8f}".format(v) for v in v)) + print() + print("W") + for row in w: + print(",".join("{:12.8f}".format(v) for v in row)) + print() + +print("x") +print(",".join("{:12.8f}".format(v) for v in x_hat)) +print() +print("P") +for row in P_hat: + print(",".join("{:12.8f}".format(v) for v in row)) +print() + + +fig = plt.figure() +ax = fig.add_subplot(111) + +for x,p in zip(xhs, phs): + L = np.linalg.cholesky(p)[:2,:2] + xy = np.array([L@np.array([np.sin(u), np.cos(u)]) + x[:2] for u in np.linspace(0,2*np.pi,100)]) + plt.plot(x[:1], x[1:2], "x") + plt.plot(xy[:,0], xy[:,1]) + + +plt.show() +